diff --git a/CMakeLists.txt b/CMakeLists.txt
index e708fcd03f4c8fc2492377e7e4d6500242246955..29c32bcf05f4494faa337e8239280d350dca9102 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -8,14 +8,18 @@ find_package("ArmarXCore" REQUIRED
 
 include(${ArmarXCore_USE_FILE})
 
+set(ARMARX_ENABLE_DEPENDENCY_VERSION_CHECK_DEFAULT TRUE)
+set(ARMARX_ENABLE_AUTO_CODE_FORMATTING TRUE)
+
 armarx_project("RobotAPI")
-set(ARMARX_ENABLE_DEPENDENCY_VERSION_CHECK_DEFAULT True)
 depends_on_armarx_package(ArmarXGui "OPTIONAL")
 
-set(ArmarX_Simox_VERSION 2.3.7)
+set(ArmarX_Simox_VERSION 2.3.9)
 
 add_subdirectory(source)
 
+list(APPEND CPACK_DEBIAN_PACKAGE_DEPENDS "simox")
+
 install_project()
 
 add_subdirectory(scenarios)
diff --git a/data/RobotAPI/robots/Armar3/ArmarIII-Head.xml b/data/RobotAPI/robots/Armar3/ArmarIII-Head.xml
new file mode 100644
index 0000000000000000000000000000000000000000..489ef1beed9fd60f746ff16b21be25ad783d20f5
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/ArmarIII-Head.xml
@@ -0,0 +1,473 @@
+<?xml version="1.0" encoding="UTF-8" ?>
+
+<Robot Type="ArmarIII Head" RootNode="Head Base">
+    
+    <RobotNode name="Head Base">
+        <Transform>
+            <DH theta="90" d="0" a="0" alpha="0" unitsangle="degree" unitslength="mm"/>
+        </Transform>
+                
+        <Visualization>
+            <File type="Inventor">fullmodel/head_base.iv</File>
+        </Visualization>
+        
+        <Physics>
+            <CoM location="VisualizationBBoxCenter"/>
+            <Mass value="4" units="kg" />
+        </Physics>
+        
+        <CollisionModel>
+            <File type="Inventor">convexModel/head_base.iv</File>
+        </CollisionModel>   
+
+        <Child name="Neck_1_Pitch"/>
+    </RobotNode>
+
+    <RobotNode name="Neck_1_Pitch">
+        <Transform>
+            <DH theta="0" d="0" a="0" alpha="90" unitsangle="degree" unitslength="mm"/>
+            <DH theta="90" d="0" a="0" alpha="0" unitsangle="degree" unitslength="mm"/>
+        </Transform>
+                
+
+        <Joint type="revolute">
+            <!--DH theta="90" d="0" a="0" alpha="90" unitsangle="degree" unitslength="mm"/-->
+            <axis x="0" y="0" z="-1"/>
+            <Limits unit="degree" lo="-45" hi="42"/>
+            <MaxVelocity unit="radian" value="1"/>
+            <MaxAcceleration value="10"/>
+            <MaxTorque value="3000"/>
+        </Joint>
+
+        <Visualization>
+            <File type="Inventor">fullmodel/neck_pitch_link.iv</File>           
+        </Visualization>
+        
+        <Physics>
+            <CoM location="VisualizationBBoxCenter"/>
+            <Mass value="4" units="kg" />
+            <IgnoreCollision name="Hip Yaw"/>
+        </Physics>
+        
+        <CollisionModel>
+            <File type="Inventor">convexModel/neck_pitch_link.iv</File>
+        </CollisionModel>
+        
+        <Child name="Neck_2_Roll"/>
+    </RobotNode>
+        
+    <RobotNode name="Neck_2_Roll">
+        <Transform>
+			<DH a="0" d="0" theta="0" alpha="90" unitsangle="degree" unitslength="mm"/>
+			<DH a="0" d="0" theta="90" alpha="0" unitsangle="degree" unitslength="mm"/>
+		</Transform>
+        <Joint type="revolute">
+            <!--DH theta="90" d="0" a="0" alpha="90" unitsangle="degree" unitslength="mm"/-->
+            <axis x="0" y="0" z="1"/>
+            <Limits unit="degree" lo="-45" hi="45"/>
+            <MaxVelocity unit="radian" value="1"/>
+            <MaxAcceleration value="10"/>
+            <MaxTorque value="3000"/>
+        </Joint>
+        
+        <Visualization>
+            <File type="Inventor">fullmodel/neck_roll_link.iv</File>
+        </Visualization>
+                
+        <Physics>
+            <CoM location="VisualizationBBoxCenter"/>
+            <Mass value="2" units="kg" />
+            <IgnoreCollision name="Hip Yaw"/>
+            <IgnoreCollision name="Head Base"/>
+        </Physics>
+        
+        <CollisionModel>
+            <File type="Inventor">convexModel/neck_roll_link.iv</File>
+        </CollisionModel>
+        
+        <Child name="Neck_3_Yaw"/>
+    </RobotNode>    
+    
+    <RobotNode name="Neck_3_Yaw">
+       <Transform>
+			<DH a="0" d="0" theta="0" alpha="90" unitsangle="degree" unitslength="mm"/>
+			<DH a="0" d="0" theta="90" alpha="0" unitsangle="degree" unitslength="mm"/>
+		</Transform>
+        <Joint type="revolute">
+            <!--DH theta="90" d="120" a="0"  alpha="90" unitsangle="degree" unitslength="mm"/-->
+            <axis x="0" y="0" z="-1"/>
+            <Limits unit="degree" lo="-120" hi="120"/>
+            <MaxVelocity unit="radian" value="1"/>
+            <MaxAcceleration value="10"/>
+            <MaxTorque value="3000"/>
+        </Joint>
+        
+        <Visualization>
+            <File type="Inventor">fullmodel/neck_yaw_link.iv</File>
+        </Visualization>
+                
+        <Physics>
+            <CoM location="VisualizationBBoxCenter"/>
+            <Mass value="2" units="kg" />
+        </Physics>
+        
+        <CollisionModel>
+            <File type="Inventor">convexModel/neck_yaw_link.iv</File>
+        </CollisionModel>
+
+        <Child name="Head_Tilt"/>
+    </RobotNode>
+
+    <RobotNode name="Head_Tilt">
+        <Transform>
+			<DH theta="0" d="120" a="0" alpha="90" unitsangle="degree" unitslength="mm"/>
+		</Transform>
+        <Joint type="revolute">
+            <!--DH theta="0" d="0" a="0"  alpha="-90" unitsangle="degree" unitslength="mm"/-->
+            <axis x="0" y="0" z="1"/>
+            <!--<Limits unit="degree" lo="-45" hi="45"/>/-->
+            <Limits unit="degree" lo="0" hi="0"/>
+            <MaxVelocity unit="radian" value="1"/>
+            <MaxAcceleration value="10"/>
+            <MaxTorque value="3000"/>
+        </Joint>
+        
+        <Physics>
+            <CoM location="VisualizationBBoxCenter"/>
+            <Mass value="6.79877000" units="kg" />
+            <IgnoreCollision name="Neck_2_Roll"/>
+            <IgnoreCollision name="Hip Yaw"/>
+        </Physics>
+        
+        <Visualization>
+            <File type="Inventor">fullmodel/head.iv</File>
+        </Visualization>
+        
+        <CollisionModel>
+            <File type="Inventor">convexModel/head.iv</File>
+        </CollisionModel>  
+         
+        <Child name="Head Center1"/>
+    </RobotNode>
+    
+    <RobotNode name="Head Center1">
+        <Transform>
+			<DH theta="0" d="0" a="0" alpha="-90" unitsangle="degree" unitslength="mm"/>
+		</Transform>
+        <Child name="Head Center"/>
+    </RobotNode>
+ 
+ 
+    <RobotNode name="Head Center">
+        <Transform>
+			<DH theta="0" d="54.5" a="0" alpha="-90" unitsangle="degree" unitslength="mm"/>
+		</Transform>
+        <Child name="Cameras"/>
+        <Child name="Jaw"/>
+        <Child name="Kinect"/>
+        <Child name="DepthCamera"/>
+    </RobotNode>
+
+    <RobotNode name="Jaw"> 
+        <Joint type="revolute"> 
+            <axis x="0" y="0" z="1"/>
+            <Limits unit="degree" lo="-30" hi="30"/>
+            <MaxVelocity unit="radian" value="1"/>
+            <MaxAcceleration value="10"/>
+            <MaxTorque value="3000"/>
+        </Joint>
+        <Visualization> 
+            <File type="Inventor">fullmodel/jaw.iv</File>
+        </Visualization>
+    </RobotNode>
+
+    <RobotNode name="Cameras">
+        <Transform>
+            <Translation x="100" y="0" z="0" units='mm'/>
+        </Transform>
+        <Joint type="revolute">
+            <Axis x="0" y="0" z="-1"/>
+            <Limits unit="degree" lo="-28" hi="5"/> <!-- Real high limit is 27. Deactivated to avoid unnatural poses-->
+            <MaxVelocity unit="radian" value="1"/>
+            <MaxAcceleration value="10"/>
+            <MaxTorque value="3000"/>
+        </Joint>
+
+        <CollisionModel>
+            <File type="Inventor">iv_primitives/cyl2.wrl</File>
+        </CollisionModel> 
+
+        <Physics>
+            <CoM location="VisualizationBBoxCenter"/>
+            <Mass value="0.2" units="kg" />
+            <IgnoreCollision name="Neck_2_Roll"/>
+            <IgnoreCollision name="Hip Yaw"/>            
+	    <IgnoreCollision name="Head_Tilt"/>
+        </Physics>
+
+        <Child name="Eye_Left_Dummy"/>
+        <Child name="Eye_Right_Dummy"/>
+        <Child name="VirtualCentralGaze"/>
+    </RobotNode>
+
+    <RobotNode name="VirtualCentralGaze">
+        <Joint type="prismatic">
+            <TranslationDirection x="1" y="0" z="0"/>
+            <Limits unit="mm" lo="0" hi="10000"/>
+            <MaxVelocity unit="radian" value="1"/>
+            <MaxAcceleration value="10"/>
+            <MaxTorque value="3000"/>
+        </Joint>
+        <Visualization enable="true">
+            <CoordinateAxis type="Inventor" enable="false" scaling="3"/>
+        </Visualization>
+    </RobotNode>
+
+    <RobotNode name="Kinect">
+        <Transform>
+            <Translation x="140" y="-100" z="0" units='mm'/>
+        </Transform>
+        <Joint type="prismatic">
+            <TranslationDirection x="1" y="0" z="0"/>
+            <Limits unit="mm" lo="0" hi="10000"/>
+            <MaxVelocity unit="radian" value="1"/>
+            <MaxAcceleration value="10"/>
+            <MaxTorque value="3000"/>
+        </Joint>
+        <Visualization enable="true">
+            <CoordinateAxis type="Inventor" enable="false" scaling="3"/>
+        </Visualization>
+    </RobotNode>
+
+    <RobotNode name="DepthCamera">
+        <Transform>
+            <Translation x="105" y="70" z="0" units='mm'/>
+            <rollpitchyaw roll="0" pitch="90" yaw="0" unitsAngle="degree"/>
+            <rollpitchyaw roll="0" pitch="0" yaw="180" unitsAngle="degree"/>
+            <rollpitchyaw roll="20.7" pitch="0" yaw="0" unitsAngle="degree"/>
+            <rollpitchyaw roll="0" pitch="0" yaw="180" unitsAngle="degree"/>
+        </Transform>
+        
+        <Visualization enable="true">
+            <CoordinateAxis type="Inventor" enable="false" scaling="3"/>
+        </Visualization>
+    </RobotNode>
+    
+    <RobotNode name="Eye_Left_Dummy">
+        <Transform>
+          <DH a="0" d="46.5" theta="0" alpha="-90" unitsangle="degree" unitslength="mm"/>
+        </Transform>
+        <Child name="Eye_Left"/>
+    </RobotNode>
+
+    <RobotNode name="Eye_Right_Dummy">
+        <Transform>
+          <DH a="0" d="-46.5" theta="0" alpha="-90" unitsangle="degree" unitslength="mm"/>
+        </Transform>
+        <Child name="Eye_Right"/>
+      </RobotNode>
+
+    <RobotNode name="Eye_Left">
+        <Joint type="revolute">
+          <Axis x="0" y="0" z="1"/>
+          <Limits unit="degree" lo="-30" hi="30"/>
+            <MaxVelocity unit="radian" value="1"/>
+            <MaxAcceleration value="10"/>
+            <MaxTorque value="3000"/>
+        </Joint>
+        <Visualization>
+          <File type="Inventor">fullmodel/eye_l.iv</File>
+        </Visualization>
+
+
+        <CollisionModel>
+            <File type="Inventor">iv_primitives/cyl1.wrl</File>
+        </CollisionModel> 
+
+        <Physics>
+            <CoM location="VisualizationBBoxCenter"/>
+            <Mass value="0.1" units="kg" />
+            <IgnoreCollision name="Cameras"/>            
+	    <IgnoreCollision name="Head_Tilt"/>
+        </Physics>
+
+        <Child name="Lid Left Bottom"/>
+        <Child name="Lid Left Top"/>
+        <Child name="EyeLeftCameraPreTransformation"/>
+    </RobotNode>
+
+    <RobotNode name="Eye_Right">
+        <Joint type="revolute">
+          <Axis x="0" y="0" z="1"/>
+          <Limits unit="degree" lo="-30" hi="30"/>
+            <MaxVelocity unit="radian" value="1"/>
+            <MaxAcceleration value="10"/>
+            <MaxTorque value="3000"/>
+        </Joint>
+        <Visualization>
+          <File type="Inventor">fullmodel/eye_r.iv</File>
+        </Visualization>
+
+        <CollisionModel>
+            <File type="Inventor">iv_primitives/cyl1.wrl</File>
+        </CollisionModel> 
+
+        <Physics>
+            <CoM location="VisualizationBBoxCenter"/>
+            <Mass value="0.1" units="kg" />
+            <IgnoreCollision name="Cameras"/>            
+	    <IgnoreCollision name="Head_Tilt"/>
+        </Physics>
+
+        <Child name="Lid Right Bottom"/>
+        <Child name="Lid Right Top"/>
+        <Child name="EyeRightCameraPreTransformation"/>
+    </RobotNode>
+
+    <RobotNode name="EyeLeftCameraPreTransformation">
+        <Transform>
+            <translation x="20" y="0" z="0"/>
+            <RollPitchYaw roll="0" pitch="90" yaw ="0" units="degree"/>
+        </Transform>
+        <Child name="EyeLeftCamera"/>
+        <Child name="EyeLeftCameraSim"/>
+    </RobotNode>
+
+    <RobotNode name="EyeLeftCamera">
+        <Transform>
+            <RollPitchYaw roll="0" pitch="0" yaw ="90" units="degree"/>
+        </Transform>
+	<Visualization enable="true">
+                <CoordinateAxis type="Inventor" enable="false" scaling="5"/>
+	</Visualization>
+        <Child name="HeadMotionMeasurementTCP"/>
+        <!--Sensor type="Camera" name="LeftEyeCam">
+        </Sensor-->
+    </RobotNode>
+
+    <RobotNode name="EyeLeftCameraSim">
+        <Transform>
+            <RollPitchYaw roll="0" pitch="0" yaw ="180" units="degree"/>
+        </Transform>
+    </RobotNode>
+    
+    <RobotNode name="HeadMotionMeasurementTCP">
+        <Transform>
+            <translation x="0" y="0" z="1000"/>
+        </Transform>
+    </RobotNode>
+
+  <RobotNode name="Lid Left Bottom">
+    <Joint type="revolute">
+      <Axis x="0" y="1" z="0"/>
+        <MaxVelocity unit="radian" value="1"/>
+        <MaxAcceleration value="10"/>
+        <MaxTorque value="3000"/>
+    </Joint>
+    <Visualization>
+      <File type="Inventor">fullmodel/lid_l_bottom.iv</File>
+    </Visualization>
+  </RobotNode>
+  
+  <RobotNode name="Lid Left Top">
+    <Joint type="revolute">
+      <Axis x="0" y="1" z="0"/>
+    </Joint>
+    <Visualization>
+      <File type="Inventor">fullmodel/lid_l_top.iv</File>
+    </Visualization>
+  </RobotNode>
+
+    <RobotNode name="EyeRightCameraPreTransformation">
+        <Transform>
+            <translation x="20" y="0" z="0"/>
+            <RollPitchYaw roll="0" pitch="90" yaw ="0" units="degree"/>
+        </Transform>
+        <Child name="EyeRightCamera"/>
+        <Child name="EyeRightCameraSim"/>
+    </RobotNode>
+
+    <RobotNode name="EyeRightCamera">
+        <Transform>
+            <RollPitchYaw roll="0" pitch="0" yaw ="90" units="degree"/>
+        </Transform>
+        <!--Sensor type="Camera" name="RightEyeCam">
+        </Sensor-->
+    </RobotNode>
+
+    <RobotNode name="EyeRightCameraSim">
+        <Transform>
+            <RollPitchYaw roll="0" pitch="0" yaw ="180" units="degree"/>
+        </Transform>
+    </RobotNode>
+
+  <RobotNode name="Lid Right Bottom">
+    <Joint type="revolute">
+      <Axis x="0" y="1" z="0"/>
+        <MaxVelocity unit="radian" value="1"/>
+        <MaxAcceleration value="10"/>
+        <MaxTorque value="3000"/>
+    </Joint>
+    <Visualization>
+      <File type="Inventor">fullmodel/lid_r_bottom.iv</File>
+    </Visualization>
+  </RobotNode>
+
+  <RobotNode name="Lid Right Top">
+  <Joint type="revolute">
+    <Axis x="0" y="1" z="0"/>
+      <MaxVelocity unit="radian" value="1"/>
+      <MaxAcceleration value="10"/>
+      <MaxTorque value="3000"/>
+  </Joint>
+    <Visualization>
+      <File type="Inventor">fullmodel/lid_r_top.iv</File>
+    </Visualization>
+  </RobotNode>
+  
+    <RobotNodeSet name="Head" kinematicRoot="Neck_1_Pitch">
+        <Node name="Neck_1_Pitch"/>
+        <Node name="Neck_2_Roll"/>
+        <Node name="Neck_3_Yaw"/>
+        <Node name="Head_Tilt"/>
+        <Node name="Cameras"/>
+        <Node name="Eye_Left"/>
+        <Node name="Eye_Right"/>
+    </RobotNodeSet>
+
+
+    <RobotNodeSet name="Neck" kinematicRoot="Neck_1_Pitch">
+        <Node name="Neck_1_Pitch"/>
+        <Node name="Neck_2_Roll"/>
+        <Node name="Neck_3_Yaw"/>
+        <Node name="Head_Tilt"/>
+    </RobotNodeSet>
+
+
+    <RobotNodeSet name="IKVirtualGaze" kinematicRoot="Neck_1_Pitch" tcp="VirtualCentralGaze">
+        <Node name="Neck_1_Pitch"/>
+        <Node name="Neck_2_Roll"/>
+        <Node name="Neck_3_Yaw"/>
+        <Node name="Cameras"/>
+        <Node name="VirtualCentralGaze"/>
+    </RobotNodeSet>
+
+
+    <RobotNodeSet name="IKVirtualGazeKinect" kinematicRoot="Neck_1_Pitch" tcp="Kinect">
+        <Node name="Neck_1_Pitch"/>
+        <Node name="Neck_2_Roll"/>
+        <Node name="Neck_3_Yaw"/>
+        <Node name="Kinect"/>
+    </RobotNodeSet>
+
+
+    <RobotNodeSet name="IKVirtualGaze_WithHeadTilt" kinematicRoot="Neck_1_Pitch" tcp="VirtualCentralGaze">
+        <Node name="Neck_1_Pitch"/>
+        <Node name="Neck_2_Roll"/>
+        <Node name="Neck_3_Yaw"/>
+        <Node name="Head_Tilt"/>
+        <Node name="Cameras"/>
+        <Node name="VirtualCentralGaze"/>
+    </RobotNodeSet>
+
+</Robot>
diff --git a/data/RobotAPI/robots/Armar3/ArmarIII-Head_minColModel.xml b/data/RobotAPI/robots/Armar3/ArmarIII-Head_minColModel.xml
new file mode 100644
index 0000000000000000000000000000000000000000..bf9e3e887b9503dc97ea4768158d2cc2a1f3c45e
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/ArmarIII-Head_minColModel.xml
@@ -0,0 +1,221 @@
+<?xml version="1.0" encoding="UTF-8" ?>
+
+<Robot Type="ArmarIII Head" RootNode="Head Base">
+    
+    <RobotNode name="Head Base">
+        <Joint type="fixed">
+            <DH theta="90" d="0" a="0" alpha="90" units="degree"/>
+        </Joint>
+        <Child name="Neck_1_Pitch"/>
+        <Visualization>
+            <File type="Inventor">fullmodel/head_base.iv</File>
+        </Visualization>
+    </RobotNode>
+
+    <RobotNode name="Neck_1_Pitch">
+        <Joint type="revolute">
+            <DH theta="90" d="0" a="0" alpha="90" units="degree"/>
+            <Limits unit="degree" lo="-45" hi="45"/>
+        </Joint>
+
+        <Visualization>
+            <File type="Inventor">fullmodel/neck_pitch_link.iv</File>           
+        </Visualization>
+        <Child name="Neck_2_Roll"/>
+    </RobotNode>
+        
+    <RobotNode name="Neck_2_Roll">
+        <Joint type="revolute">
+            <DH theta="90" d="0" a="0" alpha="90" units="degree"/>
+            <Limits unit="degree" lo="-45" hi="45"/>
+        </Joint>
+        <Visualization>
+            <File type="Inventor">fullmodel/neck_roll_link.iv</File>
+        </Visualization>
+        <Child name="Neck_3_Yaw"/>
+    </RobotNode>    
+    
+    <RobotNode name="Neck_3_Yaw">
+        <Joint type="revolute">
+            <DH theta="90" d="120" a="0"  alpha="90" units="degree"/>
+            <Limits unit="degree" lo="-45" hi="45"/>
+        </Joint>
+        <Visualization>
+            <File type="Inventor">fullmodel/neck_yaw_link.iv</File>
+        </Visualization>
+        <Child name="Head_Tilt"/>
+    </RobotNode>
+
+    <RobotNode name="Head_Tilt">
+        <Joint type="revolute">
+            <DH theta="0" d="0" a="0"  alpha="-90" units="degree"/>
+            <Limits unit="degree" lo="-45" hi="45"/>
+        </Joint>
+        <Physics>
+            <CoM location="VisualizationBBoxCenter"/>
+            <Mass value="6.79877000" units="kg" />
+        </Physics>
+        <Visualization>
+            <File type="Inventor">fullmodel/head.iv</File>
+        </Visualization>
+        <CollisionModel>
+            <File type="Inventor">collisionModel/head.iv</File>
+        </CollisionModel>   
+        <Child name="Head Center"/>
+    </RobotNode>
+    
+    <RobotNode name="Head Center">
+        <Joint type="fixed">
+          <DH theta="0" d="54.5" a="0" alpha="-90" units="degree"/>
+        </Joint>
+        <Child name="Cameras"/>
+        <Child name="Jaw"/>
+    </RobotNode>
+
+    <RobotNode name="Jaw"> 
+        <Joint type="revolute"> 
+            <DH theta="0" d="0" a="0" alpha="0" units="degree"/>
+            <Limits unit="degree" lo="-30" hi="30"/>
+        </Joint>
+        <Visualization> 
+            <File type="Inventor">fullmodel/jaw.iv</File>
+        </Visualization>
+    </RobotNode>
+
+    <RobotNode name="Cameras">
+        <!-- TODO: this was an AlphaJoint: but rotations around alpha axis are not supported by DH!! -->
+        <Joint type="revolute">
+            <PreJointTransform>
+                <Transform>
+                    <Translation x="100" y="0" z="0"/>
+                </Transform>
+            </PreJointTransform>       
+            <Axis x="0" y="0" z="1"/>
+            <PostJointTransform>
+                <Transform>
+                    <Translation x="0" y="0" z="0"/>
+                </Transform>
+            </PostJointTransform>
+            <Limits unit="degree" lo="-30" hi="45"/>
+        </Joint>
+        <Child name="Eye_Left_Dummy"/>
+        <Child name="Eye_Right_Dummy"/>
+    </RobotNode>
+
+    <RobotNode name="Eye_Left_Dummy">
+        <Joint type="fixed">
+            <DH a="0" d="46.5" theta="0" alpha="-90" units="degree"/>
+        </Joint>
+        <Child name="Eye_Left"/>
+    </RobotNode>
+
+    <RobotNode name="Eye_Right_Dummy">
+        <Joint type="fixed">
+          <DH a="0" d="-46.5" theta="0" alpha="-90" units="degree"/>
+        </Joint>
+        <Child name="Eye_Right"/>
+      </RobotNode>
+
+    <RobotNode name="Eye_Left">
+        <Joint type="revolute">
+          <DH theta="0" d="0" a="0" alpha="0" units="degree"/>
+          <Limits unit="degree" lo="-30" hi="30"/>
+        </Joint>
+        <Visualization>
+          <File type="Inventor">fullmodel/eye_l.iv</File>
+        </Visualization>
+        <Child name="Lid Left Bottom"/>
+        <Child name="Lid Left Top"/>
+        <Child name="EyeLeftCamera"/>
+    </RobotNode>
+
+    <RobotNode name="Eye_Right">
+        <Joint type="revolute">
+          <DH theta="0" d="0" a="0" alpha="0" units="degree"/>
+          <Limits unit="degree" lo="-30" hi="30"/>
+        </Joint>
+        <Visualization>
+          <File type="Inventor">fullmodel/eye_r.iv</File>
+        </Visualization>
+        <Child name="Lid Right Bottom"/>
+        <Child name="Lid Right Top"/>
+        <Child name="EyeRightCamera"/>
+    </RobotNode>
+
+    <RobotNode name="EyeLeftCamera">
+        <Joint type="fixed">
+            <PreJointTransform>
+                <Transform>
+                    <translation x="20" y="0" z="0"/>
+                    <RollPitchYaw roll="0" pitch="90" yaw ="0" units="degree"/>
+                </Transform>
+            </PreJointTransform>
+        </Joint>
+    </RobotNode>
+
+  <RobotNode name="Lid Left Bottom">
+    <Joint type="revolute">
+      <Axis x="0" y="1" z="0"/>
+    </Joint>
+    <Visualization>
+      <File type="Inventor">fullmodel/lid_l_bottom.iv</File>
+    </Visualization>
+  </RobotNode>
+  
+  <RobotNode name="Lid Left Top">
+    <Joint type="revolute">
+      <Axis x="0" y="1" z="0"/>
+    </Joint>
+    <Visualization>
+      <File type="Inventor">fullmodel/lid_l_top.iv</File>
+    </Visualization>
+  </RobotNode>
+
+    <RobotNode name="EyeRightCamera">
+        <Joint type="fixed">
+            <PreJointTransform>
+                <Transform>
+                    <translation x="20" y="0" z="0"/>
+                    <RollPitchYaw roll="0" pitch="90" yaw ="0" units="degree"/>
+                </Transform>
+            </PreJointTransform>
+        </Joint>
+    </RobotNode>
+
+  <RobotNode name="Lid Right Bottom">
+    <Joint type="revolute">
+      <Axis x="0" y="1" z="0"/>
+    </Joint>
+    <Visualization>
+      <File type="Inventor">fullmodel/lid_r_bottom.iv</File>
+    </Visualization>
+  </RobotNode>
+
+  <RobotNode name="Lid Right Top">
+  <Joint type="revolute">
+    <Axis x="0" y="1" z="0"/>
+  </Joint>
+    <Visualization>
+      <File type="Inventor">fullmodel/lid_r_top.iv</File>
+    </Visualization>
+  </RobotNode>
+  
+    <RobotNodeSet name="Head" kinematicRoot="Neck_1_Pitch">
+        <Node name="Neck_1_Pitch"/>
+        <Node name="Neck_2_Roll"/>
+        <Node name="Neck_3_Yaw"/>
+        <Node name="Head_Tilt"/>
+        <Node name="Cameras"/>
+        <Node name="Eye_Left"/>
+        <Node name="Eye_Right"/>
+    </RobotNodeSet>
+
+
+    <RobotNodeSet name="Neck" kinematicRoot="Neck_1_Pitch">
+        <Node name="Neck_1_Pitch"/>
+        <Node name="Neck_2_Roll"/>
+        <Node name="Neck_3_Yaw"/>
+        <Node name="Head_Tilt"/>
+    </RobotNodeSet>
+
+</Robot>
diff --git a/data/RobotAPI/robots/Armar3/ArmarIII-LeftArm.xml b/data/RobotAPI/robots/Armar3/ArmarIII-LeftArm.xml
new file mode 100644
index 0000000000000000000000000000000000000000..4e462ca1eb3ed06f68f9828e9272de46950e7baf
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/ArmarIII-LeftArm.xml
@@ -0,0 +1,274 @@
+<?xml version="1.0" encoding="UTF-8" ?>
+
+<Robot Type="ArmarIII LeftArm" RootNode="Left Arm Base">
+
+  <RobotNode name="Left Arm Base">
+    <!-- Trafo BTo0; COS 0; DOF q1 -->
+    <Transform>
+      <DH a="0" d="0" theta="-90" alpha="90" units="degree"/>
+    </Transform>
+    <Child name="Shoulder 1 L"/>
+  </RobotNode>
+
+  <RobotNode name="Shoulder 1 L">
+    <!-- Trafo BTo0; COS 0; DOF q1 -->
+    <Transform>
+      <DH a="0" d="0" theta="90" alpha="0" units="degree"/>
+    </Transform>
+    <Joint type="revolute">
+      <!--DH a="0" d="0" theta="90" alpha="90" units="degree"/-->
+      <axis x="0" y="0" z="1"/>
+      <Limits unit="degree" lo="-107" hi="42"/>
+		<MaxVelocity unit="radian" value="1"/>
+		<MaxAcceleration value="10"/>
+                <MaxTorque value="3000"/>
+    </Joint>
+    <Physics>
+      <CoM location="VisualizationBBoxCenter"/>
+      <Mass value="3.65" units="kg" />
+    </Physics>
+    <Visualization enable="true">
+      <File type="Inventor">fullmodel/shoulder_l.iv</File>
+    </Visualization>
+    <CollisionModel>
+      <File type="Inventor">convexModel/shoulder_l.iv</File>
+    </CollisionModel>
+    <Child name="Shoulder 2 L"/>
+  </RobotNode>
+
+  <RobotNode name="Shoulder 2 L">
+    <!-- Trafo 0To1; COS 1; DOF q2 -->
+    <Transform>
+      <DH a="0" d="0" theta="0" alpha="90" units="degree"/>
+      <DH a="0" d="0" theta="75" alpha="0" units="degree"/>
+    </Transform>
+    <Joint type="revolute">
+      <!--DH a="0" d="0" theta="75" alpha="90" units="degree"/-->
+      <axis x="0" y="0" z="-1"/>
+      <Limits unit="degree" lo="-14" hi="95"/>
+		<MaxVelocity unit="radian"  value="1"/>
+		<MaxAcceleration value="10"/>
+                <MaxTorque value="3000"/>
+    </Joint>
+    <Physics>
+      <CoM location="VisualizationBBoxCenter"/>
+      <Mass value="2.5" units="kg" />
+    </Physics>
+    <Visualization enable="true">
+      <File type="Inventor">fullmodel/shoulder2_l_rot.iv</File>
+    </Visualization>
+    <CollisionModel>
+      <File type="Inventor">convexModel/shoulder2_l_rot.iv</File>
+    </CollisionModel>
+    <Child name="Upperarm L"/>
+  </RobotNode>
+
+  <RobotNode name="Upperarm L">
+    <!-- Trafo 1To2; COS 2; DOF q3 -->
+    <Transform>
+      <DH a="0" d="0" theta="0" alpha="90" units="degree"/>
+      <DH a="0" d="0" theta="-90" alpha="0" units="degree"/>
+    </Transform>
+    <Joint type="revolute">
+      <!--DH a="20" d="-310" theta="-90" alpha="90" units="degree"/-->
+      <axis x="0" y="0" z="-1"/>
+      <Limits unit="degree" lo="-70" hi="109"/>
+		<MaxVelocity unit="radian" value="1"/>
+		<MaxAcceleration value="10"/>
+                <MaxTorque value="3000"/>
+    </Joint>
+    <Physics>
+      <CoM location="VisualizationBBoxCenter"/>
+      <Mass value="1.55685000" units="kg" />
+      <IgnoreCollision name="Shoulder 1 L"/>
+    </Physics>
+    <Visualization enable="true">
+      <File type="Inventor">fullmodel/upperarm_l.iv</File>
+    </Visualization>
+    <CollisionModel>
+      <File type="Inventor">convexModel/upperarm_l.iv</File>
+    </CollisionModel>
+    <Child name="Elbow L"/>
+  </RobotNode>
+
+  <RobotNode name="Elbow L">
+    <Transform>
+      <DH a="20" d="-310" theta="0" alpha="90" units="degree"/>
+      <DH a="0" d="0" theta="90" alpha="0" units="degree"/>
+    </Transform>
+    <Joint type="revolute">
+      <!--DH a="0" d="-7.5" theta="90" alpha="-90" units="degree"/-->
+      <axis x="0" y="0" z="1"/>
+      <Limits unit="degree" lo="-120" hi="40"/>
+		<MaxVelocity unit="radian" value="1"/>
+		<MaxAcceleration value="10"/>
+                <MaxTorque value="3000"/>
+    </Joint>
+    <Visualization enable="true">
+      <CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+      <File type="Inventor">fullmodel/elbow_l.iv</File>
+    </Visualization>
+    <CollisionModel>
+      <File type="Inventor">convexModel/elbow_l.iv</File>
+    </CollisionModel>
+    <Physics>
+      <CoM location="Joint"/>
+      <Mass value="1.15744000" units="kg" />
+    </Physics>
+    <Child name="Underarm L"/>
+  </RobotNode>
+
+  <RobotNode name="Underarm L">
+    <Transform>
+      <DH a="0" d="-7.5" theta="0" alpha="-90" units="degree"/>
+      <DH a="0" d="0" theta="90" alpha="0" units="degree"/>
+    </Transform>
+    <Joint type="revolute">
+      <!--DH a="0" d="-240" theta="90" alpha="-90" units="degree"/-->
+      <axis x="0" y="0" z="-1"/>
+      <!--Limits unit="degree" lo="-57.29" hi="174.48"/-->
+      <Limits unit="degree" lo="-90" hi="200"/>
+		<MaxVelocity unit="radian" value="1"/>
+		<MaxAcceleration value="10"/>
+                <MaxTorque value="3000"/>
+    </Joint>
+    <Visualization enable="true">
+      <File type="Inventor">fullmodel/underarm_l.iv</File>
+    </Visualization>
+    <CollisionModel>
+      <File type="Inventor">convexModel/underarm_l.iv</File>
+    </CollisionModel>
+    <Physics>
+      <CoM location="VisualizationBBoxCenter"/>
+      <Mass value="2.26566087" units="kg" />
+    </Physics>
+    <Child name="Wrist 1 L"/>
+  </RobotNode>
+
+  <RobotNode name="Wrist 1 L">
+    <Transform>
+      <DH a="0" d="-240" theta="0" alpha="-90" units="degree"/>
+      <DH a="0" d="0" theta="-90" alpha="0" units="degree"/>
+    </Transform>
+    <Joint type="revolute">
+      <!--DH a="0" d="0" theta="-90" alpha="-90" units="degree"/-->
+      <axis x="0" y="0" z="-1"/>
+      <Limits unit="degree" lo="-30" hi="30"/>
+		<MaxVelocity unit="radian" value="1"/>
+		<MaxAcceleration value="10"/>
+                <MaxTorque value="3000"/>
+    </Joint>
+    <Physics>
+      <CoM location="VisualizationBBoxCenter"/>
+      <Mass value="1.29945309" units="kg" />
+    </Physics>
+    <Visualization enable="true">
+      <CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+      <File type="Inventor">fullmodel/wrist1_l.iv</File>
+    </Visualization>
+    <CollisionModel>
+      <File type="Inventor">convexModel/wrist1_l.iv</File>
+    </CollisionModel>
+    <Child name="Wrist 2 L"/>
+  </RobotNode>
+
+  <RobotNode name="Wrist 2 L">
+    <Transform>
+      <DH a="0" d="0" theta="0" alpha="-90" units="degree"/>
+      <DH a="0" d="0" theta="-90" alpha="0" units="degree"/>
+    </Transform>
+    <Joint type="revolute">
+      <!--DH a="0" d="0" theta="-90" alpha="90" units="degree"/-->
+      <axis x="0" y="0" z="1"/>
+      <Limits unit="degree" lo="-38" hi="44"/>
+		<MaxVelocity unit="radian" value="1"/>
+		<MaxAcceleration value="10"/>
+                <MaxTorque value="3000"/>
+    </Joint>
+
+    <Visualization enable="true">
+      <CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+      <File type="Inventor">fullmodel/wrist2_l.iv</File>
+    </Visualization>
+    <!-- bullet doesn't like two models connected with a fixed joint -> disable this collisison model and just use the hand palm model-->
+    <!--CollisionModel>
+      <File type="Inventor">convexModel/wrist2_l.iv</File>
+    </CollisionModel>
+
+    <Physics>
+      <CoM location="VisualizationBBoxCenter"/>
+      <Mass value="2.59945309" units="kg" />
+      <IgnoreCollision name="Underarm L"/>
+    </Physics-->
+    <Sensor type="forcetorque" name="FT L">
+		<!--Transform>
+            <Translation x="0" y="-40" z="0"/>
+        </Transform-->
+    </Sensor>
+    <Child name="EndArmL"/>
+  </RobotNode>
+	
+    <!--RobotNode name="FTSensorL">
+        <Transform>
+            <Translation x="0" y="-40" z="0"/>
+        </Transform>
+        <Sensor type="forcetorque"/>
+        <Child name="EndArmL"/>
+    </RobotNode-->
+
+  <RobotNode name="EndArmL">
+    <Transform>
+	  <Translation x="0" y="-40" z="0"/>
+      <DH a="0" d="0" theta="0" alpha="90" units="degree"/>
+    </Transform>
+    <Visualization enable="false">
+        <CoordinateAxis type="Inventor" enable="true" scaling="2"/>
+    </Visualization>
+    <ChildFromRobot>
+      <File importEEF="true">ArmarIII-LeftHand.xml</File>
+    </ChildFromRobot>
+  </RobotNode>
+
+
+  <RobotNodeSet name="LeftArm" kinematicRoot="Left Arm Base" tcp="TCP L">
+    <Node name="Shoulder 1 L"/>
+    <Node name="Shoulder 2 L"/>
+    <Node name="Upperarm L"/>
+    <Node name="Elbow L"/>
+    <Node name="Underarm L"/>
+    <Node name="Wrist 1 L"/>
+    <Node name="Wrist 2 L"/>
+  </RobotNodeSet>
+
+  <RobotNodeSet name="LeftArmElbow" kinematicRoot="Left Arm Base" tcp="Upperarm L">
+    <Node name="Shoulder 1 L"/>
+    <Node name="Shoulder 2 L"/>
+    <Node name="Upperarm L"/>
+  </RobotNodeSet>
+
+  <RobotNodeSet name="LeftArmColModel" kinematicRoot="Left Arm Base" tcp="TCP L">
+		<Node name="Upperarm L"/>
+		<Node name="Underarm L"/>
+		<Node name="Wrist 2 L"/>
+	</RobotNodeSet>
+	
+	<RobotNodeSet name="LeftArmHandColModel" kinematicRoot="Left Arm Base" tcp="TCP L">
+		<Node name="Upperarm L"/>
+		<Node name="Underarm L"/>
+		<Node name="Hand Palm 1 L"/>
+		<Node name="Hand Palm 2 L"/>
+		<Node name="Thumb L J0"/>
+		<Node name="Thumb L J1"/>
+		<Node name="Index L J0"/>
+		<Node name="Index L J1"/>
+		<Node name="Middle L J0"/>
+		<Node name="Middle L J1"/>
+		<Node name="Ring L J0"/>
+		<Node name="Ring L J1"/>
+		<Node name="Pinky L J0"/>
+		<Node name="Pinky L J1"/>
+	</RobotNodeSet>
+
+
+	
+</Robot>
diff --git a/data/RobotAPI/robots/Armar3/ArmarIII-LeftArm_minColModel.xml b/data/RobotAPI/robots/Armar3/ArmarIII-LeftArm_minColModel.xml
new file mode 100644
index 0000000000000000000000000000000000000000..586d73babaaccdbeb8dea53c7bdb26a5ffeca629
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/ArmarIII-LeftArm_minColModel.xml
@@ -0,0 +1,186 @@
+<?xml version="1.0" encoding="UTF-8" ?>
+
+<Robot Type="ArmarIII LeftArm" RootNode="Left Arm Base">
+
+	<RobotNode name="Left Arm Base"> <!-- Trafo BTo0; COS 0; DOF q1 -->
+		<Joint type="fixed">
+			<DH a="0" d="0" theta="-90" alpha="90" units="degree"/>
+		</Joint>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+		</Visualization>
+		<Child name="Shoulder 1 L"/>
+	</RobotNode>
+	
+	<RobotNode name="Shoulder 1 L"> <!-- Trafo BTo0; COS 0; DOF q1 -->
+		<Joint type="revolute">
+			<DH a="0" d="0" theta="90" alpha="90" units="degree"/>
+			<Limits unit="degree" lo="-106.91" hi="42.8"/>
+		</Joint>
+		<Physics>
+            <CoM location="VisualizationBBoxCenter"/>
+            <Mass value="3.65" units="kg" />
+        </Physics>
+        <Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/shoulder_l.iv</File>
+		</Visualization>
+		<CollisionModel>
+			<File type="Inventor">collisionModel/shoulder_l.iv</File>
+		</CollisionModel>
+		<Child name="Shoulder 2 L"/>
+	</RobotNode>
+	
+	<RobotNode name="Shoulder 2 L"> <!-- Trafo 0To1; COS 1; DOF q2 -->
+		<Joint type="revolute">
+			<DH a="0" d="0" theta="75" alpha="90" units="degree"/>
+			<Limits unit="degree" lo="-94.62" hi="13.85"/>  <!-- ?! -->
+		</Joint>
+		<!--Physics>
+            <CoM location="Joint"/>
+            <Mass value="2.54491000" units="kg" />
+        </Physics-->
+        <Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/shoulder2_l_rot.iv</File>
+		</Visualization>
+		<Child name="Upperarm L"/>
+	</RobotNode>
+	
+	<RobotNode name="Upperarm L"> <!-- Trafo 1To2; COS 2; DOF q3 -->
+		<Joint type="revolute">
+			<DH a="20" d="-310" theta="-90" alpha="90" units="degree"/>
+			<Limits unit="degree" lo="-69.65" hi="108.25"/>
+		</Joint>
+		<Physics>
+            <CoM location="VisualizationBBoxCenter"/>
+            <Mass value="1.55685000" units="kg" />
+        </Physics>
+        <Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/upperarm_l.iv</File>
+		</Visualization>
+		<CollisionModel>
+			<File type="Inventor">collisionModel/upperarm_l.iv</File>
+		</CollisionModel>
+		<Child name="Elbow L"/>
+	</RobotNode>
+	
+	<RobotNode name="Elbow L">
+		<Joint type="revolute">
+			<DH a="0" d="-7.5" theta="90" alpha="-90" units="degree"/>
+			<Limits unit="degree" lo="-122.96" hi="19.14"/>
+		</Joint>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/elbow_l.iv</File>
+		</Visualization>
+		<!--Physics>
+            <CoM location="Joint"/>
+            <Mass value="1.15744000" units="kg" />
+        </Physics-->
+		<!-- TODO elbow_l.iv does not exist (currently not needed)-->
+		<!--<CollisionModel>-->
+			<!--<File type="Inventor">collisionModel/elbow_l.iv</File>-->
+		<!--</CollisionModel>-->
+		<Child name="Underarm L"/>
+	</RobotNode>
+	
+	<RobotNode name="Underarm L">
+		<Joint type="revolute">
+			<DH a="0" d="-240" theta="90" alpha="-90" units="degree"/>
+			<!--Limits unit="degree" lo="-57.29" hi="174.48"/-->
+			<Limits unit="degree" lo="-108.25" hi="69.65"/>
+		</Joint>
+		<Physics>
+            <CoM location="VisualizationBBoxCenter"/>
+            <Mass value="2.26566087" units="kg" />
+        </Physics>
+        <Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/underarm_l.iv</File>
+		</Visualization>
+		<CollisionModel>
+			<File type="Inventor">collisionModel/underarm_l.iv</File>
+		</CollisionModel>
+		<Child name="Wrist 1 L"/>
+	</RobotNode>
+	
+	<RobotNode name="Wrist 1 L">
+		<Joint type="revolute">
+			<DH a="0" d="0" theta="-90" alpha="-90" units="degree"/>
+			<Limits unit="degree" lo="-29.36" hi="24.11"/>
+		</Joint>
+		<!--Physics>
+            <CoM location="VisualizationBBoxCenter"/>
+            <Mass value="1.29945309" units="kg" />
+        </Physics-->
+        <Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/wrist1_l.iv</File>
+		</Visualization>
+		<!--CollisionModel>
+			<File type="Inventor">collisionModel/wrist1_l.iv</File>
+		</CollisionModel-->
+		<Child name="Wrist 2 L"/>
+	</RobotNode>
+	
+	<RobotNode name="Wrist 2 L">
+		<Joint type="revolute">
+			<DH a="0" d="0" theta="-90" alpha="90" units="degree"/>
+			<Limits unit="degree" lo="-38.4" hi="44.32"/>
+		</Joint>
+		<Physics>
+            <CoM location="VisualizationBBoxCenter"/>
+            <Mass value="2.59945309" units="kg" />
+        </Physics>
+        <Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/wrist2_l.iv</File>
+		</Visualization>
+        <!--CollisionModel>
+			<File type="Inventor">collisionModel/wrist2_l.iv</File>
+		</CollisionModel-->
+		
+		<ChildFromRobot>
+			<File importEEF="true">ArmarIII-LeftHand_minColModel.xml</File>
+		</ChildFromRobot>
+		
+	</RobotNode>
+	
+	<RobotNodeSet name="LeftArm" kinematicRoot="Left Arm Base" tcp="TCP L">
+		<Node name="Shoulder 1 L"/>
+		<Node name="Shoulder 2 L"/>
+		<Node name="Upperarm L"/>
+		<Node name="Elbow L"/>
+		<Node name="Underarm L"/>
+		<Node name="Wrist 1 L"/>
+		<Node name="Wrist 2 L"/>
+	</RobotNodeSet>
+	
+	<RobotNodeSet name="LeftArmColModel" kinematicRoot="Left Arm Base" tcp="TCP L">
+		<Node name="Upperarm L"/>
+		<Node name="Underarm L"/>
+		<Node name="Wrist 2 L"/>
+	</RobotNodeSet>
+	
+	<RobotNodeSet name="LeftArmHandColModel" kinematicRoot="Left Arm Base" tcp="TCP L">
+		<Node name="Upperarm L"/>
+		<Node name="Underarm L"/>
+		<Node name="Hand Palm 1 L"/>
+		<Node name="Hand Palm 2 L"/>
+		<Node name="Thumb L J0"/>
+		<Node name="Thumb L J1"/>
+		<Node name="Index L J0"/>
+		<Node name="Index L J1"/>
+		<Node name="Middle L J0"/>
+		<Node name="Middle L J1"/>
+		<Node name="Ring L J0"/>
+		<Node name="Ring L J1"/>
+		<Node name="Pinky L J0"/>
+		<Node name="Pinky L J1"/>
+	</RobotNodeSet>
+
+
+	
+</Robot>
diff --git a/data/RobotAPI/robots/Armar3/ArmarIII-LeftHand.xml b/data/RobotAPI/robots/Armar3/ArmarIII-LeftHand.xml
new file mode 100644
index 0000000000000000000000000000000000000000..2135b1b4d3e78eccb8d09b28e90327bfea051462
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/ArmarIII-LeftHand.xml
@@ -0,0 +1,469 @@
+<?xml version="1.0" encoding="UTF-8" ?>
+
+<Robot Type="ArmarIII LeftHand" RootNode="Hand L Base">
+
+    <RobotNode name="Hand L Base">
+		<Child name="TCP L"/>
+		<Child name="GCP L"/>
+		<Child name="Marker L"/>
+		<Child name="left_hand_configuration_actual_float"/>
+		<Child name="Hand Palm 1 L"/>
+	</RobotNode>
+	
+	<RobotNode name="TCP L">
+		<Transform>
+			<Translation x="0" y="0" z="130"/>
+		</Transform>
+	</RobotNode>
+	
+	<RobotNode name="GCP L">
+		<Transform>
+			<Translation X="-40" Y="-20" Z="90"/>
+			<rollpitchyaw roll="0" pitch="-45" yaw="0" units="degree"/>
+		</Transform>
+	</RobotNode>
+	
+	<RobotNode name="Marker L">
+		<Transform>
+			<Translation x="-35" y="45" z="65"/>
+		</Transform>
+		<Visualization enable="false">
+			<CoordinateAxis type="Inventor" enable="true" scaling="1"/>
+		</Visualization>
+	</RobotNode>
+	
+	<RobotNode name="left_hand_configuration_actual_float">
+                <!--Joint type="revolute">
+			<Axis x="0" y="0" z="1"/>
+			<Limits unit="degree" lo="-20" hi="20"/>
+                </Joint-->
+	</RobotNode>
+	
+	<RobotNode name="Hand Palm 1 L">
+		<Transform>
+			<Translation x="0" y="0" z="36"/>
+		</Transform>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/palm1_l.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">convexModel/palm1_l.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="800" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+		
+		<Child name="Hand Palm 2 L"/>
+		<Child name="Thumb L"/>
+	</RobotNode>
+	
+	<RobotNode name="Hand Palm 2 L">
+		<Transform>
+			<Translation x="-8.7" y="13.5" z="29.25"/>
+		</Transform>
+		<Joint type="revolute">
+			<Axis x="0" y="-1" z="0"/>
+                        <Limits unit="degree" lo="-90" hi="90"/>
+                        <MaxVelocity unit="radian" value="1"/>
+                        <MaxAcceleration value="10"/>
+                        <MaxTorque value="10"/>
+                </Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/palm2_l.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">convexModel/palm2_l.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="800" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>	
+			
+		<Child name="Pinky L"/>
+		<Child name="Ring L"/>
+		<Child name="Middle L"/>
+		<Child name="Index L"/>
+	</RobotNode>
+	
+	<RobotNode name="Thumb L">
+		<Transform>
+			<Translation x="-48.9" y="0" z="29.25"/>
+		</Transform>
+		<Child name="Thumb L J0"/>
+	</RobotNode>
+	
+	<RobotNode name="Thumb L J0">
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<Axis x="0" y="1" z="0"/>
+            <MaxVelocity unit="radian" value="1"/>
+            <MaxAcceleration value="10"/>
+            <MaxTorque value="10"/>
+        </Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/thumb_l1.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">convexModel/thumb_l1.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>	
+			
+		<Child name="Thumb L J1"/>
+	</RobotNode>
+	
+	<RobotNode name="Thumb L J1">
+		<Transform>
+			<Translation x="-40.2" y="0" z="0"/>
+		</Transform>
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<Axis x="0" y="1" z="0"/>
+            <MaxVelocity unit="radian" value="1"/>
+            <MaxAcceleration value="10"/>
+            <MaxTorque value="10"/>
+        </Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/thumb_l2.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">convexModel/thumb_l2.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+	</RobotNode>
+	
+	<RobotNode name="Pinky L">
+		<Transform>
+			<Translation x="0" y="-73" z="40.4"/>
+		</Transform>
+		
+		<Child name="Pinky L J0"/>
+	</RobotNode>
+	
+	<RobotNode name="Pinky L J0">
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<Axis x="0" y="-1" z="0"/>
+            <MaxVelocity unit="radian" value="1"/>
+            <MaxAcceleration value="10"/>
+            <MaxTorque value="10"/>
+        </Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/pinky_l1.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">convexModel/pinky_l1.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+		
+		<Child name="Pinky L J1"/>
+	</RobotNode>
+	
+	<RobotNode name="Pinky L J1">
+		<Transform>
+			<Translation x="0" y="0" z="40.2"/>
+		</Transform>
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<Axis x="0" y="-1" z="0"/>
+            <MaxVelocity unit="radian" value="1"/>
+            <MaxAcceleration value="10"/>
+            <MaxTorque value="10"/>
+        </Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/pinky_l2.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">convexModel/pinky_l2.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+	</RobotNode>
+	
+	<RobotNode name="Ring L">
+		<Transform>
+			<Translation x="0" y="-51" z="40.4"/>
+		</Transform>
+		
+		<Child name="Ring L J0"/>
+	</RobotNode>
+	
+	<RobotNode name="Ring L J0">
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<Axis x="0" y="-1" z="0"/>
+            <MaxVelocity unit="radian" value="1"/>
+            <MaxAcceleration value="10"/>
+            <MaxTorque value="10"/>
+        </Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/ring_l1.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">convexModel/ring_l1.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+		
+		<Child name="Ring L J1"/>
+	</RobotNode>
+	
+	<RobotNode name="Ring L J1">
+		<Transform>
+			<Translation x="0" y="0" z="40.2"/>
+		</Transform>
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<Axis x="0" y="-1" z="0"/>
+            <MaxVelocity unit="radian" value="1"/>
+            <MaxAcceleration value="10"/>
+            <MaxTorque value="10"/>
+        </Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/ring_l2.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">convexModel/ring_l2.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+	</RobotNode>
+	
+	<RobotNode name="Middle L">
+		<Transform>
+			<Translation x="0" y="-27" z="40.4"/>
+		</Transform>
+		
+		<Child name="Middle L J0"/>
+	</RobotNode>
+	
+	<RobotNode name="Middle L J0">
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<Axis x="0" y="-1" z="0"/>
+            <MaxVelocity unit="radian" value="1"/>
+            <MaxAcceleration value="10"/>
+            <MaxTorque value="10"/>
+        </Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/middle_l1.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">convexModel/middle_l1.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+		
+		<Child name="Middle L J1"/>
+	</RobotNode>
+	
+	<RobotNode name="Middle L J1">
+		<Transform>
+			<Translation x="0" y="0" z="40.2"/>
+		</Transform>
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<Axis x="0" y="-1" z="0"/>
+            <MaxVelocity unit="radian" value="1"/>
+            <MaxAcceleration value="10"/>
+            <MaxTorque value="10"/>
+        </Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/middle_l2.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">convexModel/middle_l2.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+	</RobotNode>
+	
+	<RobotNode name="Index L">
+		<Transform>
+			<Translation x="0" y="0" z="40.2"/>
+		</Transform>
+		
+		<Child name="Index L J0"/>
+	</RobotNode>
+	
+	<RobotNode name="Index L J0">
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<Axis x="0" y="-1" z="0"/>
+            <MaxVelocity unit="radian" value="1"/>
+            <MaxAcceleration value="10"/>
+            <MaxTorque value="10"/>
+        </Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/index_l1.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">convexModel/index_l1.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+		
+		<Child name="Index L J1"/>
+	</RobotNode>
+	
+	<RobotNode name="Index L J1">
+		<Transform>
+			<Translation x="0" y="0" z="40.2"/>
+		</Transform>
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<Axis x="0" y="-1" z="0"/>
+            <MaxVelocity unit="radian" value="1"/>
+            <MaxAcceleration value="10"/>
+            <MaxTorque value="10"/>
+        </Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/index_l2.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">convexModel/index_l2.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+	</RobotNode>
+	
+	<RobotNodeSet name="LeftHandColModel" kinematicRoot="Hand L Base" tcp="TCP L">
+		<Node name="Hand Palm 1 L"/>
+		<Node name="Hand Palm 2 L"/>
+		<Node name="Thumb L J0"/>
+		<Node name="Thumb L J1"/>
+		<Node name="Index L J0"/>
+		<Node name="Index L J1"/>
+		<Node name="Middle L J0"/>
+		<Node name="Middle L J1"/>
+		<Node name="Ring L J0"/>
+		<Node name="Ring L J1"/>
+		<Node name="Pinky L J0"/>
+		<Node name="Pinky L J1"/>
+	</RobotNodeSet>
+	
+	
+	<RobotNodeSet name="LeftHandJoints" kinematicRoot="Hand L Base" tcp="TCP L">
+		<Node name="Thumb L J0"/>
+		<Node name="Thumb L J1"/>
+		<Node name="Index L J0"/>
+		<Node name="Index L J1"/>
+		<Node name="Middle L J0"/>
+		<Node name="Middle L J1"/>
+		<Node name="Ring L J0"/>
+		<Node name="Ring L J1"/>
+		<Node name="Pinky L J0"/>
+		<Node name="Pinky L J1"/>
+	</RobotNodeSet>
+
+        <Endeffector name="TCP L" base="Hand L Base" tcp="TCP L" gcp="GCP L">
+	    <Preshape name="Open Preshape">
+	        <Node name="Thumb L J0" unit="radian" value="0"/>
+	        <Node name="Thumb L J1" unit="radian" value="0"/>
+	        <Node name="Index L J0" unit="radian" value="0"/>
+	        <Node name="Index L J1" unit="radian" value="0"/>
+	        <Node name="Middle L J0" unit="radian" value="0"/>
+	        <Node name="Middle L J1" unit="radian" value="0"/>
+	        <Node name="Ring L J0" unit="radian" value="0"/>
+	        <Node name="Ring L J1" unit="radian" value="0"/>
+	        <Node name="Pinky L J0" unit="radian" value="0"/>
+	        <Node name="Pinky L J1" unit="radian" value="0"/>
+	    </Preshape>
+            <Preshape name="Close Preshape">
+                <Node name="Thumb L J0" unit="radian" value="1"/>
+                <Node name="Thumb L J1" unit="radian" value="1"/>
+                <Node name="Index L J0" unit="radian" value="1"/>
+                <Node name="Index L J1" unit="radian" value="1"/>
+                <Node name="Middle L J0" unit="radian" value="1"/>
+                <Node name="Middle L J1" unit="radian" value="1"/>
+                <Node name="Ring L J0" unit="radian" value="1"/>
+                <Node name="Ring L J1" unit="radian" value="1"/>
+                <Node name="Pinky L J0" unit="radian" value="1"/>
+                <Node name="Pinky L J1" unit="radian" value="1"/>
+            </Preshape>
+		<Static>
+			<Node name="Hand Palm 1 L"/>
+			<Node name="Hand Palm 2 L"/>
+		</Static>
+		<Actor name="Thumb Left">
+			<Node name="Thumb L J0" considerCollisions="Actors"/>
+			<Node name="Thumb L J1" considerCollisions="All"/>
+		</Actor>
+		<Actor name="Index Left">
+			<Node name="Index L J0" considerCollisions="Actors"/>
+			<Node name="Index L J1" considerCollisions="All"/>
+		</Actor>
+		<Actor name="Middle Left">
+			<Node name="Middle L J0" considerCollisions="Actors"/>
+			<Node name="Middle L J1" considerCollisions="All"/>
+		</Actor>
+		<Actor name="Ring Left">
+			<Node name="Ring L J0" considerCollisions="Actors"/>
+			<Node name="Ring L J1" considerCollisions="All"/>
+		</Actor>
+		<Actor name="Pinky Left">
+			<Node name="Pinky L J0" considerCollisions="Actors"/>
+			<Node name="Pinky L J1" considerCollisions="All"/>
+		</Actor>
+	</Endeffector>
+
+</Robot>
diff --git a/data/RobotAPI/robots/Armar3/ArmarIII-LeftHand_minColModel.xml b/data/RobotAPI/robots/Armar3/ArmarIII-LeftHand_minColModel.xml
new file mode 100644
index 0000000000000000000000000000000000000000..e946ba874996ed9b27c03bb53fb66336302f754e
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/ArmarIII-LeftHand_minColModel.xml
@@ -0,0 +1,463 @@
+<?xml version="1.0" encoding="UTF-8" ?>
+
+<Robot Type="ArmarIII LeftHand" RootNode="Hand L Base">
+
+    <RobotNode name="Hand L Base">
+		<Child name="TCP L"/>
+		<Child name="GCP L"/>
+		<Child name="Hand Palm 1 L"/>
+	</RobotNode>
+	
+	<RobotNode name="TCP L">
+		<Joint type="fixed">
+			<PreJointTransform>
+				<Transform>
+					<Translation x="0" y="0" z="130"/>
+				</Transform>
+			</PreJointTransform>
+		</Joint>
+	</RobotNode>
+	
+	<RobotNode name="GCP L">
+		<Joint type="fixed">
+			<PreJointTransform>
+				<Transform>
+					<Translation X="-40" Y="-20" Z="90"/>
+					<rollpitchyaw roll="0" pitch="-45" yaw="0" units="degree"/>
+				</Transform>
+			</PreJointTransform>
+		</Joint>
+	</RobotNode>
+	
+	<RobotNode name="Hand Palm 1 L">
+		<Joint type="fixed">
+			<PreJointTransform>
+				<Transform>
+					<Translation x="0" y="0" z="36"/>
+				</Transform>
+			</PreJointTransform>
+		</Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/palm1_l.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">collisionModel/palm1_l.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="800" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+		
+		<Child name="Hand Palm 2 L"/>
+		<Child name="Thumb L"/>
+	</RobotNode>
+	
+	<RobotNode name="Hand Palm 2 L">
+		<Joint type="revolute">
+			<PreJointTransform>
+				<Transform>
+					<Translation x="-8.7" y="13.5" z="29.25"/>
+				</Transform>
+			</PreJointTransform>
+			<Axis x="0" y="-1" z="0"/>
+			<Limits unit="degree" lo="-90" hi="90"/>
+		</Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/palm2_l.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">collisionModel/palm2_l.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="800" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>	
+			
+		<Child name="Pinky L"/>
+		<Child name="Ring L"/>
+		<Child name="Middle L"/>
+		<Child name="Index L"/>
+	</RobotNode>
+	
+	<RobotNode name="Thumb L">
+		<Joint type="fixed">
+			<PreJointTransform>
+				<Transform>
+					<Translation x="-48.9" y="0" z="29.25"/>
+				</Transform>
+			</PreJointTransform>
+		</Joint>
+		
+		<Child name="Thumb L J0"/>
+	</RobotNode>
+	
+	<RobotNode name="Thumb L J0">
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<PreJointTransform>
+				<Transform>
+					<Translation x="0" y="0" z="0"/>
+				</Transform>
+			</PreJointTransform>
+			<Axis x="0" y="1" z="0"/>
+		</Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/thumb_l1.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">collisionModel/thumb_l1.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>	
+			
+		<Child name="Thumb L J1"/>
+	</RobotNode>
+	
+	<RobotNode name="Thumb L J1">
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<PreJointTransform>
+				<Transform>
+					<Translation x="-40.2" y="0" z="0"/>
+				</Transform>
+			</PreJointTransform>
+			<Axis x="0" y="1" z="0"/>
+		</Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/thumb_l2.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">collisionModel/thumb_l2.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+	</RobotNode>
+	
+	<RobotNode name="Pinky L">
+		<Joint type="fixed">
+			<PreJointTransform>
+				<Transform>
+					<Translation x="0" y="-73" z="40.4"/>
+				</Transform>
+			</PreJointTransform>
+		</Joint>
+		
+		<Child name="Pinky L J0"/>
+	</RobotNode>
+	
+	<RobotNode name="Pinky L J0">
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<PreJointTransform>
+				<Transform>
+					<Translation x="0" y="0" z="0"/>
+				</Transform>
+			</PreJointTransform>
+			<Axis x="0" y="-1" z="0"/>
+		</Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/pinky_l1.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">collisionModel/pinky_l1.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+		
+		<Child name="Pinky L J1"/>
+	</RobotNode>
+	
+	<RobotNode name="Pinky L J1">
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<PreJointTransform>
+				<Transform>
+					<Translation x="0" y="0" z="40.2"/>
+				</Transform>
+			</PreJointTransform>
+			<Axis x="0" y="-1" z="0"/>
+		</Joint>
+		
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/pinky_l2.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">collisionModel/pinky_l2.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+	</RobotNode>
+	
+	<RobotNode name="Ring L">
+		<Joint type="fixed">
+			<PreJointTransform>
+				<Transform>
+					<Translation x="0" y="-51" z="40.4"/>
+				</Transform>
+			</PreJointTransform>
+		</Joint>
+		
+		<Child name="Ring L J0"/>
+	</RobotNode>
+	
+	<RobotNode name="Ring L J0">
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<PreJointTransform>
+				<Transform>
+					<Translation x="0" y="0" z="0"/>
+				</Transform>
+			</PreJointTransform>
+			<Axis x="0" y="-1" z="0"/>
+		</Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/ring_l1.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">collisionModel/ring_l1.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+		
+		<Child name="Ring L J1"/>
+	</RobotNode>
+	
+	<RobotNode name="Ring L J1">
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<PreJointTransform>
+				<Transform>
+					<Translation x="0" y="0" z="40.2"/>
+				</Transform>
+			</PreJointTransform>
+			<Axis x="0" y="-1" z="0"/>
+		</Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/ring_l2.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">collisionModel/ring_l2.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+	</RobotNode>
+	
+	<RobotNode name="Middle L">
+		<Joint type="fixed">
+			<PreJointTransform>
+				<Transform>
+					<Translation x="0" y="-27" z="40.4"/>
+				</Transform>
+			</PreJointTransform>
+		</Joint>
+		
+		<Child name="Middle L J0"/>
+	</RobotNode>
+	
+	<RobotNode name="Middle L J0">
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<PreJointTransform>
+				<Transform>
+					<Translation x="0" y="0" z="0"/>
+				</Transform>
+			</PreJointTransform>
+			<Axis x="0" y="-1" z="0"/>
+		</Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/middle_l1.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">collisionModel/middle_l1.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+		
+		<Child name="Middle L J1"/>
+	</RobotNode>
+	
+	<RobotNode name="Middle L J1">
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<PreJointTransform>
+				<Transform>
+					<Translation x="0" y="0" z="40.2"/>
+				</Transform>
+			</PreJointTransform>
+			<Axis x="0" y="-1" z="0"/>
+		</Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/middle_l2.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">collisionModel/middle_l2.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+	</RobotNode>
+	
+	<RobotNode name="Index L">
+		<Joint type="fixed">
+			<PreJointTransform>
+				<Transform>
+					<Translation x="0" y="0" z="40.2"/>
+				</Transform>
+			</PreJointTransform>
+		</Joint>
+		
+		<Child name="Index L J0"/>
+	</RobotNode>
+	
+	<RobotNode name="Index L J0">
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<PreJointTransform>
+				<Transform>
+					<Translation x="0" y="0" z="0"/>
+				</Transform>
+			</PreJointTransform>
+			<Axis x="0" y="-1" z="0"/>
+		</Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/index_l1.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">collisionModel/index_l1.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+		
+		<Child name="Index L J1"/>
+	</RobotNode>
+	
+	<RobotNode name="Index L J1">
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<PreJointTransform>
+				<Transform>
+					<Translation x="0" y="0" z="40.2"/>
+				</Transform>
+			</PreJointTransform>
+			<Axis x="0" y="-1" z="0"/>
+		</Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/index_l2.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">collisionModel/index_l2.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+	</RobotNode>
+	
+	<RobotNodeSet name="LeftHandColModel" kinematicRoot="Hand L Base" tcp="TCP L">
+		<Node name="Hand Palm 1 L"/>
+		<Node name="Hand Palm 2 L"/>
+		<Node name="Thumb L J0"/>
+		<Node name="Thumb L J1"/>
+		<Node name="Index L J0"/>
+		<Node name="Index L J1"/>
+		<Node name="Middle L J0"/>
+		<Node name="Middle L J1"/>
+		<Node name="Ring L J0"/>
+		<Node name="Ring L J1"/>
+		<Node name="Pinky L J0"/>
+		<Node name="Pinky L J1"/>
+	</RobotNodeSet>
+
+        <Endeffector name="TCP L" base="Hand L Base" tcp="TCP L" gcp="GCP L">
+	    <Preshape name="Grasp Preshape">
+	        <Node name="Thumb L J0" unit="radian" value="0"/>
+	        <Node name="Thumb L J1" unit="radian" value="0"/>
+	        <Node name="Index L J0" unit="radian" value="0"/>
+	        <Node name="Index L J1" unit="radian" value="0"/>
+	        <Node name="Middle L J0" unit="radian" value="0"/>
+	        <Node name="Middle L J1" unit="radian" value="0"/>
+	        <Node name="Ring L J0" unit="radian" value="0"/>
+	        <Node name="Ring L J1" unit="radian" value="0"/>
+	        <Node name="Pinky L J0" unit="radian" value="0"/>
+	        <Node name="Pinky L J1" unit="radian" value="0"/>
+	    </Preshape>
+		<Static>
+			<Node name="Hand Palm 1 L"/>
+			<Node name="Hand Palm 2 L"/>
+		</Static>
+		<Actor name="Thumb Left">
+			<Node name="Thumb L J0" considerCollisions="Actors"/>
+			<Node name="Thumb L J1" considerCollisions="All"/>
+		</Actor>
+		<Actor name="Index Left">
+			<Node name="Index L J0" considerCollisions="Actors"/>
+			<Node name="Index L J1" considerCollisions="All"/>
+		</Actor>
+		<Actor name="Middle Left">
+			<Node name="Middle L J0" considerCollisions="Actors"/>
+			<Node name="Middle L J1" considerCollisions="All"/>
+		</Actor>
+		<Actor name="Ring Left">
+			<Node name="Ring L J0" considerCollisions="Actors"/>
+			<Node name="Ring L J1" considerCollisions="All"/>
+		</Actor>
+		<Actor name="Pinky Left">
+			<Node name="Pinky L J0" considerCollisions="Actors"/>
+			<Node name="Pinky L J1" considerCollisions="All"/>
+		</Actor>
+	</Endeffector>
+
+</Robot>
diff --git a/data/RobotAPI/robots/Armar3/ArmarIII-Platform.xml b/data/RobotAPI/robots/Armar3/ArmarIII-Platform.xml
new file mode 100644
index 0000000000000000000000000000000000000000..a41d1fc7e21321b3aa9ba9be339307d687061521
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/ArmarIII-Platform.xml
@@ -0,0 +1,230 @@
+<?xml version="1.0" encoding="UTF-8" ?>
+
+<Robot Type="Armar3" StandardName="Armar3" RootNode="Armar3_Base">
+	
+	<RobotNode name="Armar3_Base">
+		<Visualization enable="true">
+			<CoordinateAxis  type="Inventor" enable="false" scaling="20"/>
+		</Visualization>
+		<Child name="Dummy_Platform"/>
+	</RobotNode>
+	
+	<RobotNode name="Dummy_Platform">
+				<Transform>
+					<DH a="0" d="0" theta="0" alpha="-90" units="degree"/>
+				</Transform>
+		<!--Joint type="fixed">
+			<DH a="0" d="0" theta="0" alpha="-90" units="degree"/>
+		</Joint-->
+		<Child name="X_Platform"/>
+	</RobotNode>
+	
+	<RobotNode name="X_Platform">
+				<Transform>
+					<DH a="0" d="0" theta="90" alpha="0" units="degree"/>
+				</Transform>
+		<Joint type="prismatic">
+			<!--DH a="0" d="0" theta="90" alpha="-90" units="degree"/-->
+			<TranslationDirection x="0" y="0" z="1"/>
+			<Limits unit="mm" lo="-10000" hi="10000"/>
+			<!--
+			<PreJointTransform>
+				<Transform>
+					<Translation x="0" y="0" z="100"/>
+				</Transform>
+			</PreJointTransform>
+			-->
+			<!--
+			<Axis x="1" y="0" z="0"/>-->   <!-- definition of movement axis if DH not defined ?-->
+			<!--
+			<PostJointTransform>
+				<Transform>
+					<Translation x="0" y="0" z="0"/>
+				</Transform>
+			</PostJointTransform>
+			-->
+		</Joint>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+		</Visualization>
+		<Child name="Y_Platform"/>
+	</RobotNode>
+	
+	<RobotNode name="Y_Platform">
+				<Transform>
+					<DH a="0" d="0" theta="-90" alpha="0" units="degree"/>
+					<DH a="0" d="0" theta="0" alpha="-90" units="degree"/>
+        </Transform>
+		<Joint type="prismatic">
+			<!--DH a="0" d="0" theta="-90" alpha="90" units="degree"/-->
+			<TranslationDirection x="0" y="0" z="1"/>
+			<Limits unit="mm" lo="-10000" hi="10000"/>
+		</Joint>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+		</Visualization>
+		<Child name="Yaw_Platform"/>
+	</RobotNode>
+	
+	<RobotNode name="Yaw_Platform">
+				<Transform>
+					<DH a="0" d="0" theta="-90" alpha="0" units="degree"/>
+					<DH a="0" d="0" theta="0" alpha="90" units="degree"/>
+        </Transform>
+		<Joint type="revolute">
+			<axis x="0" y="0" z="1"/>
+			<!--DH a="0" d="0" theta="-90" alpha="0" units="degree"/-->
+			<Limits unit="degree" lo="-360" hi="360"/>
+                        <MaxVelocity unit="radian" value="1"/>
+                        <MaxAcceleration value="10"/>
+                        <MaxTorque value="3000"/>
+		</Joint>
+		
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/platform.iv</File>
+		</Visualization>
+		<CollisionModel>
+			<File type="Inventor">collisionModel/platform.iv</File>
+		</CollisionModel>
+		
+		<Child name="Hip Pitch"/>
+	</RobotNode>
+	
+
+	<RobotNode name="Hip Pitch">
+				<Transform>
+					<Translation x="0" y="158" z="890"/>  <!-- x,y,z of THIS COS, NOT any other COS-->
+				</Transform>
+		<Joint type="revolute">
+			<Axis x="1" y="0" z="0"/>
+			<Limits unit="degree" lo="-45" hi="45"/>
+                        <MaxVelocity unit="radian" value="1"/>
+                        <MaxAcceleration value="10"/>
+                        <MaxTorque value="3000"/>
+		</Joint>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/platform_pitch_link.iv</File>
+		</Visualization>
+		<Child name="Hip Roll"/>
+	</RobotNode>
+	
+	<RobotNode name="Hip Roll">
+		<Joint type="revolute">
+			<Axis x="0" y="1" z="0"/>
+			<Limits unit="degree" lo="-45" hi="45"/>
+                        <MaxVelocity unit="radian" value="1"/>
+                        <MaxAcceleration value="10"/>
+                        <MaxTorque value="3000"/>
+		</Joint>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/platform_roll_link.iv</File>
+		</Visualization>
+		<Child name="Hip Yaw"/>
+	</RobotNode>
+	
+	<RobotNode name="Hip Yaw">
+		<Joint type="revolute">
+			<Axis x="0" y="0" z="1"/>
+			<Limits unit="degree" lo="-45" hi="45"/>
+                        <MaxVelocity unit="radian" value="1"/>
+                        <MaxAcceleration value="10"/>
+                        <MaxTorque value="3000"/>
+		</Joint>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/torso.iv</File>
+		</Visualization>
+		<CollisionModel>
+			<File type="Inventor">collisionModel/torso.iv</File>
+		</CollisionModel>
+		<Child name="Center of Arms"/>
+	</RobotNode>
+	
+	<RobotNode name="Center of Arms">
+				<Transform>
+					<Translation x="0" y="-35" z="485"/>
+				</Transform>
+
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+		</Visualization>
+		
+		<Child name="TrafoToHead"/>
+		<Child name="TrafoToLeftArm"/>
+		<Child name="TrafoToRightArm"/>
+	</RobotNode>
+	
+	<RobotNode name="TrafoToHead">
+		<Transform>
+					<Translation x="0" y="0" z="118"/>
+	  </Transform>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+		</Visualization>
+		
+		<ChildFromRobot>
+			<File importEEF="true">ArmarIII-Head.xml</File>
+		</ChildFromRobot>
+	</RobotNode>
+	
+	<RobotNode name="TrafoToLeftArm">
+		<Transform>
+					<Translation x="-232" y="0" z="0"/>
+				</Transform>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+		</Visualization>
+		
+		<ChildFromRobot>
+			<File importEEF="true">ArmarIII-LeftArm.xml</File>
+		</ChildFromRobot>
+	</RobotNode>
+	
+	<RobotNode name="TrafoToRightArm">
+				<Transform>
+					<Translation x="232" y="0" z="0"/>
+				</Transform>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+		</Visualization>
+		
+		<ChildFromRobot>
+			<File importEEF="true">ArmarIII-RightArm.xml</File>
+		</ChildFromRobot>
+	</RobotNode>
+	
+	<RobotNodeSet name="Platform">
+		<Node name="X_Platform"/>
+		<Node name="Y_Platform"/>
+		<Node name="Yaw_Platform"/>
+	</RobotNodeSet>
+	
+	<RobotNodeSet name="PlatformColModel">
+		<Node name="Yaw_Platform"/>
+	</RobotNodeSet>
+	
+	<RobotNodeSet name="TorsoColModel">
+		<Node name="Hip Yaw"/>
+	</RobotNodeSet>
+	
+	<RobotNodeSet name="Hip">
+		<Node name="Hip Pitch"/>
+		<Node name="Hip Roll"/>
+		<Node name="Hip Yaw"/>
+	</RobotNodeSet>
+	
+        <RobotNodeSet name="PlatformTorsoColModel">
+		<Node name="Yaw_Platform"/>
+                <Node name="Hip Yaw"/>
+        </RobotNodeSet>
+
+	<RobotNodeSet name="PlatformTorsoHeadColModel">
+		<Node name="Yaw_Platform"/>
+		<Node name="Hip Yaw"/>
+		<Node name="Head_Tilt"/>
+	</RobotNodeSet>
+	
+</Robot>
diff --git a/data/RobotAPI/robots/Armar3/ArmarIII-RightArm.xml b/data/RobotAPI/robots/Armar3/ArmarIII-RightArm.xml
new file mode 100644
index 0000000000000000000000000000000000000000..3f4b75084f79e4c0567a0dd2ad4d711910cb3898
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/ArmarIII-RightArm.xml
@@ -0,0 +1,257 @@
+<?xml version="1.0" encoding="UTF-8" ?>	
+
+<Robot Type="ArmarIII RightArm" RootNode="Right Arm Base">	
+
+    <RobotNode name="Right Arm Base">
+		<Transform>
+			<DH a="0" d="0" theta="-90" alpha="90" units="degree"/>
+		</Transform>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+		</Visualization>
+		<Child name="Shoulder 1 R"/>
+	</RobotNode>
+	
+	<RobotNode name="Shoulder 1 R">
+		<Transform>
+			<DH a="0" d="0" theta="90" alpha="0" units="degree"/>
+		</Transform>
+		<Joint type="revolute">
+			<!--DH a="0" d="0" theta="90" alpha="90" units="degree"/-->
+			<Limits unit="degree" lo="-107" hi="42"/>
+                        <MaxVelocity unit="radian" value="0.5"/>
+                        <MaxAcceleration value="10"/>
+                        <MaxTorque value="3000"/>
+                </Joint>
+		<Physics>
+            <CoM location="VisualizationBBoxCenter"/>
+            <Mass value="3.65" units="kg" />
+        </Physics>
+		<Visualization enable="true">
+                        <CoordinateAxis type="Inventor" enable="false" scaling="4"/>
+			<File type="Inventor">fullmodel/shoulder_r.iv</File>
+		</Visualization>
+		<CollisionModel>
+			<File type="Inventor">convexModel/shoulder_r.iv</File>
+		</CollisionModel>
+		<Child name="Shoulder 2 R"/>
+	</RobotNode>
+	
+	<RobotNode name="Shoulder 2 R">
+		<Transform>
+			<DH a="0" d="0" theta="0" alpha="90" units="degree"/>
+			<DH a="0" d="0" theta="105" alpha="0" units="degree"/>
+		</Transform>
+		<Joint type="revolute">
+			<!--DH a="0" d="0" theta="105" alpha="90" units="degree"/-->
+			<Limits unit="degree" lo="-14" hi="95"/> 
+                        <MaxVelocity unit="radian" value="0.5"/>
+                        <MaxAcceleration value="10"/>
+                        <MaxTorque value="3000"/>
+                </Joint>
+        <Physics>
+            <CoM location="VisualizationBBoxCenter"/>
+            <Mass value="2.5" units="kg" />
+        </Physics>
+        <Visualization enable="true">
+			<File type="Inventor">fullmodel/shoulder2_r_rot.iv</File>
+		</Visualization>
+		<CollisionModel>
+			<File type="Inventor">convexModel/shoulder2_r_rot.iv</File>
+		</CollisionModel>
+		<Child name="Upperarm R"/>
+	</RobotNode>
+	
+	<RobotNode name="Upperarm R">
+		<Transform>
+			<DH a="0" d="0" theta="0" alpha="90" units="degree"/>
+			<DH a="0" d="0" theta="-90" alpha="0" units="degree"/>
+		</Transform>
+		<Joint type="revolute">
+			<!--DH a="20" d="-310" theta="-90" alpha="90" units="degree"/-->
+			<Limits unit="degree" lo="-109" hi="70"/>
+                        <MaxVelocity unit="radian" value="0.5"/>
+                        <MaxAcceleration value="10"/>
+                        <MaxTorque value="3000"/>
+                </Joint>
+		<Physics>
+            <CoM location="VisualizationBBoxCenter"/>
+            <Mass value="1.55685000" units="kg" />
+            <IgnoreCollision name="Shoulder 1 R"/>
+        </Physics>
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/upperarm_r.iv</File>
+		</Visualization>
+		<CollisionModel>
+			<File type="Inventor">convexModel/upperarm_r.iv</File>
+		</CollisionModel>
+		<Child name="Elbow R"/>
+	</RobotNode>
+	
+	<RobotNode name="Elbow R">
+		<Transform>
+			<DH a="20" d="-310" theta="0" alpha="90" units="degree"/>
+			<DH a="0" d="0" theta="90" alpha="0" units="degree"/>
+		</Transform>
+		<Joint type="revolute">
+			<!--DH a="0" d="7.5" theta="90" alpha="-90" units="degree"/-->
+			<Limits unit="degree" lo="-120" hi="40"/> 
+                        <MaxVelocity unit="radian" value="1"/>
+                        <MaxAcceleration value="10"/>
+                        <MaxTorque value="3000"/>
+                </Joint>
+		<Visualization enable="true">
+                        <CoordinateAxis type="Inventor" enable="false" scaling="4"/>
+			<File type="Inventor">fullmodel/elbow_r.iv</File>
+		</Visualization>
+		<CollisionModel>
+			<File type="Inventor">convexModel/elbow_r.iv</File>
+		</CollisionModel>
+		<Physics>
+            <CoM location="Joint"/>
+            <Mass value="1.15744000" units="kg" />
+        </Physics>
+		<Child name="Underarm R"/>
+	</RobotNode>
+	
+	<RobotNode name="Underarm R">
+		<Transform>
+			<DH a="0" d="7.5" theta="0" alpha="-90" units="degree"/>
+			<DH a="0" d="0" theta="90" alpha="0" units="degree"/>
+		</Transform>
+		<Joint type="revolute">
+			<!--DH a="0" d="-240" theta="90" alpha="-90" units="degree"/-->
+			
+            <Limits unit="degree" lo="-90" hi="200"/>
+                        <MaxVelocity unit="radian" value="0.5"/>
+                        <MaxAcceleration value="10"/>
+                        <MaxTorque value="3000"/>
+                </Joint>
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/underarm_r.iv</File>
+		</Visualization>
+ 		<CollisionModel>
+			<File type="Inventor">convexModel/underarm_r.iv</File>
+		</CollisionModel>
+		<Physics>
+            <CoM location="VisualizationBBoxCenter"/>
+            <Mass value="2.26566087" units="kg" />
+        </Physics>
+		<Child name="Wrist 1 R"/>
+	</RobotNode>
+	
+	<RobotNode name="Wrist 1 R">
+		<Transform>
+			<DH a="0" d="-240" theta="0" alpha="-90" units="degree"/>
+			<DH a="0" d="0" theta="-90" alpha="0" units="degree"/>
+		</Transform>
+		<Joint type="revolute">
+			<!--DH a="0" d="0" theta="-90" alpha="-90" units="degree"/-->
+            <Limits unit="degree" lo="-22.3" hi="22.8"/>
+                        <MaxVelocity unit="radian" value="0.5"/>
+                        <MaxAcceleration value="10"/>
+                        <MaxTorque value="3000"/>
+                </Joint>
+		<Physics>
+            <CoM location="VisualizationBBoxCenter"/>
+            <Mass value="1.29945309" units="kg" /><!--1.13047000-->
+        </Physics>
+   	    <Visualization enable="true">
+                        <CoordinateAxis type="Inventor" enable="false" scaling="2"/>
+			<File type="Inventor">fullmodel/wrist1_r.iv</File>
+		</Visualization>
+		<CollisionModel>
+			<File type="Inventor">convexModel/wrist1_r.iv</File>
+		</CollisionModel>
+		<Child name="Wrist 2 R"/>
+	</RobotNode>
+	
+	<RobotNode name="Wrist 2 R">
+		<Transform>
+			<DH a="0" d="0" theta="0" alpha="-90" units="degree"/>
+			<DH a="0" d="0" theta="-90" alpha="0" units="degree"/>
+		</Transform>
+		<Joint type="revolute">
+			<!--DH a="0" d="0" theta="-90" alpha="90" units="degree"/-->
+                        <Limits unit="degree" lo="-31" hi="38"/>
+                        <MaxVelocity unit="radian" value="0.5"/>
+                        <MaxAcceleration value="10"/>
+                        <MaxTorque value="3000"/>
+                </Joint>
+
+    	<Visualization enable="true">
+                        <CoordinateAxis type="Inventor" enable="false" scaling="2"/>
+			<File type="Inventor">fullmodel/wrist2_r.iv</File>
+		</Visualization>
+		<!-- bullet doesn't like two models connected with a fixed joint -> disable this collisison model and just use the hand palm model-->
+        <!--CollisionModel>
+			<File type="Inventor">convexModel/wrist2_r.iv</File>
+		</CollisionModel>
+		
+		<Physics>
+            <CoM location="VisualizationBBoxCenter"/>
+            <Mass value="2.59945309" units="kg" />
+            <IgnoreCollision name="Underarm R"/>
+        </Physics-->
+        <Sensor type="forcetorque" name="FT R">
+			<!--Transform>
+				<Translation x="0" y="-40" z="0"/>
+			</Transform-->
+		</Sensor>
+		<Child name="EndArmR"/>
+    </RobotNode>
+	
+    <!--RobotNode name="FTSensorR">
+        <Transform>
+            <Translation x="0" y="-40" z="0"/>
+        </Transform>
+        <Sensor type="forcetorque"/>
+        <Child name="EndArmR"/>
+    </RobotNode-->
+	
+	<RobotNode name="EndArmR">
+		<Transform>
+			<Translation x="0" y="-40" z="0"/>
+			<DH a="0" d="0" theta="0" alpha="90" units="degree"/>
+		</Transform>
+	    <ChildFromRobot>
+			<File importEEF="true">ArmarIII-RightHand.xml</File>
+		</ChildFromRobot>
+	</RobotNode>
+	
+	<RobotNodeSet name="RightArm" kinematicRoot="Right Arm Base" tcp="TCP R">
+		<Node name="Shoulder 1 R"/>
+		<Node name="Shoulder 2 R"/>
+		<Node name="Upperarm R"/>
+		<Node name="Elbow R"/>
+		<Node name="Underarm R"/>
+		<Node name="Wrist 1 R"/>
+		<Node name="Wrist 2 R"/>
+	</RobotNodeSet>
+	
+	
+	
+	<RobotNodeSet name="RightArmColModel" kinematicRoot="Right Arm Base" tcp="TCP R">
+		<Node name="Upperarm R"/>
+		<Node name="Underarm R"/>
+		<Node name="Wrist 2 R"/>
+	</RobotNodeSet>
+	
+	<RobotNodeSet name="RightArmHandColModel" kinematicRoot="Right Arm Base" tcp="TCP R">
+		<Node name="Upperarm R"/>
+		<Node name="Underarm R"/>
+		<Node name="Hand Palm 1 R"/>
+		<Node name="Hand Palm 2 R"/>
+		<Node name="Thumb R J0"/>
+		<Node name="Thumb R J1"/>
+		<Node name="Index R J0"/>
+		<Node name="Index R J1"/>
+		<Node name="Middle R J0"/>
+		<Node name="Middle R J1"/>
+		<Node name="Ring R J0"/>
+		<Node name="Ring R J1"/>
+		<Node name="Pinky R J0"/>
+		<Node name="Pinky R J1"/>
+	</RobotNodeSet>
+	
+</Robot>
diff --git a/data/RobotAPI/robots/Armar3/ArmarIII-RightArm_minColModel.xml b/data/RobotAPI/robots/Armar3/ArmarIII-RightArm_minColModel.xml
new file mode 100644
index 0000000000000000000000000000000000000000..15f1001797cef37d3a5ded1ccebfb166e1741ed1
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/ArmarIII-RightArm_minColModel.xml
@@ -0,0 +1,174 @@
+<?xml version="1.0" encoding="UTF-8" ?>	
+
+<Robot Type="ArmarIII RightArm" RootNode="Right Arm Base">	
+
+<RobotNode name="Right Arm Base">
+		<Joint type="fixed">
+			<DH a="0" d="0" theta="-90" alpha="90" units="degree"/>
+		</Joint>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+		</Visualization>
+		<Child name="Shoulder 1 R"/>
+	</RobotNode>
+	
+	<RobotNode name="Shoulder 1 R">
+		<Joint type="revolute">
+			<DH a="0" d="0" theta="90" alpha="90" units="degree"/>
+			<Limits unit="degree" lo="-106.94" hi="41.67"/>
+		</Joint>
+		<Physics>
+            <CoM location="VisualizationBBoxCenter"/>
+            <Mass value="3.65" units="kg" />
+        </Physics>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/shoulder_r.iv</File>
+		</Visualization>
+		<CollisionModel>
+			<File type="Inventor">collisionModel/shoulder_r.iv</File>
+		</CollisionModel>
+		<Child name="Shoulder 2 R"/>
+	</RobotNode>
+	
+	<RobotNode name="Shoulder 2 R">
+		<Joint type="revolute">
+			<DH a="0" d="0" theta="105" alpha="90" units="degree"/>
+			<Limits unit="degree" lo="-13.85" hi="94.62"/>  <!-- ?! -->
+		</Joint>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/shoulder2_r_rot.iv</File>
+		</Visualization>
+		<Child name="Upperarm R"/>
+	</RobotNode>
+	
+	<RobotNode name="Upperarm R">
+		<Joint type="revolute">
+			<DH a="20" d="-310" theta="-90" alpha="90" units="degree"/>
+			<Limits unit="degree" lo="-108.11" hi="73.94"/>
+		</Joint>
+		<Physics>
+            <CoM location="VisualizationBBoxCenter"/>
+            <Mass value="1.55685000" units="kg" />
+        </Physics>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/upperarm_r.iv</File>
+		</Visualization>
+		<CollisionModel>
+			<File type="Inventor">collisionModel/upperarm_r.iv</File>
+		</CollisionModel>
+		<Child name="Elbow R"/>
+	</RobotNode>
+	
+	<RobotNode name="Elbow R">
+		<Joint type="revolute">
+			<DH a="0" d="7.5" theta="90" alpha="-90" units="degree"/>
+			<Limits unit="degree" lo="-114.58" hi="39.7"/> <!-- ?! -->
+		</Joint>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/elbow_r.iv</File>
+		</Visualization>
+		<!--Physics>
+            <CoM location="Joint"/>
+            <Mass value="1.15744000" units="kg" />
+        </Physics-->
+		<Child name="Underarm R"/>
+	</RobotNode>
+	
+	<RobotNode name="Underarm R">
+		<Joint type="revolute">
+			<DH a="0" d="-240" theta="90" alpha="-90" units="degree"/>
+			<Limits unit="degree" lo="-69.65" hi="108.25"/>
+		</Joint>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/underarm_r.iv</File>
+		</Visualization>
+		<Physics>
+            <CoM location="VisualizationBBoxCenter"/>
+            <Mass value="2.26566087" units="kg" />
+        </Physics>
+ 		<CollisionModel>
+			<File type="Inventor">collisionModel/underarm_r.iv</File>
+		</CollisionModel>
+		<Child name="Wrist 1 R"/>
+	</RobotNode>
+	
+	<RobotNode name="Wrist 1 R">
+		<Joint type="revolute">
+			<DH a="0" d="0" theta="-90" alpha="-90" units="degree"/>
+			<Limits unit="degree" lo="-29.18" hi="29.88"/>
+		</Joint>
+
+   	    <Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/wrist1_r.iv</File>
+		</Visualization>
+		<!--CollisionModel>
+			<File type="Inventor">collisionModel/wrist1_l.iv</File>
+		</CollisionModel-->
+		<Child name="Wrist 2 R"/>
+	</RobotNode>
+	
+	<RobotNode name="Wrist 2 R">
+		<Joint type="revolute">
+			<DH a="0" d="0" theta="-90" alpha="90" units="degree"/>
+			<Limits unit="degree" lo="-30.9" hi="50.87"/>
+		</Joint>
+		<!--Physics>
+            <CoM location="VisualizationBBoxCenter"/>
+            <Mass value="1.13047000" units="kg" />
+        </Physics-->
+    	<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/wrist2_r.iv</File>
+		</Visualization>
+        <!--CollisionModel>
+			<File type="Inventor">collisionModel/wrist2_l.iv</File>
+		</CollisionModel-->
+		<Physics>
+            <CoM location="VisualizationBBoxCenter"/>
+            <Mass value="2.59945309" units="kg" />
+        </Physics>
+		<ChildFromRobot>
+			<File importEEF="true">ArmarIII-RightHand_minColModel.xml</File>
+		</ChildFromRobot>
+	</RobotNode>
+	
+	<RobotNodeSet name="RightArm" kinematicRoot="Right Arm Base" tcp="TCP R">
+		<Node name="Shoulder 1 R"/>
+		<Node name="Shoulder 2 R"/>
+		<Node name="Upperarm R"/>
+		<Node name="Elbow R"/>
+		<Node name="Underarm R"/>
+		<Node name="Wrist 1 R"/>
+		<Node name="Wrist 2 R"/>
+	</RobotNodeSet>
+	
+	<RobotNodeSet name="RightArmColModel" kinematicRoot="Right Arm Base" tcp="TCP R">
+		<Node name="Upperarm R"/>
+		<Node name="Underarm R"/>
+		<Node name="Wrist 2 R"/>
+	</RobotNodeSet>
+	
+	<RobotNodeSet name="RightArmHandColModel" kinematicRoot="Right Arm Base" tcp="TCP R">
+		<Node name="Upperarm R"/>
+		<Node name="Underarm R"/>
+		<Node name="Hand Palm 1 R"/>
+		<Node name="Hand Palm 2 R"/>
+		<Node name="Thumb R J0"/>
+		<Node name="Thumb R J1"/>
+		<Node name="Index R J0"/>
+		<Node name="Index R J1"/>
+		<Node name="Middle R J0"/>
+		<Node name="Middle R J1"/>
+		<Node name="Ring R J0"/>
+		<Node name="Ring R J1"/>
+		<Node name="Pinky R J0"/>
+		<Node name="Pinky R J1"/>
+	</RobotNodeSet>
+	
+</Robot>
diff --git a/data/RobotAPI/robots/Armar3/ArmarIII-RightHand.xml b/data/RobotAPI/robots/Armar3/ArmarIII-RightHand.xml
new file mode 100644
index 0000000000000000000000000000000000000000..204c042374f46747c34f293f50edef8b8512d618
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/ArmarIII-RightHand.xml
@@ -0,0 +1,519 @@
+<?xml version="1.0" encoding="UTF-8" ?>
+
+<Robot Type="ArmarIII RightHand" RootNode="Hand R Base">
+
+    <RobotNode name="Hand R Base">
+		<Child name="TCP R"/>
+		<Child name="GCP R"/>
+		<Child name="Marker R"/>
+		<Child name="right_hand_configuration_actual_float"/>
+		<Child name="Hand Palm 1 R"/>
+	</RobotNode>
+	
+	<RobotNode name="TCP R">
+		<Transform>
+			<Translation x="0" y="0" z="130"/>
+		</Transform>
+                <Visualization enable="false">
+                        <CoordinateAxis type="Inventor" enable="true" scaling="1"/>
+                </Visualization>
+	</RobotNode>
+	
+	<RobotNode name="GCP R">
+		<Transform>
+			<Translation X="-40" Y="20" Z="90"/>
+			<rollpitchyaw roll="0" pitch="-45" yaw="0" units="degree"/>
+		</Transform>
+	</RobotNode>
+	
+	<RobotNode name="Marker R">
+		<Transform>
+			<Translation x="-35" y="-45" z="65"/>
+		</Transform>
+		<Visualization enable="false">
+			<CoordinateAxis type="Inventor" enable="true" scaling="1"/>
+		</Visualization>
+	</RobotNode>
+	
+	<RobotNode name="right_hand_configuration_actual_float">
+                <!--Joint type="revolute">
+			<Axis x="0" y="0" z="1"/>
+			<Limits unit="degree" lo="-20" hi="20"/>
+                </Joint-->
+	</RobotNode>
+	
+	<RobotNode name="Hand Palm 1 R">
+
+		<Transform>
+			<Translation x="0" y="0" z="36"/>
+		</Transform>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/palm1_r.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">convexModel/palm1_r.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="800" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>	
+			
+		<Child name="Hand Palm 2 R"/>
+		<Child name="Thumb R"/>
+	</RobotNode>
+	
+	<RobotNode name="Hand Palm 2 R">
+		<Transform>
+			<Translation x="-8.7" y="-13.5" z="29.25"/>
+		</Transform>
+		<Joint type="revolute">
+                    <Axis x="0" y="-1" z="0"/>
+                    <Limits unit="degree" lo="-90" hi="90"/>
+                    <MaxVelocity unit="radian" value="1"/>
+                    <MaxAcceleration value="10"/>
+                    <MaxTorque value="10"/>
+                </Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/palm2_r.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">convexModel/palm2_r.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="800" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>		
+		
+		<Child name="Pinky R"/>
+		<Child name="Ring R"/>
+		<Child name="Middle R"/>
+		<Child name="Index R"/>
+	</RobotNode>
+	
+	<RobotNode name="Thumb R">
+		<Transform>
+			<Translation x="-48.9" y="0" z="29.25"/>
+		</Transform>
+		<Child name="Thumb R J0"/>
+	</RobotNode>
+	
+	<RobotNode name="Thumb R J0">
+		<Joint type="revolute">
+                    <Limits unit="degree" lo="0" hi="90"/>
+                    <Axis x="0" y="1" z="0"/>
+                    <MaxVelocity unit="radian" value="1"/>
+                    <MaxAcceleration value="10"/>
+                    <MaxTorque value="10"/>
+                </Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/thumb_r1.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">convexModel/thumb_r1.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+		
+		<Child name="Thumb R J1"/>
+	</RobotNode>
+	
+	<RobotNode name="Thumb R J1">
+        <Transform>
+			<Translation x="-40.2" y="0" z="0"/>
+		</Transform>
+		<Joint type="revolute">
+                    <Limits unit="degree" lo="0" hi="90"/>
+                    <Axis x="0" y="1" z="0"/>
+                    <MaxVelocity unit="radian" value="1"/>
+                    <MaxAcceleration value="10"/>
+                    <MaxTorque value="10"/>
+                </Joint>
+
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/thumb_r2.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">convexModel/thumb_r2.iv</File>
+		</CollisionModel>
+		
+	    	<Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+		<Child name="Thumb R Fingertip"/>
+	</RobotNode>
+
+	<RobotNode name="Thumb R Fingertip">
+		<Transform>
+			<Translation x="-50" y="0" z="0"/>
+		</Transform>
+                <Visualization enable="false">
+			<CoordinateAxis type="Inventor" enable="true" scaling="1"/>
+		</Visualization>
+	</RobotNode>
+	
+	<RobotNode name="Pinky R">
+		<Transform>
+			<Translation x="0" y="73" z="40.4"/>
+		</Transform>
+		
+		<Child name="Pinky R J0"/>
+	</RobotNode>
+	
+	<RobotNode name="Pinky R J0">
+		<Joint type="revolute">
+                    <Limits unit="degree" lo="0" hi="90"/>
+                    <Axis x="0" y="-1" z="0"/>
+                    <MaxVelocity unit="radian" value="1"/>
+                    <MaxAcceleration value="10"/>
+                    <MaxTorque value="10"/>
+                </Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/pinky_r1.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">convexModel/pinky_r1.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+		
+		<Child name="Pinky R J1"/>
+	</RobotNode>
+	
+	<RobotNode name="Pinky R J1">
+		<Transform>
+			<Translation x="0" y="0" z="40.2"/>
+		</Transform>
+		<Joint type="revolute">
+                    <Limits unit="degree" lo="0" hi="90"/>
+                    <Axis x="0" y="-1" z="0"/>
+                    <MaxVelocity unit="radian" value="1"/>
+                    <MaxAcceleration value="10"/>
+                    <MaxTorque value="10"/>
+		</Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/pinky_r2.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">convexModel/pinky_r2.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+	</RobotNode>
+	
+	<RobotNode name="Ring R">
+
+		<Transform>
+			<Translation x="0" y="51" z="40.4"/>
+		</Transform>
+		
+		<Child name="Ring R J0"/>
+	</RobotNode>
+	
+	<RobotNode name="Ring R J0">
+		<Joint type="revolute">
+                    <Limits unit="degree" lo="0" hi="90"/>
+                    <Axis x="0" y="-1" z="0"/>
+                    <MaxVelocity unit="radian" value="1"/>
+                    <MaxAcceleration value="10"/>
+                    <MaxTorque value="10"/>
+		</Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/ring_r1.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">convexModel/ring_r1.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+		
+		<Child name="Ring R J1"/>
+	</RobotNode>
+	
+	<RobotNode name="Ring R J1">
+    	<Transform>
+    		<Translation x="0" y="0" z="40.2"/>
+    	</Transform>
+		<Joint type="revolute">
+                    <Limits unit="degree" lo="0" hi="90"/>
+                    <Axis x="0" y="-1" z="0"/>
+                    <MaxVelocity unit="radian" value="1"/>
+                    <MaxAcceleration value="10"/>
+                    <MaxTorque value="10"/>
+		</Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/ring_r2.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">convexModel/ring_r2.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+	</RobotNode>
+	
+	<RobotNode name="Middle R">
+		<Transform>
+			<Translation x="0" y="27" z="40.4"/>
+		</Transform>
+
+		<Child name="Middle R J0"/>
+	</RobotNode>
+	
+	<RobotNode name="Middle R J0">
+		<Joint type="revolute">
+                    <Limits unit="degree" lo="0" hi="90"/>
+                    <Axis x="0" y="-1" z="0"/>
+                    <MaxVelocity unit="radian" value="1"/>
+                    <MaxAcceleration value="10"/>
+                    <MaxTorque value="10"/>
+                </Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/middle_r1.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">convexModel/middle_r1.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+		
+		<Child name="Middle R J1"/>
+	</RobotNode>
+	
+	<RobotNode name="Middle R J1">
+		<Transform>
+			<Translation x="0" y="0" z="40.2"/>
+		</Transform>
+		<Joint type="revolute">
+                    <Limits unit="degree" lo="0" hi="90"/>
+                    <Axis x="0" y="-1" z="0"/>
+                    <MaxVelocity unit="radian" value="1"/>
+                    <MaxAcceleration value="10"/>
+                    <MaxTorque value="10"/>
+                </Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/middle_r2.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">convexModel/middle_r2.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+		<Child name="Middle R Fingertip"/>
+	</RobotNode>
+	
+	<RobotNode name="Middle R Fingertip">
+		<Transform>
+			<Translation x="-5" y="0" z="40.2"/>
+		</Transform>
+                <Visualization enable="false">
+			<CoordinateAxis type="Inventor" enable="true" scaling="1"/>
+		</Visualization>
+	</RobotNode>
+	
+	<RobotNode name="Index R">
+		<Transform>
+			<Translation x="0" y="0" z="40.2"/>
+		</Transform>
+		
+		<Child name="Index R J0"/>
+	</RobotNode>
+	
+	<RobotNode name="Index R J0">
+		<Joint type="revolute">
+                    <Limits unit="degree" lo="0" hi="90"/>
+                    <Axis x="0" y="-1" z="0"/>
+                    <MaxVelocity unit="radian" value="1"/>
+                    <MaxAcceleration value="10"/>
+                    <MaxTorque value="10"/>
+                </Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/index_r1.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">convexModel/index_r1.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+		
+		<Child name="Index R J1"/>
+	</RobotNode>
+	
+	<RobotNode name="Index R J1">
+		<Transform>
+			<Translation x="0" y="0" z="40.2"/>
+		</Transform>
+		<Joint type="revolute">
+                    <Limits unit="degree" lo="0" hi="90"/>
+                    <Axis x="0" y="-1" z="0"/>
+                    <MaxVelocity unit="radian" value="1"/>
+                    <MaxAcceleration value="10"/>
+                    <MaxTorque value="10"/>
+                </Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/index_r2.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">convexModel/index_r2.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+		
+		<Child name="Index R Fingertip"/>
+	</RobotNode>
+	
+	<RobotNode name="Index R Fingertip">
+		<Transform>
+			<Translation x="-5" y="0" z="40.2"/>
+		</Transform>
+                <Visualization enable="false">
+			<CoordinateAxis type="Inventor" enable="true" scaling="1"/>
+		</Visualization>
+	</RobotNode>
+	
+	<RobotNodeSet name="RightHandColModel" kinematicRoot="Hand R Base" tcp="TCP R">
+		<Node name="Hand Palm 1 R"/>
+		<Node name="Hand Palm 2 R"/>
+		<Node name="Thumb R J0"/>
+		<Node name="Thumb R J1"/>
+		<Node name="Index R J0"/>
+		<Node name="Index R J1"/>
+		<Node name="Middle R J0"/>
+		<Node name="Middle R J1"/>
+		<Node name="Ring R J0"/>
+		<Node name="Ring R J1"/>
+		<Node name="Pinky R J0"/>
+		<Node name="Pinky R J1"/>
+	</RobotNodeSet>
+
+	
+	<RobotNodeSet name="RightHandJoints" kinematicRoot="Hand R Base" tcp="TCP R">
+		<Node name="Thumb R J0"/>
+		<Node name="Thumb R J1"/>
+		<Node name="Index R J0"/>
+		<Node name="Index R J1"/>
+		<Node name="Middle R J0"/>
+		<Node name="Middle R J1"/>
+		<Node name="Ring R J0"/>
+		<Node name="Ring R J1"/>
+		<Node name="Pinky R J0"/>
+		<Node name="Pinky R J1"/>
+	</RobotNodeSet>
+
+        <Endeffector name="TCP R" base="Hand R Base" tcp="TCP R" gcp="GCP R">
+	    <Preshape name="Open Preshape">
+	        <Node name="Thumb R J0" unit="radian" value="0"/>
+	        <Node name="Thumb R J1" unit="radian" value="0"/>
+	        <Node name="Index R J0" unit="radian" value="0"/>
+	        <Node name="Index R J1" unit="radian" value="0"/>
+	        <Node name="Middle R J0" unit="radian" value="0"/>
+	        <Node name="Middle R J1" unit="radian" value="0"/>
+	        <Node name="Ring R J0" unit="radian" value="0"/>
+	        <Node name="Ring R J1" unit="radian" value="0"/>
+	        <Node name="Pinky R J0" unit="radian" value="0"/>
+	        <Node name="Pinky R J1" unit="radian" value="0"/>
+	    </Preshape>
+            <Preshape name="Close Preshape">
+                <Node name="Thumb R J0" unit="radian" value="1"/>
+                <Node name="Thumb R J1" unit="radian" value="1"/>
+                <Node name="Index R J0" unit="radian" value="1"/>
+                <Node name="Index R J1" unit="radian" value="1"/>
+                <Node name="Middle R J0" unit="radian" value="1"/>
+                <Node name="Middle R J1" unit="radian" value="1"/>
+                <Node name="Ring R J0" unit="radian" value="1"/>
+                <Node name="Ring R J1" unit="radian" value="1"/>
+                <Node name="Pinky R J0" unit="radian" value="1"/>
+                <Node name="Pinky R J1" unit="radian" value="1"/>
+            </Preshape>
+            <Preshape name="Julia Preshape">
+                <Node name="Thumb R J0" unit="radian" value="0"/>
+                <Node name="Thumb R J1" unit="radian" value="0"/>
+                <Node name="Index R J0" unit="radian" value="0"/>
+                <Node name="Index R J1" unit="radian" value="0"/>
+                <Node name="Middle R J0" unit="radian" value="1.5"/>
+                <Node name="Middle R J1" unit="radian" value="1.5"/>
+                <Node name="Ring R J0" unit="radian" value="1.5"/>
+                <Node name="Ring R J1" unit="radian" value="1.5"/>
+                <Node name="Pinky R J0" unit="radian" value="0"/>
+                <Node name="Pinky R J1" unit="radian" value="0"/>
+            </Preshape>
+	    
+	    
+		<Static>
+			<Node name="Hand Palm 1 R"/>
+			<Node name="Hand Palm 2 R"/>
+		</Static>
+		<Actor name="Thumb Right">
+			<Node name="Thumb R J0" considerCollisions="Actors"/>
+			<Node name="Thumb R J1" considerCollisions="All"/>
+		</Actor>
+		<Actor name="Index Right">
+			<Node name="Index R J0" considerCollisions="Actors"/>
+			<Node name="Index R J1" considerCollisions="All"/>
+		</Actor>
+		<Actor name="Middle Right">
+			<Node name="Middle R J0" considerCollisions="Actors"/>
+			<Node name="Middle R J1" considerCollisions="All"/>
+		</Actor>
+		<Actor name="Ring Right">
+			<Node name="Ring R J0" considerCollisions="Actors"/>
+			<Node name="Ring R J1" considerCollisions="All"/>
+		</Actor>
+		<Actor name="Pinky Right">
+			<Node name="Pinky R J0" considerCollisions="Actors"/>
+			<Node name="Pinky R J1" considerCollisions="All"/>
+		</Actor>
+	</Endeffector>
+
+</Robot>
diff --git a/data/RobotAPI/robots/Armar3/ArmarIII-RightHand_minColModel.xml b/data/RobotAPI/robots/Armar3/ArmarIII-RightHand_minColModel.xml
new file mode 100644
index 0000000000000000000000000000000000000000..06a8d148da39a248a55ff7e2e547ec783021cd30
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/ArmarIII-RightHand_minColModel.xml
@@ -0,0 +1,437 @@
+<?xml version="1.0" encoding="UTF-8" ?>
+
+<Robot Type="ArmarIII RightHand" RootNode="Hand R Base">
+
+
+    <RobotNode name="Hand R Base">
+		<Child name="TCP R"/>
+		<Child name="GCP R"/>
+		<Child name="Hand Palm 1 R"/>
+	</RobotNode>
+	
+	<RobotNode name="TCP R">
+		<Joint type="fixed">
+			<PreJointTransform>
+				<Transform>
+					<Translation x="0" y="0" z="130"/>
+				</Transform>
+			</PreJointTransform>
+		</Joint>
+	</RobotNode>
+	
+	<RobotNode name="GCP R">
+		<Joint type="fixed">
+			<PreJointTransform>
+				<Transform>
+					<Translation X="-40" Y="20" Z="90"/>
+					<rollpitchyaw roll="0" pitch="-45" yaw="0" units="degree"/>
+				</Transform>
+			</PreJointTransform>
+		</Joint>
+	</RobotNode>
+	
+	<RobotNode name="Hand Palm 1 R">
+		<Joint type="fixed">
+			<PreJointTransform>
+				<Transform>
+					<Translation x="0" y="0" z="36"/>
+				</Transform>
+			</PreJointTransform>
+		</Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/palm1_r.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">collisionModel/palm1_r.iv</File>
+		</CollisionModel>
+	    <Physics>
+			<Mass value="800" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>		
+		<Child name="Hand Palm 2 R"/>
+		<Child name="Thumb R"/>
+	</RobotNode>
+	
+	<RobotNode name="Hand Palm 2 R">
+		<Joint type="revolute">
+			<PreJointTransform>
+				<Transform>
+					<Translation x="-8.7" y="-13.5" z="29.25"/>
+				</Transform>
+			</PreJointTransform>
+			<Axis x="0" y="-1" z="0"/>
+			<Limits unit="degree" lo="-90" hi="90"/>
+		</Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/palm2_r.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">collisionModel/palm2_r.iv</File>
+		</CollisionModel>
+	    <Physics>
+			<Mass value="800" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>		
+		<Child name="Pinky R"/>
+		<Child name="Ring R"/>
+		<Child name="Middle R"/>
+		<Child name="Index R"/>
+	</RobotNode>
+	
+	<RobotNode name="Thumb R">
+		<Joint type="fixed">
+			<PreJointTransform>
+				<Transform>
+					<Translation x="-48.9" y="0" z="29.25"/>
+				</Transform>
+			</PreJointTransform>
+		</Joint>
+		<Child name="Thumb R J0"/>
+	</RobotNode>
+	
+	<RobotNode name="Thumb R J0">
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<Axis x="0" y="1" z="0"/>
+		</Joint>
+		
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/thumb_r1.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">collisionModel/thumb_r1.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+		
+		<Child name="Thumb R J1"/>
+	</RobotNode>
+	
+	<RobotNode name="Thumb R J1">
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<PreJointTransform>
+				<Transform>
+					<Translation x="-40.2" y="0" z="0"/>
+				</Transform>
+			</PreJointTransform>
+			<Axis x="0" y="1" z="0"/>
+		</Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/thumb_r2.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">collisionModel/thumb_r2.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+	</RobotNode>
+	
+	<RobotNode name="Pinky R">
+		<Joint type="fixed">
+			<PreJointTransform>
+				<Transform>
+					<Translation x="0" y="73" z="40.4"/>
+				</Transform>
+			</PreJointTransform>
+		</Joint>
+		
+		<Child name="Pinky R J0"/>
+	</RobotNode>
+	
+	<RobotNode name="Pinky R J0">
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<Axis x="0" y="-1" z="0"/>
+		</Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/pinky_r1.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">collisionModel/pinky_r1.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+		
+		<Child name="Pinky R J1"/>
+	</RobotNode>
+	
+	<RobotNode name="Pinky R J1">
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<PreJointTransform>
+				<Transform>
+					<Translation x="0" y="0" z="40.2"/>
+				</Transform>
+			</PreJointTransform>
+			<Axis x="0" y="-1" z="0"/>
+		</Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/pinky_r2.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">collisionModel/pinky_r2.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+	</RobotNode>
+	
+	<RobotNode name="Ring R">
+		<Joint type="fixed">
+			<PreJointTransform>
+				<Transform>
+					<Translation x="0" y="51" z="40.4"/>
+				</Transform>
+			</PreJointTransform>
+		</Joint>
+		
+		<Child name="Ring R J0"/>
+	</RobotNode>
+	
+	<RobotNode name="Ring R J0">
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<Axis x="0" y="-1" z="0"/>
+		</Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/ring_r1.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">collisionModel/ring_r1.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+		
+		<Child name="Ring R J1"/>
+	</RobotNode>
+	
+	<RobotNode name="Ring R J1">
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<PreJointTransform>
+				<Transform>
+					<Translation x="0" y="0" z="40.2"/>
+				</Transform>
+			</PreJointTransform>
+			<Axis x="0" y="-1" z="0"/>
+		</Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/ring_r2.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">collisionModel/ring_r2.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+	</RobotNode>
+	
+	<RobotNode name="Middle R">
+		<Joint type="fixed">
+			<PreJointTransform>
+				<Transform>
+					<Translation x="0" y="27" z="40.4"/>
+				</Transform>
+			</PreJointTransform>
+		</Joint>
+		
+		<Child name="Middle R J0"/>
+	</RobotNode>
+	
+	<RobotNode name="Middle R J0">
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<Axis x="0" y="-1" z="0"/>
+		</Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/middle_r1.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">collisionModel/middle_r1.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+		
+		<Child name="Middle R J1"/>
+	</RobotNode>
+	
+	<RobotNode name="Middle R J1">
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<PreJointTransform>
+				<Transform>
+					<Translation x="0" y="0" z="40.2"/>
+				</Transform>
+			</PreJointTransform>
+			<Axis x="0" y="-1" z="0"/>
+		</Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/middle_r2.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">collisionModel/middle_r2.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+	</RobotNode>
+	
+	<RobotNode name="Index R">
+		<Joint type="fixed">
+			<PreJointTransform>
+				<Transform>
+					<Translation x="0" y="0" z="40.2"/>
+				</Transform>
+			</PreJointTransform>
+		</Joint>
+		
+		<Child name="Index R J0"/>
+	</RobotNode>
+	
+	<RobotNode name="Index R J0">
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<Axis x="0" y="-1" z="0"/>
+		</Joint>
+		
+		<Visualization enable="true">
+			<File type="Inventor">fullmodel/index_r1.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">collisionModel/index_r1.iv</File>
+		</CollisionModel>
+		
+	    <Physics>
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+		
+		<Child name="Index R J1"/>
+	</RobotNode>
+	
+	<RobotNode name="Index R J1">
+		<Joint type="revolute">
+			<Limits unit="degree" lo="0" hi="180"/>
+			<PreJointTransform>
+				<Transform>
+					<Translation x="0" y="0" z="40.2"/>
+				</Transform>
+			</PreJointTransform>
+			<Axis x="0" y="-1" z="0"/>
+		</Joint>
+		
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/index_r2.iv</File>
+		</Visualization>
+		
+		<CollisionModel>
+			<File type="Inventor">collisionModel/index_r2.iv</File>
+		</CollisionModel>
+	    <Physics>
+	        
+			<Mass value="500" unit="g"/>
+			<CoM location="VisualizationBBoxCenter"/>
+		</Physics>
+	</RobotNode>
+	
+	<RobotNodeSet name="RightHandColModel" kinematicRoot="Hand R Base" tcp="TCP R">
+		<Node name="Hand Palm 1 R"/>
+		<Node name="Hand Palm 2 R"/>
+		<Node name="Thumb R J0"/>
+		<Node name="Thumb R J1"/>
+		<Node name="Index R J0"/>
+		<Node name="Index R J1"/>
+		<Node name="Middle R J0"/>
+		<Node name="Middle R J1"/>
+		<Node name="Ring R J0"/>
+		<Node name="Ring R J1"/>
+		<Node name="Pinky R J0"/>
+		<Node name="Pinky R J1"/>
+	</RobotNodeSet>
+
+        <Endeffector name="TCP R" base="Hand R Base" tcp="TCP R" gcp="GCP R">
+	    <Preshape name="Grasp Preshape">
+	        <Node name="Thumb R J0" unit="radian" value="0"/>
+	        <Node name="Thumb R J1" unit="radian" value="0"/>
+	        <Node name="Index R J0" unit="radian" value="0"/>
+	        <Node name="Index R J1" unit="radian" value="0"/>
+	        <Node name="Middle R J0" unit="radian" value="0"/>
+	        <Node name="Middle R J1" unit="radian" value="0"/>
+	        <Node name="Ring R J0" unit="radian" value="0"/>
+	        <Node name="Ring R J1" unit="radian" value="0"/>
+	        <Node name="Pinky R J0" unit="radian" value="0"/>
+	        <Node name="Pinky R J1" unit="radian" value="0"/>
+	    </Preshape>
+	    
+	    
+		<Static>
+			<Node name="Hand Palm 1 R"/>
+			<Node name="Hand Palm 2 R"/>
+		</Static>
+		<Actor name="Thumb Right">
+			<Node name="Thumb R J0" considerCollisions="Actors"/>
+			<Node name="Thumb R J1" considerCollisions="All"/>
+		</Actor>
+		<Actor name="Index Right">
+			<Node name="Index R J0" considerCollisions="Actors"/>
+			<Node name="Index R J1" considerCollisions="All"/>
+		</Actor>
+		<Actor name="Middle Right">
+			<Node name="Middle R J0" considerCollisions="Actors"/>
+			<Node name="Middle R J1" considerCollisions="All"/>
+		</Actor>
+		<Actor name="Ring Right">
+			<Node name="Ring R J0" considerCollisions="Actors"/>
+			<Node name="Ring R J1" considerCollisions="All"/>
+		</Actor>
+		<Actor name="Pinky Right">
+			<Node name="Pinky R J0" considerCollisions="Actors"/>
+			<Node name="Pinky R J1" considerCollisions="All"/>
+		</Actor>
+	</Endeffector>
+
+</Robot>
diff --git a/data/RobotAPI/robots/Armar3/ArmarIII-WithPlatform.xml b/data/RobotAPI/robots/Armar3/ArmarIII-WithPlatform.xml
new file mode 100644
index 0000000000000000000000000000000000000000..b8575f65b58bcfb7b56db0b7e42e0f383062b953
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/ArmarIII-WithPlatform.xml
@@ -0,0 +1,353 @@
+<?xml version="1.0" encoding="UTF-8" ?>
+
+<Robot Type="Armar3" RootNode="Armar3_Base">
+	
+	<RobotNode name="Armar3_Base">
+		<Visualization enable="true">
+			<CoordinateAxis  type="Inventor" enable="false" scaling="20"/>
+		</Visualization>
+		<Child name="Dummy_Platform"/>
+		<!--Child name="Platform"/-->
+	</RobotNode>
+	
+	<RobotNode name="Dummy_Platform">
+        <Transform>
+            <DH a="0" d="0" theta="0" alpha="-90" units="degree"/>
+        </Transform>
+		<!--<Joint type="fixed">
+			<DH a="0" d="0" theta="0" alpha="-90" units="degree"/>
+		</Joint>-->
+		<Child name="X_Platform"/>
+	</RobotNode>
+	
+	<RobotNode name="X_Platform">
+        <Transform>
+            <DH a="0" d="0" theta="90" alpha="0" units="degree"/>
+        </Transform>
+		<Joint type="prismatic">
+            <TranslationDirection x="0" y="0" z="1"/>
+            <Limits unit="mm" lo="-10000" hi="10000"/>
+		</Joint>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+		</Visualization>
+		<Child name="Y_Platform"/>
+	</RobotNode>
+	
+	<RobotNode name="Y_Platform">
+        <Transform>
+            <DH a="0" d="0" theta="-90" alpha="0" units="degree"/>
+            <DH a="0" d="0" theta="0" alpha="-90" units="degree"/>
+        </Transform>
+		<Joint type="prismatic">
+            <TranslationDirection x="0" y="0" z="1"/>
+            <Limits unit="mm" lo="-10000" hi="10000"/>
+		</Joint>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+		</Visualization>
+		<Child name="Yaw_Platform"/>
+	</RobotNode>
+	
+	<RobotNode name="Yaw_Platform">
+        <Transform>
+            <DH a="0" d="0" theta="-90" alpha="0" units="degree"/>
+            <DH a="0" d="0" theta="0" alpha="90" units="degree"/>
+        </Transform>
+		<Joint type="revolute">
+			<axis x="0" y="0" z="1"/>
+            <Limits unit="degree" lo="-360" hi="360"/>
+		</Joint>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+		</Visualization>
+		<Child name="Platform"/>
+	</RobotNode>
+	
+	<RobotNode name="Platform">  <!-- visualization via 3D-model at the very end of the kinematic chain-->
+		<Joint type="fixed"/>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/platform.iv</File>
+		</Visualization>
+		<Physics>
+            <CoM location="Joint" x="0" y="0" z="200"/>
+            <Mass value="100" units="kg" />
+        </Physics>
+		<CollisionModel>
+			<File type="Inventor">convexModel/platform.iv</File>
+		</CollisionModel>
+		<Child name="Hip Pitch"/>
+	</RobotNode>
+
+	<RobotNode name="Hip Pitch">
+            <Transform>
+                <Translation x="0" y="158" z="890"/>
+            </Transform>
+            <Joint type="revolute">
+            <Axis x="1" y="0" z="0"/>
+            <Limits unit="degree" lo="-45" hi="45"/>
+        </Joint>
+
+        <Visualization enable="true">
+            <CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+            <File type="Inventor">fullmodel/platform_pitch_link.iv</File>
+        </Visualization>
+        <Physics>
+            <Mass value="10" units="kg" />
+        </Physics>
+        <CollisionModel>
+            <File type="Inventor">convexModel/platform_pitch_link.iv</File>
+        </CollisionModel>
+        <Child name="Hip Roll"/>
+	</RobotNode>
+	
+	<RobotNode name="Hip Roll">
+		<Joint type="revolute">
+			<Axis x="0" y="1" z="0"/>
+			<Limits unit="degree" lo="-45" hi="45"/>
+		</Joint>
+
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/platform_roll_link.iv</File>
+		</Visualization>
+		<Physics>
+            <Mass value="10" units="kg" />
+            <IgnoreCollision name="Platform"/>
+        </Physics>
+		<CollisionModel>
+			<File type="Inventor">convexModel/platform_roll_link.iv</File>
+		</CollisionModel>
+		<Child name="Hip Yaw"/>
+	</RobotNode>
+	
+	<RobotNode name="Hip Yaw">
+		<Joint type="revolute">
+			<Axis x="0" y="0" z="1"/>
+			<Limits unit="degree" lo="-45" hi="45"/>
+		</Joint>
+		<Physics>
+            <CoM location="VisualizationBBoxCenter"/>
+            <Mass value="15.415" units="kg" />
+            <IgnoreCollision name="Hip Pitch"/>
+            <IgnoreCollision name="Platform"/>
+        </Physics>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/torso.iv</File>
+		</Visualization>
+		<CollisionModel>
+			<File type="Inventor">convexModel/torso.iv</File>
+		</CollisionModel>
+		<Child name="Center of Arms"/>
+	</RobotNode>
+	
+	<RobotNode name="Center of Arms">
+        <Transform>
+            <Translation x="0" y="-35" z="485"/>
+        </Transform>
+        <Visualization enable="true">
+            <CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+        </Visualization>
+        
+        <Child name="TrafoToHead"/>
+        <Child name="TrafoToLeftArm"/>
+        <Child name="TrafoToRightArm"/>
+	</RobotNode>
+	
+	<RobotNode name="TrafoToHead">
+        <Transform>
+            <Translation x="0" y="0" z="118"/>
+        </Transform>
+        <Visualization enable="true">
+            <CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+        </Visualization>
+        
+        <ChildFromRobot>
+            <File importEEF="true">ArmarIII-Head.xml</File>
+        </ChildFromRobot>
+	</RobotNode>
+	
+	<RobotNode name="TrafoToLeftArm">
+        <Transform>
+            <Translation x="-232" y="0" z="0"/>
+        </Transform>
+        <Visualization enable="true">
+            <CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+        </Visualization>
+        
+        <ChildFromRobot>
+            <File importEEF="true">ArmarIII-LeftArm.xml</File>
+        </ChildFromRobot>
+	</RobotNode>
+	
+	<RobotNode name="TrafoToRightArm">
+        <Transform>
+            <Translation x="232" y="0" z="0"/>
+        </Transform>
+        <Visualization enable="true">
+            <CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+        </Visualization>
+        
+        <ChildFromRobot>
+            <File importEEF="true">ArmarIII-RightArm.xml</File>
+        </ChildFromRobot>
+	</RobotNode>
+	
+	<RobotNodeSet name="Torso" kinematicRoot="Platform">
+		<Node name="Hip Pitch"/>
+		<Node name="Hip Roll"/>
+		<Node name="Hip Yaw"/>
+	</RobotNodeSet>
+	
+	<RobotNodeSet name="TorsoHeadColModel">
+		<Node name="Hip Yaw"/>
+		<Node name="Head_Tilt"/>
+	</RobotNodeSet>
+	
+	<RobotNodeSet name="PlatformTorsoColModel">
+		<Node name="Platform"/>
+		<Node name="Hip Yaw"/>
+	</RobotNodeSet>
+	
+	<RobotNodeSet name="PlatformTorsoHeadColModel">
+		<Node name="Platform"/>
+		<Node name="Hip Yaw"/>
+		<Node name="Head_Tilt"/>
+	</RobotNodeSet>
+	
+	<RobotNodeSet name="TorsoLeftArm" kinematicRoot="Platform" tcp="TCP L">
+		<Node name="Hip Pitch"/>
+		<Node name="Hip Roll"/>
+		<Node name="Hip Yaw"/>
+		<Node name="Shoulder 1 L"/>
+		<Node name="Shoulder 2 L"/>
+		<Node name="Upperarm L"/>
+		<Node name="Elbow L"/>
+		<Node name="Underarm L"/>
+		<Node name="Wrist 1 L"/>
+		<Node name="Wrist 2 L"/>
+	</RobotNodeSet>	
+	
+	<RobotNodeSet name="TorsoRightArm" kinematicRoot="Platform" tcp="TCP R">
+		<Node name="Hip Pitch"/>
+		<Node name="Hip Roll"/>
+		<Node name="Hip Yaw"/>
+		<Node name="Shoulder 1 R"/>
+		<Node name="Shoulder 2 R"/>
+		<Node name="Upperarm R"/>
+		<Node name="Elbow R"/>
+		<Node name="Underarm R"/>
+		<Node name="Wrist 1 R"/>
+		<Node name="Wrist 2 R"/>
+	</RobotNodeSet>
+	
+	
+	<RobotNodeSet name="TorsoBothArms" kinematicRoot="Platform">
+		<Node name="Hip Pitch"/>
+		<Node name="Hip Roll"/>
+		<Node name="Hip Yaw"/>
+		<Node name="Shoulder 1 L"/>
+		<Node name="Shoulder 2 L"/>
+		<Node name="Upperarm L"/>
+		<Node name="Elbow L"/>
+		<Node name="Underarm L"/>
+		<Node name="Wrist 1 L"/>
+		<Node name="Wrist 2 L"/>
+		<Node name="Shoulder 1 R"/>
+		<Node name="Shoulder 2 R"/>
+		<Node name="Upperarm R"/>
+		<Node name="Elbow R"/>
+		<Node name="Underarm R"/>
+		<Node name="Wrist 1 R"/>
+		<Node name="Wrist 2 R"/>
+	</RobotNodeSet>	
+	
+	<RobotNodeSet name="Robot" kinematicRoot="Platform">
+		<Node name="Neck_1_Pitch"/>
+		<Node name="Neck_2_Roll"/>
+		<Node name="Neck_3_Yaw"/>
+		<Node name="Head_Tilt"/>
+		<Node name="Cameras"/>
+		<Node name="Eye_Left"/>
+		<Node name="Eye_Right"/>
+		<Node name="Hip Pitch"/>
+		<Node name="Hip Roll"/>
+		<Node name="Hip Yaw"/>
+		<Node name="Shoulder 1 L"/>
+		<Node name="Shoulder 2 L"/>
+		<Node name="Upperarm L"/>
+		<Node name="Elbow L"/>
+		<Node name="Underarm L"/>
+		<Node name="Wrist 1 L"/>
+		<Node name="Wrist 2 L"/>
+		<Node name="Shoulder 1 R"/>
+		<Node name="Shoulder 2 R"/>
+		<Node name="Upperarm R"/>
+		<Node name="Elbow R"/>
+		<Node name="Underarm R"/>
+		<Node name="Wrist 1 R"/>
+		<Node name="Wrist 2 R"/>
+		<Node name="Hand Palm 1 L"/>
+		<Node name="Hand Palm 2 L"/>
+		<Node name="Thumb L J0"/>
+		<Node name="Thumb L J1"/>
+		<Node name="Index L J0"/>
+		<Node name="Index L J1"/>
+		<Node name="Middle L J0"/>
+		<Node name="Middle L J1"/>
+		<Node name="Ring L J0"/>
+		<Node name="Ring L J1"/>
+		<Node name="Pinky L J0"/>
+		<Node name="Pinky L J1"/>
+		<Node name="Hand Palm 1 R"/>
+		<Node name="Hand Palm 2 R"/>
+		<Node name="Thumb R J0"/>
+		<Node name="Thumb R J1"/>
+		<Node name="Index R J0"/>
+		<Node name="Index R J1"/>
+		<Node name="Middle R J0"/>
+		<Node name="Middle R J1"/>
+		<Node name="Ring R J0"/>
+		<Node name="Ring R J1"/>
+		<Node name="Pinky R J0"/>
+		<Node name="Pinky R J1"/>
+	</RobotNodeSet>	
+
+	<RobotNodeSet name="PlatformYawTorsoLeftArm" kinematicRoot="Armar3_Base" tcp="TCP L">
+	    <Node name="Yaw_Platform"/>
+		<Node name="Hip Pitch"/>
+		<Node name="Hip Roll"/>
+		<Node name="Hip Yaw"/>
+		<Node name="Shoulder 1 L"/>
+		<Node name="Shoulder 2 L"/>
+		<Node name="Upperarm L"/>
+		<Node name="Elbow L"/>
+		<Node name="Underarm L"/>
+		<Node name="Wrist 1 L"/>
+		<Node name="Wrist 2 L"/>
+	</RobotNodeSet>	
+
+	<RobotNodeSet name="PlatformYawTorsoRightArm" kinematicRoot="Armar3_Base" tcp="TCP R">
+		<Node name="Yaw_Platform"/>
+		<Node name="Hip Pitch"/>
+		<Node name="Hip Roll"/>
+		<Node name="Hip Yaw"/>
+		<Node name="Shoulder 1 R"/>
+		<Node name="Shoulder 2 R"/>
+		<Node name="Upperarm R"/>
+		<Node name="Elbow R"/>
+		<Node name="Underarm R"/>
+		<Node name="Wrist 1 R"/>
+		<Node name="Wrist 2 R"/>
+	</RobotNodeSet>
+	
+    <RobotNodeSet name="Platform">
+        <Node name="X_Platform"/>
+        <Node name="Y_Platform"/>
+        <Node name="Yaw_Platform"/>
+    </RobotNodeSet>
+	
+
+</Robot>
diff --git a/data/RobotAPI/robots/Armar3/ArmarIII.xml b/data/RobotAPI/robots/Armar3/ArmarIII.xml
new file mode 100644
index 0000000000000000000000000000000000000000..ecec3bf1dc53cea37588230ecf0b3ae1b5b1946c
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/ArmarIII.xml
@@ -0,0 +1,395 @@
+<?xml version="1.0" encoding="UTF-8" ?>
+
+<Robot Type="Armar3" RootNode="Armar3_Base">
+	
+	<RobotNode name="Armar3_Base">
+		<Visualization enable="true">
+			<CoordinateAxis  type="Inventor" enable="false" scaling="20"/>
+		</Visualization>
+		<Child name="Dummy_Platform"/>
+		<!--Child name="Platform"/-->
+	</RobotNode>
+	
+	<RobotNode name="Dummy_Platform">
+		<Transform>
+			<DH a="0" d="0" theta="0" alpha="-90" unitsangle="degree" unitslength="mm"/>
+		</Transform>
+		<Child name="X_Platform"/>
+	</RobotNode>
+	
+	<RobotNode name="X_Platform">
+		<Transform>
+			<DH a="0" d="0" theta="90" alpha="-90" unitsangle="degree" unitslength="mm"/>
+            <!--Limits unit="mm" lo="-10000" hi="10000"/-->
+		</Transform>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+		</Visualization>
+		<Child name="Y_Platform"/>
+	</RobotNode>
+	
+	<RobotNode name="Y_Platform">
+		<Transform>
+			<DH a="0" d="0" theta="-90" alpha="90" unitsangle="degree" unitslength="mm"/>
+            <!--Limits unit="mm" lo="-10000" hi="10000"/-->
+		</Transform>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+		</Visualization>
+		<Child name="Yaw_Platform"/>
+	</RobotNode>
+	
+	<RobotNode name="Yaw_Platform">
+	    <Transform>
+			<DH a="0" d="0" theta="-90" alpha="0" unitsangle="degree" unitslength="mm"/>
+            <!--Limits unit="mm" lo="-10000" hi="10000"/-->
+		</Transform>
+		<Joint type="revolute">
+			<axis x="0" y="0" z="1"/>
+			<Limits unit="degree" lo="-360" hi="360"/>
+            <MaxVelocity unit="radian" value="1"/>
+            <MaxAcceleration value="10"/>
+            <MaxTorque value="3000"/>
+        </Joint>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+		</Visualization>
+		<Child name="Platform"/>
+	</RobotNode>
+	
+	<RobotNode name="Platform">  <!-- visualization via 3D-model at the very end of the kinematic chain-->
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/platform.iv</File>
+		</Visualization>
+		<Physics>
+            <CoM location="Joint" x="0" y="0" z="200"/>
+            <Mass value="100" units="kg" />
+        </Physics>
+		<CollisionModel>
+			<File type="Inventor">convexModel/platform.iv</File>
+		</CollisionModel>
+		<Child name="Hip Pitch"/>
+	</RobotNode>
+
+	<RobotNode name="Hip Pitch">
+			<Transform>
+				<Translation x="0" y="158" z="890" units='mm'/>
+			</Transform>
+                <Joint type="revolute">
+			<Axis x="1" y="0" z="0"/>
+			<Limits unit="degree" lo="-45" hi="45"/>
+                    <MaxVelocity unit="radian" value="1"/>
+                    <MaxAcceleration value="10"/>
+                    <MaxTorque value="3000"/>
+                </Joint>
+
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/platform_pitch_link.iv</File>
+		</Visualization>
+		<Physics>
+            <Mass value="10" units="kg" />
+        </Physics>
+		<CollisionModel>
+			<File type="Inventor">convexModel/platform_pitch_link.iv</File>
+		</CollisionModel>
+		<Child name="Hip Roll"/>
+	</RobotNode>
+	
+	<RobotNode name="Hip Roll">
+		<Joint type="revolute">
+			<Axis x="0" y="1" z="0"/>
+			<Limits unit="degree" lo="-45" hi="45"/>
+                    <MaxVelocity unit="radian" value="1"/>
+                    <MaxAcceleration value="10"/>
+                    <MaxTorque value="3000"/>
+                </Joint>
+
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/platform_roll_link.iv</File>
+		</Visualization>
+		<Physics>
+            <Mass value="10" units="kg" />
+            <IgnoreCollision name="Platform"/>
+        </Physics>
+		<CollisionModel>
+			<File type="Inventor">convexModel/platform_roll_link.iv</File>
+		</CollisionModel>
+		<Child name="Hip Yaw"/>
+	</RobotNode>
+	
+	<RobotNode name="Hip Yaw">
+		<Joint type="revolute">
+			<Axis x="0" y="0" z="1"/>
+			<Limits unit="degree" lo="-45" hi="45"/>
+                    <MaxVelocity unit="radian" value="1"/>
+                    <MaxAcceleration value="10"/>
+                    <MaxTorque value="3000"/>
+                </Joint>
+		<Physics>
+            <CoM location="VisualizationBBoxCenter"/>
+            <Mass value="15.415" units="kg" />
+            <IgnoreCollision name="Hip Pitch"/>
+            <IgnoreCollision name="Platform"/>
+        </Physics>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/torso.iv</File>
+		</Visualization>
+		<CollisionModel>
+			<File type="Inventor">convexModel/torso.iv</File>
+		</CollisionModel>
+		<Child name="Center of Arms"/>
+	</RobotNode>
+	
+	<RobotNode name="Center of Arms">
+		<Transform>
+			<Translation x="0" y="-35" z="485" units='mm'/>
+		</Transform>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+		</Visualization>
+		
+		<Child name="TrafoToHead"/>
+		<Child name="TrafoToLeftArm"/>
+		<Child name="TrafoToRightArm"/>
+	</RobotNode>
+	
+	<RobotNode name="TrafoToHead">
+		<Transform>
+			<Translation x="0" y="0" z="118" units='mm'/>
+		</Transform>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+		</Visualization>
+		
+		<ChildFromRobot>
+			<File importEEF="true">ArmarIII-Head.xml</File>
+		</ChildFromRobot>
+	</RobotNode>
+	
+	<RobotNode name="TrafoToLeftArm">
+		<Transform>
+			<Translation x="-232" y="0" z="0" units='mm'/>
+		</Transform>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+		</Visualization>
+		
+		<ChildFromRobot>
+			<File importEEF="true">ArmarIII-LeftArm.xml</File>
+		</ChildFromRobot>
+	</RobotNode>
+	
+	<RobotNode name="TrafoToRightArm">
+		<Transform>
+			<Translation x="232" y="0" z="0" units='mm'/>
+		</Transform>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+		</Visualization>
+		
+		<ChildFromRobot>
+			<File importEEF="true">ArmarIII-RightArm.xml</File>
+		</ChildFromRobot>
+	</RobotNode>
+	
+	<RobotNodeSet name="Torso" kinematicRoot="Platform">
+		<Node name="Hip Pitch"/>
+		<Node name="Hip Roll"/>
+		<Node name="Hip Yaw"/>
+	</RobotNodeSet>
+	
+	<RobotNodeSet name="TorsoHeadColModel">
+		<Node name="Hip Yaw"/>
+		<Node name="Head_Tilt"/>
+	</RobotNodeSet>
+	
+	<RobotNodeSet name="PlatformTorsoColModel">
+		<Node name="Platform"/>
+		<Node name="Hip Yaw"/>
+	</RobotNodeSet>
+	
+	<RobotNodeSet name="PlatformTorsoHeadColModel">
+		<Node name="Platform"/>
+		<Node name="Hip Yaw"/>
+		<Node name="Head_Tilt"/>
+	</RobotNodeSet>
+	
+	<RobotNodeSet name="TorsoLeftArm" kinematicRoot="Platform" tcp="TCP L">
+		<Node name="Hip Pitch"/>
+		<Node name="Hip Roll"/>
+		<Node name="Hip Yaw"/>
+		<Node name="Shoulder 1 L"/>
+		<Node name="Shoulder 2 L"/>
+		<Node name="Upperarm L"/>
+		<Node name="Elbow L"/>
+		<Node name="Underarm L"/>
+		<Node name="Wrist 1 L"/>
+		<Node name="Wrist 2 L"/>
+	</RobotNodeSet>	
+	
+	<RobotNodeSet name="HipYawLeftArm" kinematicRoot="Platform" tcp="TCP L">
+		<Node name="Hip Yaw"/>
+		<Node name="Shoulder 1 L"/>
+		<Node name="Shoulder 2 L"/>
+		<Node name="Upperarm L"/>
+		<Node name="Elbow L"/>
+		<Node name="Underarm L"/>
+		<Node name="Wrist 1 L"/>
+		<Node name="Wrist 2 L"/>
+	</RobotNodeSet>	
+	
+	<RobotNodeSet name="TorsoRightArm" kinematicRoot="Platform" tcp="TCP R">
+		<Node name="Hip Pitch"/>
+		<Node name="Hip Roll"/>
+		<Node name="Hip Yaw"/>
+		<Node name="Shoulder 1 R"/>
+		<Node name="Shoulder 2 R"/>
+		<Node name="Upperarm R"/>
+		<Node name="Elbow R"/>
+		<Node name="Underarm R"/>
+		<Node name="Wrist 1 R"/>
+		<Node name="Wrist 2 R"/>
+	</RobotNodeSet>
+	
+	<RobotNodeSet name="TorsoRightArmIndexFingertip" kinematicRoot="Platform" tcp="Index R Fingertip">
+		<Node name="Hip Pitch"/>
+		<Node name="Hip Roll"/>
+		<Node name="Hip Yaw"/>
+		<Node name="Shoulder 1 R"/>
+		<Node name="Shoulder 2 R"/>
+		<Node name="Upperarm R"/>
+		<Node name="Elbow R"/>
+		<Node name="Underarm R"/>
+		<Node name="Wrist 1 R"/>
+		<Node name="Wrist 2 R"/>
+	</RobotNodeSet>
+	
+	<RobotNodeSet name="HipYawRightArm" kinematicRoot="Platform" tcp="TCP R">
+		<Node name="Hip Yaw"/>
+		<Node name="Shoulder 1 R"/>
+		<Node name="Shoulder 2 R"/>
+		<Node name="Upperarm R"/>
+		<Node name="Elbow R"/>
+		<Node name="Underarm R"/>
+		<Node name="Wrist 1 R"/>
+		<Node name="Wrist 2 R"/>
+	</RobotNodeSet>
+	
+	
+    <RobotNodeSet name="TorsoBothArms" kinematicRoot="Platform">
+        <Node name="Hip Pitch"/>
+        <Node name="Hip Roll"/>
+        <Node name="Hip Yaw"/>
+        <Node name="Shoulder 1 L"/>
+        <Node name="Shoulder 2 L"/>
+        <Node name="Upperarm L"/>
+        <Node name="Elbow L"/>
+        <Node name="Underarm L"/>
+        <Node name="Wrist 1 L"/>
+        <Node name="Wrist 2 L"/>
+        <Node name="Shoulder 1 R"/>
+        <Node name="Shoulder 2 R"/>
+        <Node name="Upperarm R"/>
+        <Node name="Elbow R"/>
+        <Node name="Underarm R"/>
+        <Node name="Wrist 1 R"/>
+        <Node name="Wrist 2 R"/>
+    </RobotNodeSet>
+
+    <RobotNodeSet name="Robot" kinematicRoot="Platform">
+		<Node name="Neck_1_Pitch"/>
+		<Node name="Neck_2_Roll"/>
+		<Node name="Neck_3_Yaw"/>
+		<Node name="Head_Tilt"/>
+		<Node name="Cameras"/>
+		<Node name="Eye_Left"/>
+		<Node name="Eye_Right"/>
+		<Node name="VirtualCentralGaze"/>
+		<Node name="Hip Pitch"/>
+		<Node name="Hip Roll"/>
+		<Node name="Hip Yaw"/>
+		<Node name="Shoulder 1 L"/>
+		<Node name="Shoulder 2 L"/>
+		<Node name="Upperarm L"/>
+		<Node name="Elbow L"/>
+		<Node name="Underarm L"/>
+		<Node name="Wrist 1 L"/>
+		<Node name="Wrist 2 L"/>
+		<Node name="Shoulder 1 R"/>
+		<Node name="Shoulder 2 R"/>
+		<Node name="Upperarm R"/>
+		<Node name="Elbow R"/>
+		<Node name="Underarm R"/>
+		<Node name="Wrist 1 R"/>
+		<Node name="Wrist 2 R"/>
+		<Node name="Hand Palm 1 L"/>
+		<Node name="Hand Palm 2 L"/>
+		<Node name="Thumb L J0"/>
+		<Node name="Thumb L J1"/>
+		<Node name="Index L J0"/>
+		<Node name="Index L J1"/>
+		<Node name="Middle L J0"/>
+		<Node name="Middle L J1"/>
+		<Node name="Ring L J0"/>
+		<Node name="Ring L J1"/>
+		<Node name="Pinky L J0"/>
+		<Node name="Pinky L J1"/>
+		<Node name="Hand Palm 1 R"/>
+		<Node name="Hand Palm 2 R"/>
+		<Node name="Thumb R J0"/>
+		<Node name="Thumb R J1"/>
+		<Node name="Index R J0"/>
+		<Node name="Index R J1"/>
+		<Node name="Middle R J0"/>
+		<Node name="Middle R J1"/>
+		<Node name="Ring R J0"/>
+		<Node name="Ring R J1"/>
+		<Node name="Pinky R J0"/>
+		<Node name="Pinky R J1"/>
+	</RobotNodeSet>	
+
+	<RobotNodeSet name="PlatformYawTorsoLeftArm" kinematicRoot="Armar3_Base" tcp="TCP L">
+	    <Node name="Yaw_Platform"/>
+		<Node name="Hip Pitch"/>
+		<Node name="Hip Roll"/>
+		<Node name="Hip Yaw"/>
+		<Node name="Shoulder 1 L"/>
+		<Node name="Shoulder 2 L"/>
+		<Node name="Upperarm L"/>
+		<Node name="Elbow L"/>
+		<Node name="Underarm L"/>
+		<Node name="Wrist 1 L"/>
+		<Node name="Wrist 2 L"/>
+	</RobotNodeSet>	
+
+	<RobotNodeSet name="PlatformYawTorsoRightArm" kinematicRoot="Armar3_Base" tcp="TCP R">
+		<Node name="Yaw_Platform"/>
+		<Node name="Hip Pitch"/>
+		<Node name="Hip Roll"/>
+		<Node name="Hip Yaw"/>
+		<Node name="Shoulder 1 R"/>
+		<Node name="Shoulder 2 R"/>
+		<Node name="Upperarm R"/>
+		<Node name="Elbow R"/>
+		<Node name="Underarm R"/>
+		<Node name="Wrist 1 R"/>
+		<Node name="Wrist 2 R"/>
+	</RobotNodeSet>
+	
+  
+    <RobotNodeSet name="HeadMotionMeasurementChain" kinematicRoot="Neck_1_Pitch" tcp="HeadMotionMeasurementTCP">
+        <Node name="Neck_1_Pitch"/>
+        <Node name="Neck_2_Roll"/>
+        <Node name="Neck_3_Yaw"/>
+        <Node name="Head_Tilt"/>
+        <Node name="Cameras"/>
+        <Node name="Eye_Left"/>
+        <Node name="HeadMotionMeasurementTCP"/>
+    </RobotNodeSet>
+	
+
+</Robot>
diff --git a/data/RobotAPI/robots/Armar3/ArmarIII_minColModel.xml b/data/RobotAPI/robots/Armar3/ArmarIII_minColModel.xml
new file mode 100644
index 0000000000000000000000000000000000000000..e93b374607794e20319c31da9e0c9a33e66ca114
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/ArmarIII_minColModel.xml
@@ -0,0 +1,336 @@
+<?xml version="1.0" encoding="UTF-8" ?>
+
+<Robot Type="Armar3" RootNode="Armar3_Base">
+	
+	<RobotNode name="Armar3_Base">
+		<Visualization enable="true">
+			<CoordinateAxis  type="Inventor" enable="false" scaling="20"/>
+		</Visualization>
+		<Child name="Dummy_Platform"/>
+	</RobotNode>
+	
+	<RobotNode name="Dummy_Platform">
+		<Joint type="fixed">
+			<DH a="0" d="0" theta="0" alpha="-90" units="degree"/>
+		</Joint>
+		<Child name="X_Platform"/>
+	</RobotNode>
+	
+	<RobotNode name="X_Platform">
+		<Joint type="prismatic">
+			<DH a="0" d="0" theta="90" alpha="-90" units="degree"/>
+			<Limits unit="mm" lo="-10000" hi="10000"/>
+		</Joint>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+		</Visualization>
+		<Child name="Y_Platform"/>
+	</RobotNode>
+	
+	<RobotNode name="Y_Platform">
+		<Joint type="prismatic">
+			<DH a="0" d="0" theta="-90" alpha="90" units="degree"/>
+			<Limits unit="mm" lo="-10000" hi="10000"/>
+		</Joint>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+		</Visualization>
+		<Child name="Yaw_Platform"/>
+	</RobotNode>
+	
+	<RobotNode name="Yaw_Platform">
+		<Joint type="revolute">
+			<DH a="0" d="0" theta="-90" alpha="0" units="degree"/>
+			<Limits unit="degree" lo="-360" hi="360"/>
+		</Joint>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+		</Visualization>
+		<Child name="Platform"/>
+	</RobotNode>
+	
+	<RobotNode name="Platform">  <!-- visualization via 3D-model at the very end of the kinematic chain-->
+		<Joint type="fixed"/>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/platform.iv</File>
+		</Visualization>
+		<Physics>
+            <CoM location="Joint" x="0" y="0" z="200"/>
+            <Mass value="200" units="kg" />
+        </Physics>
+		<CollisionModel>
+			<File type="Inventor">collisionModel/platform.iv</File>
+		</CollisionModel>
+		<Child name="Hip Pitch"/>
+	</RobotNode>
+
+	<RobotNode name="Hip Pitch">
+		<Joint type="revolute">
+			<Axis x="1" y="0" z="0"/>
+			<Limits unit="degree" lo="-45" hi="45"/>
+			<PreJointTransform>
+				<Transform>
+					<Translation x="0" y="158" z="890"/>  <!-- x,y,z of THIS COS, NOT any other COS-->
+				</Transform>
+			</PreJointTransform>
+		</Joint>
+
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/platform_pitch_link.iv</File>
+		</Visualization>
+		<Child name="Hip Roll"/>
+	</RobotNode>
+	
+	<RobotNode name="Hip Roll">
+		<Joint type="revolute">
+			<Axis x="0" y="1" z="0"/>
+			<Limits unit="degree" lo="-45" hi="45"/>
+		</Joint>
+
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/platform_roll_link.iv</File>
+		</Visualization>
+		<Child name="Hip Yaw"/>
+	</RobotNode>
+	
+	<RobotNode name="Hip Yaw">
+		<Joint type="revolute">
+			<Axis x="0" y="0" z="1"/>
+			<Limits unit="degree" lo="-45" hi="45"/>
+		</Joint>
+		<Physics>
+            <CoM location="VisualizationBBoxCenter"/>
+            <Mass value="15.415" units="kg" />
+        </Physics>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+			<File type="Inventor">fullmodel/torso.iv</File>
+		</Visualization>
+		<CollisionModel>
+			<File type="Inventor">collisionModel/torso.iv</File>
+		</CollisionModel>
+		<Child name="Center of Arms"/>
+	</RobotNode>
+	
+	<RobotNode name="Center of Arms">
+		<Joint type="fixed">
+			<PreJointTransform>
+				<Transform>
+					<Translation x="0" y="-35" z="485"/>
+				</Transform>
+			</PreJointTransform>
+		</Joint>
+
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+		</Visualization>
+		
+		<Child name="TrafoToHead"/>
+		<Child name="TrafoToLeftArm"/>
+		<Child name="TrafoToRightArm"/>
+	</RobotNode>
+	
+	<RobotNode name="TrafoToHead">
+		<Joint type="fixed">
+			<PreJointTransform>
+				<Transform>
+					<Translation x="0" y="0" z="118"/>
+				</Transform>
+			</PreJointTransform>
+		</Joint>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+		</Visualization>
+		
+		<ChildFromRobot>
+			<File importEEF="true">ArmarIII-Head_minColModel.xml</File>
+		</ChildFromRobot>
+	</RobotNode>
+	
+	<RobotNode name="TrafoToLeftArm">
+		<Joint type="fixed">
+			<PreJointTransform>
+				<Transform>
+					<Translation x="-232" y="0" z="0"/>
+				</Transform>
+			</PreJointTransform>
+		</Joint>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+		</Visualization>
+		
+		<ChildFromRobot>
+			<File importEEF="true">ArmarIII-LeftArm_minColModel.xml</File>
+		</ChildFromRobot>
+	</RobotNode>
+	
+	<RobotNode name="TrafoToRightArm">
+		<Joint type="fixed">
+			<PreJointTransform>
+				<Transform>
+					<Translation x="232" y="0" z="0"/>
+				</Transform>
+			</PreJointTransform>
+		</Joint>
+		<Visualization enable="true">
+			<CoordinateAxis type="Inventor" enable="false" scaling="8"/>
+		</Visualization>
+		
+		<ChildFromRobot>
+			<File importEEF="true">ArmarIII-RightArm_minColModel.xml</File>
+		</ChildFromRobot>
+	</RobotNode>
+	
+	<RobotNodeSet name="Torso" kinematicRoot="Platform">
+		<Node name="Hip Pitch"/>
+		<Node name="Hip Roll"/>
+		<Node name="Hip Yaw"/>
+	</RobotNodeSet>
+	
+	<RobotNodeSet name="TorsoHeadColModel">
+		<Node name="Hip Yaw"/>
+		<Node name="Head_Tilt"/>
+	</RobotNodeSet>
+	
+	<RobotNodeSet name="PlatformTorsoColModel">
+		<Node name="Platform"/>
+		<Node name="Hip Yaw"/>
+	</RobotNodeSet>
+	
+	<RobotNodeSet name="PlatformTorsoHeadColModel">
+		<Node name="Platform"/>
+		<Node name="Hip Yaw"/>
+		<Node name="Head_Tilt"/>
+	</RobotNodeSet>
+	
+	<RobotNodeSet name="TorsoLeftArm" kinematicRoot="Platform" tcp="TCP L">
+		<Node name="Hip Pitch"/>
+		<Node name="Hip Roll"/>
+		<Node name="Hip Yaw"/>
+		<Node name="Shoulder 1 L"/>
+		<Node name="Shoulder 2 L"/>
+		<Node name="Upperarm L"/>
+		<Node name="Elbow L"/>
+		<Node name="Underarm L"/>
+		<Node name="Wrist 1 L"/>
+		<Node name="Wrist 2 L"/>
+	</RobotNodeSet>	
+	
+	<RobotNodeSet name="TorsoRightArm" kinematicRoot="Platform" tcp="TCP R">
+		<Node name="Hip Pitch"/>
+		<Node name="Hip Roll"/>
+		<Node name="Hip Yaw"/>
+		<Node name="Shoulder 1 R"/>
+		<Node name="Shoulder 2 R"/>
+		<Node name="Upperarm R"/>
+		<Node name="Elbow R"/>
+		<Node name="Underarm R"/>
+		<Node name="Wrist 1 R"/>
+		<Node name="Wrist 2 R"/>
+	</RobotNodeSet>
+	
+	
+	<RobotNodeSet name="TorsoBothArms" kinematicRoot="Platform">
+		<Node name="Hip Pitch"/>
+		<Node name="Hip Roll"/>
+		<Node name="Hip Yaw"/>
+		<Node name="Shoulder 1 L"/>
+		<Node name="Shoulder 2 L"/>
+		<Node name="Upperarm L"/>
+		<Node name="Elbow L"/>
+		<Node name="Underarm L"/>
+		<Node name="Wrist 1 L"/>
+		<Node name="Wrist 2 L"/>
+		<Node name="Shoulder 1 R"/>
+		<Node name="Shoulder 2 R"/>
+		<Node name="Upperarm R"/>
+		<Node name="Elbow R"/>
+		<Node name="Underarm R"/>
+		<Node name="Wrist 1 R"/>
+		<Node name="Wrist 2 R"/>
+	</RobotNodeSet>	
+	
+	<RobotNodeSet name="Robot" kinematicRoot="Platform">
+		<Node name="Neck_1_Pitch"/>
+		<Node name="Neck_2_Roll"/>
+		<Node name="Neck_3_Yaw"/>
+		<Node name="Head_Tilt"/>
+		<Node name="Cameras"/>
+		<Node name="Eye_Left"/>
+		<Node name="Eye_Right"/>
+		<Node name="Hip Pitch"/>
+		<Node name="Hip Roll"/>
+		<Node name="Hip Yaw"/>
+		<Node name="Shoulder 1 L"/>
+		<Node name="Shoulder 2 L"/>
+		<Node name="Upperarm L"/>
+		<Node name="Elbow L"/>
+		<Node name="Underarm L"/>
+		<Node name="Wrist 1 L"/>
+		<Node name="Wrist 2 L"/>
+		<Node name="Shoulder 1 R"/>
+		<Node name="Shoulder 2 R"/>
+		<Node name="Upperarm R"/>
+		<Node name="Elbow R"/>
+		<Node name="Underarm R"/>
+		<Node name="Wrist 1 R"/>
+		<Node name="Wrist 2 R"/>
+		<Node name="Hand Palm 1 L"/>
+		<Node name="Hand Palm 2 L"/>
+		<Node name="Thumb L J0"/>
+		<Node name="Thumb L J1"/>
+		<Node name="Index L J0"/>
+		<Node name="Index L J1"/>
+		<Node name="Middle L J0"/>
+		<Node name="Middle L J1"/>
+		<Node name="Ring L J0"/>
+		<Node name="Ring L J1"/>
+		<Node name="Pinky L J0"/>
+		<Node name="Pinky L J1"/>
+		<Node name="Hand Palm 1 R"/>
+		<Node name="Hand Palm 2 R"/>
+		<Node name="Thumb R J0"/>
+		<Node name="Thumb R J1"/>
+		<Node name="Index R J0"/>
+		<Node name="Index R J1"/>
+		<Node name="Middle R J0"/>
+		<Node name="Middle R J1"/>
+		<Node name="Ring R J0"/>
+		<Node name="Ring R J1"/>
+		<Node name="Pinky R J0"/>
+		<Node name="Pinky R J1"/>
+	</RobotNodeSet>	
+
+	<RobotNodeSet name="PlatformYawTorsoLeftArm" kinematicRoot="Armar3_Base" tcp="TCP L">
+	    <Node name="Yaw_Platform"/>
+		<Node name="Hip Pitch"/>
+		<Node name="Hip Roll"/>
+		<Node name="Hip Yaw"/>
+		<Node name="Shoulder 1 L"/>
+		<Node name="Shoulder 2 L"/>
+		<Node name="Upperarm L"/>
+		<Node name="Elbow L"/>
+		<Node name="Underarm L"/>
+		<Node name="Wrist 1 L"/>
+		<Node name="Wrist 2 L"/>
+	</RobotNodeSet>	
+
+	<RobotNodeSet name="PlatformYawTorsoRightArm" kinematicRoot="Armar3_Base" tcp="TCP R">
+		<Node name="Yaw_Platform"/>
+		<Node name="Hip Pitch"/>
+		<Node name="Hip Roll"/>
+		<Node name="Hip Yaw"/>
+		<Node name="Shoulder 1 R"/>
+		<Node name="Shoulder 2 R"/>
+		<Node name="Upperarm R"/>
+		<Node name="Elbow R"/>
+		<Node name="Underarm R"/>
+		<Node name="Wrist 1 R"/>
+		<Node name="Wrist 2 R"/>
+	</RobotNodeSet>
+	
+
+</Robot>
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/head.iv b/data/RobotAPI/robots/Armar3/collisionModel/head.iv
new file mode 100644
index 0000000000000000000000000000000000000000..509324db37893a45c08d2eb791ea056bc4d19460
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/head.iv
@@ -0,0 +1,429 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+        Units {
+            units MILLIMETERS
+    }
+
+	Transform {
+	translation 0 0 0
+	rotation 0 1 0 1.57
+	}
+	Transform {
+	translation 0 0 0
+	rotation 1 0 0 3.14
+	}
+	Transform {
+	translation 0 0 0
+	rotation 0 1 0 3.14
+	}
+    Material {
+        diffuseColor    1 1 1
+    }
+    Separator {
+        Normal {
+            vector      [ -4.88664e-16 2.39001e-16 -1,
+                          -4.88664e-16 2.39001e-16 -1,
+                          -4.88664e-16 2.39001e-16 -1,
+                          -0.707107 1.8482e-16 -0.707107,
+                          -0.707107 1.8482e-16 -0.707107,
+                          -0.707107 1.8482e-16 -0.707107,
+                          -4.88664e-16 2.39001e-16 -1,
+                          -4.88664e-16 2.39001e-16 -1,
+                          -4.88664e-16 2.39001e-16 -1,
+                          -4.27068e-16 0.447214 -0.894427,
+                          -4.27068e-16 0.447214 -0.894427,
+                          -4.27068e-16 0.447214 -0.894427,
+                          -4.27068e-16 0.447214 -0.894427,
+                          -4.27068e-16 0.447214 -0.894427,
+                          -4.27068e-16 0.447214 -0.894427,
+                          -0.707107 1.8482e-16 -0.707107,
+                          -0.707107 1.8482e-16 -0.707107,
+                          -0.707107 1.8482e-16 -0.707107,
+                          -3.61359e-16 -0.707107 -0.707107,
+                          -3.61359e-16 -0.707107 -0.707107,
+                          -3.61359e-16 -0.707107 -0.707107,
+                          -3.61359e-16 -0.707107 -0.707107,
+                          -3.61359e-16 -0.707107 -0.707107,
+                          -3.61359e-16 -0.707107 -0.707107,
+                          -0.707107 1.8482e-16 -0.707107,
+                          -0.707107 1.8482e-16 -0.707107,
+                          -0.707107 1.8482e-16 -0.707107,
+                          -0.707107 1.8482e-16 -0.707107,
+                          -0.707107 1.8482e-16 -0.707107,
+                          -0.707107 1.8482e-16 -0.707107,
+                          0.707107 1.53178e-16 -0.707107,
+                          0.707107 1.53178e-16 -0.707107,
+                          0.707107 1.53178e-16 -0.707107,
+                          -3.61359e-16 -0.707107 -0.707107,
+                          -3.61359e-16 -0.707107 -0.707107,
+                          -3.61359e-16 -0.707107 -0.707107,
+                          -3.61359e-16 -0.707107 -0.707107,
+                          -3.61359e-16 -0.707107 -0.707107,
+                          -3.61359e-16 -0.707107 -0.707107,
+                          0.707107 1.53178e-16 -0.707107,
+                          0.707107 1.53178e-16 -0.707107,
+                          0.707107 1.53178e-16 -0.707107,
+                          0.707107 1.53178e-16 -0.707107,
+                          0.707107 1.53178e-16 -0.707107,
+                          0.707107 1.53178e-16 -0.707107,
+                          0.707107 1.53178e-16 -0.707107,
+                          0.707107 1.53178e-16 -0.707107,
+                          0.707107 1.53178e-16 -0.707107,
+                          4.88664e-16 -2.39001e-16 1,
+                          4.88664e-16 -2.39001e-16 1,
+                          4.88664e-16 -2.39001e-16 1,
+                          3.29717e-16 -0.707107 0.707107,
+                          3.29717e-16 -0.707107 0.707107,
+                          3.29717e-16 -0.707107 0.707107,
+                          0.707107 -1.8482e-16 0.707107,
+                          0.707107 -1.8482e-16 0.707107,
+                          0.707107 -1.8482e-16 0.707107,
+                          3.29717e-16 -0.707107 0.707107,
+                          3.29717e-16 -0.707107 0.707107,
+                          3.29717e-16 -0.707107 0.707107,
+                          0.707107 -1.8482e-16 0.707107,
+                          0.707107 -1.8482e-16 0.707107,
+                          0.707107 -1.8482e-16 0.707107,
+                          0.707107 -1.8482e-16 0.707107,
+                          0.707107 -1.8482e-16 0.707107,
+                          0.707107 -1.8482e-16 0.707107,
+                          0.707107 -1.8482e-16 0.707107,
+                          0.707107 -1.8482e-16 0.707107,
+                          0.707107 -1.8482e-16 0.707107,
+                          4.88664e-16 -2.39001e-16 1,
+                          4.88664e-16 -2.39001e-16 1,
+                          4.88664e-16 -2.39001e-16 1,
+                          -0.707107 -1.53178e-16 0.707107,
+                          -0.707107 -1.53178e-16 0.707107,
+                          -0.707107 -1.53178e-16 0.707107,
+                          3.29717e-16 -0.707107 0.707107,
+                          3.29717e-16 -0.707107 0.707107,
+                          3.29717e-16 -0.707107 0.707107,
+                          3.29717e-16 -0.707107 0.707107,
+                          3.29717e-16 -0.707107 0.707107,
+                          3.29717e-16 -0.707107 0.707107,
+                          -0.707107 -1.53178e-16 0.707107,
+                          -0.707107 -1.53178e-16 0.707107,
+                          -0.707107 -1.53178e-16 0.707107,
+                          2.23744e-17 1 2.39001e-16,
+                          2.23744e-17 1 2.39001e-16,
+                          2.23744e-17 1 2.39001e-16,
+                          -0.707107 -1.53178e-16 0.707107,
+                          -0.707107 -1.53178e-16 0.707107,
+                          -0.707107 -1.53178e-16 0.707107,
+                          -0.707107 -1.53178e-16 0.707107,
+                          -0.707107 -1.53178e-16 0.707107,
+                          -0.707107 -1.53178e-16 0.707107,
+                          2.23744e-17 1 2.39001e-16,
+                          2.23744e-17 1 2.39001e-16,
+                          2.23744e-17 1 2.39001e-16,
+                          2.23744e-17 1 2.39001e-16,
+                          2.23744e-17 1 2.39001e-16,
+                          2.23744e-17 1 2.39001e-16,
+                          -2.23744e-17 -1 -2.39001e-16,
+                          -2.23744e-17 -1 -2.39001e-16,
+                          -2.23744e-17 -1 -2.39001e-16,
+                          -0.707107 -0.707107 1.76539e-16,
+                          -0.707107 -0.707107 1.76539e-16,
+                          -0.707107 -0.707107 1.76539e-16,
+                          -0.707107 -0.707107 1.76539e-16,
+                          -0.707107 -0.707107 1.76539e-16,
+                          -0.707107 -0.707107 1.76539e-16,
+                          -0.707107 -0.707107 1.76539e-16,
+                          -0.707107 -0.707107 1.76539e-16,
+                          -0.707107 -0.707107 1.76539e-16,
+                          -2.23744e-17 -1 -2.39001e-16,
+                          -2.23744e-17 -1 -2.39001e-16,
+                          -2.23744e-17 -1 -2.39001e-16,
+                          0.707107 -0.707107 -5.14537e-16,
+                          0.707107 -0.707107 -5.14537e-16,
+                          0.707107 -0.707107 -5.14537e-16,
+                          0.707107 -0.707107 -5.14537e-16,
+                          0.707107 -0.707107 -5.14537e-16,
+                          0.707107 -0.707107 -5.14537e-16,
+                          0.707107 -0.707107 -5.14537e-16,
+                          0.707107 -0.707107 -5.14537e-16,
+                          0.707107 -0.707107 -5.14537e-16,
+                          0.707107 -0.707107 -5.14537e-16,
+                          0.707107 -0.707107 -5.14537e-16,
+                          0.707107 -0.707107 -5.14537e-16,
+                          -0.707107 -0.707107 1.76539e-16,
+                          -0.707107 -0.707107 1.76539e-16,
+                          -0.707107 -0.707107 1.76539e-16,
+                          1 -2.23744e-17 -4.88664e-16,
+                          1 -2.23744e-17 -4.88664e-16,
+                          1 -2.23744e-17 -4.88664e-16,
+                          1 -2.23744e-17 -4.88664e-16,
+                          1 -2.23744e-17 -4.88664e-16,
+                          1 -2.23744e-17 -4.88664e-16,
+                          1 -2.23744e-17 -4.88664e-16,
+                          1 -2.23744e-17 -4.88664e-16,
+                          1 -2.23744e-17 -4.88664e-16,
+                          0.707107 0.707107 -1.76539e-16,
+                          0.707107 0.707107 -1.76539e-16,
+                          0.707107 0.707107 -1.76539e-16,
+                          0.961524 0.274721 -4.04204e-16,
+                          0.961524 0.274721 -4.04204e-16,
+                          0.961524 0.274721 -4.04204e-16,
+                          4.88664e-16 -2.39001e-16 1,
+                          4.88664e-16 -2.39001e-16 1,
+                          4.88664e-16 -2.39001e-16 1,
+                          0.707107 0.707107 -1.76539e-16,
+                          0.707107 0.707107 -1.76539e-16,
+                          0.707107 0.707107 -1.76539e-16,
+                          0.961524 0.274721 -4.04204e-16,
+                          0.961524 0.274721 -4.04204e-16,
+                          0.961524 0.274721 -4.04204e-16,
+                          2.23744e-17 1 2.39001e-16,
+                          2.23744e-17 1 2.39001e-16,
+                          2.23744e-17 1 2.39001e-16,
+                          4.88664e-16 -2.39001e-16 1,
+                          4.88664e-16 -2.39001e-16 1,
+                          4.88664e-16 -2.39001e-16 1,
+                          2.23744e-17 1 2.39001e-16,
+                          2.23744e-17 1 2.39001e-16,
+                          2.23744e-17 1 2.39001e-16,
+                          -0.961524 0.274721 5.35521e-16,
+                          -0.961524 0.274721 5.35521e-16,
+                          -0.961524 0.274721 5.35521e-16,
+                          4.88664e-16 -2.39001e-16 1,
+                          4.88664e-16 -2.39001e-16 1,
+                          4.88664e-16 -2.39001e-16 1,
+                          4.88664e-16 -2.39001e-16 1,
+                          4.88664e-16 -2.39001e-16 1,
+                          4.88664e-16 -2.39001e-16 1,
+                          -0.961524 0.274721 5.35521e-16,
+                          -0.961524 0.274721 5.35521e-16,
+                          -0.961524 0.274721 5.35521e-16,
+                          -1 2.23744e-17 4.88664e-16,
+                          -1 2.23744e-17 4.88664e-16,
+                          -1 2.23744e-17 4.88664e-16,
+                          -1 2.23744e-17 4.88664e-16,
+                          -1 2.23744e-17 4.88664e-16,
+                          -1 2.23744e-17 4.88664e-16,
+                          -0.707107 0.707107 5.14537e-16,
+                          -0.707107 0.707107 5.14537e-16,
+                          -0.707107 0.707107 5.14537e-16,
+                          -0.707107 0.707107 5.14537e-16,
+                          -0.707107 0.707107 5.14537e-16,
+                          -0.707107 0.707107 5.14537e-16,
+                          -1 2.23744e-17 4.88664e-16,
+                          -1 2.23744e-17 4.88664e-16,
+                          -1 2.23744e-17 4.88664e-16,
+                          2.23744e-17 1 2.39001e-16,
+                          2.23744e-17 1 2.39001e-16,
+                          2.23744e-17 1 2.39001e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 34.8846 -130 -63.688,
+                          -37.9003 -130 -63.688,
+                          -37.9003 30 -63.688,
+                          -87.9003 20 -13.688,
+                          -37.9003 30 -63.688,
+                          -37.9003 -130 -63.688,
+                          34.8846 30 -63.688,
+                          34.8846 -130 -63.688,
+                          -37.9003 30 -63.688,
+                          64.8846 90 -33.688,
+                          34.8846 30 -63.688,
+                          -37.9003 30 -63.688,
+                          64.8846 90 -33.688,
+                          -37.9003 30 -63.688,
+                          -67.9003 90 -33.688,
+                          -87.9003 20 -13.688,
+                          -67.9003 90 -33.688,
+                          -37.9003 30 -63.688,
+                          -37.9003 -180 -13.688,
+                          -37.9003 -130 -63.688,
+                          34.8846 -130 -63.688,
+                          -62.9003 -155 -38.688,
+                          -37.9003 -130 -63.688,
+                          -37.9003 -180 -13.688,
+                          -87.9003 20 -13.688,
+                          -37.9003 -130 -63.688,
+                          -87.9003 -130 -13.688,
+                          -62.9003 -155 -38.688,
+                          -87.9003 -130 -13.688,
+                          -37.9003 -130 -63.688,
+                          84.8846 -130 -13.688,
+                          34.8846 -130 -63.688,
+                          34.8846 30 -63.688,
+                          -37.9003 -180 -13.688,
+                          34.8846 -130 -63.688,
+                          34.8846 -180 -13.688,
+                          59.8846 -155 -38.688,
+                          34.8846 -180 -13.688,
+                          34.8846 -130 -63.688,
+                          59.8846 -155 -38.688,
+                          34.8846 -130 -63.688,
+                          84.8846 -130 -13.688,
+                          84.8846 -130 -13.688,
+                          34.8846 30 -63.688,
+                          84.8846 20 -13.688,
+                          64.8846 90 -33.688,
+                          84.8846 20 -13.688,
+                          34.8846 30 -63.688,
+                          44.8846 50 136.312,
+                          -47.9003 -130 136.312,
+                          44.8846 -130 136.312,
+                          34.8846 -180 86.312,
+                          44.8846 -130 136.312,
+                          -47.9003 -130 136.312,
+                          54.8846 50 126.312,
+                          44.8846 50 136.312,
+                          44.8846 -130 136.312,
+                          64.8846 -150 116.312,
+                          44.8846 -130 136.312,
+                          34.8846 -180 86.312,
+                          84.8846 20 96.312,
+                          44.8846 -130 136.312,
+                          84.8846 -130 96.312,
+                          64.8846 -150 116.312,
+                          84.8846 -130 96.312,
+                          44.8846 -130 136.312,
+                          54.8846 50 126.312,
+                          44.8846 -130 136.312,
+                          84.8846 20 96.312,
+                          44.8846 50 136.312,
+                          -47.9003 50 136.312,
+                          -47.9003 -130 136.312,
+                          -87.9003 -130 96.312,
+                          -47.9003 -130 136.312,
+                          -47.9003 50 136.312,
+                          34.8846 -180 86.312,
+                          -47.9003 -130 136.312,
+                          -37.9003 -180 86.312,
+                          -67.9003 -150 116.312,
+                          -37.9003 -180 86.312,
+                          -47.9003 -130 136.312,
+                          -67.9003 -150 116.312,
+                          -47.9003 -130 136.312,
+                          -87.9003 -130 96.312,
+                          -57.9003 50 70.3252,
+                          -47.9003 50 136.312,
+                          44.8846 50 136.312,
+                          -87.9003 -130 96.312,
+                          -47.9003 50 136.312,
+                          -87.9003 20 96.312,
+                          -57.9003 50 126.312,
+                          -87.9003 20 96.312,
+                          -47.9003 50 136.312,
+                          -57.9003 50 126.312,
+                          -47.9003 50 136.312,
+                          -57.9003 50 70.3252,
+                          54.8846 50 126.312,
+                          -57.9003 50 70.3252,
+                          44.8846 50 136.312,
+                          -37.9003 -180 -13.688,
+                          34.8846 -180 86.312,
+                          -37.9003 -180 86.312,
+                          -87.9003 -130 -13.688,
+                          -37.9003 -180 -13.688,
+                          -37.9003 -180 86.312,
+                          -87.9003 -130 -13.688,
+                          -37.9003 -180 86.312,
+                          -87.9003 -130 96.312,
+                          -67.9003 -150 116.312,
+                          -87.9003 -130 96.312,
+                          -37.9003 -180 86.312,
+                          -37.9003 -180 -13.688,
+                          34.8846 -180 -13.688,
+                          34.8846 -180 86.312,
+                          84.8846 -130 96.312,
+                          34.8846 -180 86.312,
+                          34.8846 -180 -13.688,
+                          64.8846 -150 116.312,
+                          34.8846 -180 86.312,
+                          84.8846 -130 96.312,
+                          84.8846 -130 -13.688,
+                          84.8846 -130 96.312,
+                          34.8846 -180 -13.688,
+                          59.8846 -155 -38.688,
+                          84.8846 -130 -13.688,
+                          34.8846 -180 -13.688,
+                          -62.9003 -155 -38.688,
+                          -37.9003 -180 -13.688,
+                          -87.9003 -130 -13.688,
+                          84.8846 20 70.3252,
+                          84.8846 20 96.312,
+                          84.8846 -130 96.312,
+                          84.8846 20 -13.688,
+                          84.8846 20 70.3252,
+                          84.8846 -130 96.312,
+                          84.8846 -130 -13.688,
+                          84.8846 20 -13.688,
+                          84.8846 -130 96.312,
+                          54.8846 50 126.312,
+                          84.8846 20 96.312,
+                          84.8846 20 70.3252,
+                          64.8846 90 70.3252,
+                          84.8846 20 70.3252,
+                          84.8846 20 -13.688,
+                          54.8846 50 70.3252,
+                          84.8846 20 70.3252,
+                          64.8846 90 70.3252,
+                          54.8846 50 126.312,
+                          84.8846 20 70.3252,
+                          54.8846 50 70.3252,
+                          64.8846 90 -33.688,
+                          64.8846 90 70.3252,
+                          84.8846 20 -13.688,
+                          -67.9003 90 -33.688,
+                          -67.9003 90 70.3252,
+                          64.8846 90 70.3252,
+                          54.8846 50 70.3252,
+                          64.8846 90 70.3252,
+                          -67.9003 90 70.3252,
+                          64.8846 90 -33.688,
+                          -67.9003 90 -33.688,
+                          64.8846 90 70.3252,
+                          -87.9003 20 70.3252,
+                          -67.9003 90 70.3252,
+                          -67.9003 90 -33.688,
+                          -57.9003 50 70.3252,
+                          -67.9003 90 70.3252,
+                          -87.9003 20 70.3252,
+                          54.8846 50 70.3252,
+                          -67.9003 90 70.3252,
+                          -57.9003 50 70.3252,
+                          -87.9003 20 70.3252,
+                          -67.9003 90 -33.688,
+                          -87.9003 20 -13.688,
+                          -87.9003 -130 -13.688,
+                          -87.9003 -130 96.312,
+                          -87.9003 20 96.312,
+                          -87.9003 20 70.3252,
+                          -87.9003 -130 -13.688,
+                          -87.9003 20 96.312,
+                          -57.9003 50 70.3252,
+                          -87.9003 20 70.3252,
+                          -87.9003 20 96.312,
+                          -57.9003 50 126.312,
+                          -57.9003 50 70.3252,
+                          -87.9003 20 96.312,
+                          -87.9003 20 70.3252,
+                          -87.9003 20 -13.688,
+                          -87.9003 -130 -13.688,
+                          54.8846 50 126.312,
+                          54.8846 50 70.3252,
+                          -57.9003 50 70.3252 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/index_l1.iv b/data/RobotAPI/robots/Armar3/collisionModel/index_l1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..3ba7735aadcc9976b925dc9ef57a4abce72b4c8c
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/index_l1.iv
@@ -0,0 +1,111 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 -1.57
+	} 
+	Transform {
+		translation -4.25 0 0
+		rotation 0 1 0 0
+	} 
+    Separator {
+        Normal {
+            vector      [ -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 10.67 -2.4 3.75,
+                          -5 -2.4 -21.25,
+                          10.67 -2.4 -21.25,
+                          -5 42.25 -21.25,
+                          10.67 -2.4 -21.25,
+                          -5 -2.4 -21.25,
+                          10.67 42.25 -21.25,
+                          10.67 -2.4 3.75,
+                          10.67 -2.4 -21.25,
+                          -5 42.25 -21.25,
+                          10.67 42.25 -21.25,
+                          10.67 -2.4 -21.25,
+                          10.67 -2.4 3.75,
+                          -5 -2.4 3.75,
+                          -5 -2.4 -21.25,
+                          -5 42.25 3.75,
+                          -5 -2.4 -21.25,
+                          -5 -2.4 3.75,
+                          -5 42.25 -21.25,
+                          -5 -2.4 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 3.75,
+                          -5 -2.4 3.75,
+                          10.67 -2.4 3.75,
+                          -5 42.25 3.75,
+                          -5 -2.4 3.75,
+                          10.67 42.25 3.75,
+                          10.67 42.25 3.75,
+                          10.67 -2.4 3.75,
+                          10.67 42.25 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 3.75,
+                          10.67 42.25 -21.25,
+                          -5 42.25 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 -21.25 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/index_l2.iv b/data/RobotAPI/robots/Armar3/collisionModel/index_l2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..d3a66db5413ae43fdebcee249c0d122f65444961
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/index_l2.iv
@@ -0,0 +1,131 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+
+    Material {
+        diffuseColor    0 0 1
+    }
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 -1.57
+	} 
+    Separator {
+        Normal {
+            vector      [ 0 -1 1.30104e-16,
+                          0 -1 1.30104e-16,
+                          0 -1 1.30104e-16,
+                          -6.76542e-17 8.50015e-17 -1,
+                          -6.76542e-17 8.50015e-17 -1,
+                          -6.76542e-17 8.50015e-17 -1,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          0 -1 1.30104e-16,
+                          0 -1 1.30104e-16,
+                          0 -1 1.30104e-16,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -6.76542e-17 8.50015e-17 -1,
+                          -6.76542e-17 8.50015e-17 -1,
+                          -6.76542e-17 8.50015e-17 -1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          0 1 -1.30104e-16,
+                          0 1 -1.30104e-16,
+                          0 1 -1.30104e-16,
+                          -6.4801e-17 0.287348 -0.957826,
+                          -6.4801e-17 0.287348 -0.957826,
+                          -6.4801e-17 0.287348 -0.957826,
+                          0 1 -1.30104e-16,
+                          0 1 -1.30104e-16,
+                          0 1 -1.30104e-16,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -6.4801e-17 0.287348 -0.957826,
+                          -6.4801e-17 0.287348 -0.957826,
+                          -6.4801e-17 0.287348 -0.957826 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 10 -1.25 4.25,
+                          -10 -1.25 -20.75,
+                          10 -1.25 -20.75,
+                          10 8.75 -20.75,
+                          10 -1.25 -20.75,
+                          -10 -1.25 -20.75,
+                          10 8.75 -20.75,
+                          10 -1.25 4.25,
+                          10 -1.25 -20.75,
+                          10 -1.25 4.25,
+                          -10 -1.25 4.25,
+                          -10 -1.25 -20.75,
+                          -10 58.75 4.25,
+                          -10 -1.25 -20.75,
+                          -10 -1.25 4.25,
+                          -10 8.75 -20.75,
+                          -10 -1.25 -20.75,
+                          -10 58.75 4.25,
+                          10 8.75 -20.75,
+                          -10 -1.25 -20.75,
+                          -10 8.75 -20.75,
+                          10 58.75 4.25,
+                          -10 -1.25 4.25,
+                          10 -1.25 4.25,
+                          -10 58.75 4.25,
+                          -10 -1.25 4.25,
+                          10 58.75 4.25,
+                          10 58.75 4.25,
+                          10 -1.25 4.25,
+                          10 58.75 -5.75,
+                          10 8.75 -20.75,
+                          10 58.75 -5.75,
+                          10 -1.25 4.25,
+                          10 58.75 4.25,
+                          10 58.75 -5.75,
+                          -10 58.75 -5.75,
+                          10 8.75 -20.75,
+                          -10 58.75 -5.75,
+                          10 58.75 -5.75,
+                          -10 58.75 4.25,
+                          10 58.75 4.25,
+                          -10 58.75 -5.75,
+                          -10 8.75 -20.75,
+                          -10 58.75 4.25,
+                          -10 58.75 -5.75,
+                          10 8.75 -20.75,
+                          -10 8.75 -20.75,
+                          -10 58.75 -5.75 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/index_r1.iv b/data/RobotAPI/robots/Armar3/collisionModel/index_r1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..ea65ade440bca4da11e054f2f321b52dba485128
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/index_r1.iv
@@ -0,0 +1,110 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 -1.57
+	} 
+#	Transform {
+#		translation 0 0 0
+#		rotation 0 1 0 0
+#	} 
+    Separator {
+        Normal {
+            vector      [ -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 10.67 -2.4 3.75,
+                          -5 -2.4 -21.25,
+                          10.67 -2.4 -21.25,
+                          -5 42.25 -21.25,
+                          10.67 -2.4 -21.25,
+                          -5 -2.4 -21.25,
+                          10.67 42.25 -21.25,
+                          10.67 -2.4 3.75,
+                          10.67 -2.4 -21.25,
+                          -5 42.25 -21.25,
+                          10.67 42.25 -21.25,
+                          10.67 -2.4 -21.25,
+                          10.67 -2.4 3.75,
+                          -5 -2.4 3.75,
+                          -5 -2.4 -21.25,
+                          -5 42.25 3.75,
+                          -5 -2.4 -21.25,
+                          -5 -2.4 3.75,
+                          -5 42.25 -21.25,
+                          -5 -2.4 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 3.75,
+                          -5 -2.4 3.75,
+                          10.67 -2.4 3.75,
+                          -5 42.25 3.75,
+                          -5 -2.4 3.75,
+                          10.67 42.25 3.75,
+                          10.67 42.25 3.75,
+                          10.67 -2.4 3.75,
+                          10.67 42.25 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 3.75,
+                          10.67 42.25 -21.25,
+                          -5 42.25 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 -21.25 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/index_r2.iv b/data/RobotAPI/robots/Armar3/collisionModel/index_r2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..d3a66db5413ae43fdebcee249c0d122f65444961
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/index_r2.iv
@@ -0,0 +1,131 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+
+    Material {
+        diffuseColor    0 0 1
+    }
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 -1.57
+	} 
+    Separator {
+        Normal {
+            vector      [ 0 -1 1.30104e-16,
+                          0 -1 1.30104e-16,
+                          0 -1 1.30104e-16,
+                          -6.76542e-17 8.50015e-17 -1,
+                          -6.76542e-17 8.50015e-17 -1,
+                          -6.76542e-17 8.50015e-17 -1,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          0 -1 1.30104e-16,
+                          0 -1 1.30104e-16,
+                          0 -1 1.30104e-16,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -6.76542e-17 8.50015e-17 -1,
+                          -6.76542e-17 8.50015e-17 -1,
+                          -6.76542e-17 8.50015e-17 -1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          0 1 -1.30104e-16,
+                          0 1 -1.30104e-16,
+                          0 1 -1.30104e-16,
+                          -6.4801e-17 0.287348 -0.957826,
+                          -6.4801e-17 0.287348 -0.957826,
+                          -6.4801e-17 0.287348 -0.957826,
+                          0 1 -1.30104e-16,
+                          0 1 -1.30104e-16,
+                          0 1 -1.30104e-16,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -6.4801e-17 0.287348 -0.957826,
+                          -6.4801e-17 0.287348 -0.957826,
+                          -6.4801e-17 0.287348 -0.957826 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 10 -1.25 4.25,
+                          -10 -1.25 -20.75,
+                          10 -1.25 -20.75,
+                          10 8.75 -20.75,
+                          10 -1.25 -20.75,
+                          -10 -1.25 -20.75,
+                          10 8.75 -20.75,
+                          10 -1.25 4.25,
+                          10 -1.25 -20.75,
+                          10 -1.25 4.25,
+                          -10 -1.25 4.25,
+                          -10 -1.25 -20.75,
+                          -10 58.75 4.25,
+                          -10 -1.25 -20.75,
+                          -10 -1.25 4.25,
+                          -10 8.75 -20.75,
+                          -10 -1.25 -20.75,
+                          -10 58.75 4.25,
+                          10 8.75 -20.75,
+                          -10 -1.25 -20.75,
+                          -10 8.75 -20.75,
+                          10 58.75 4.25,
+                          -10 -1.25 4.25,
+                          10 -1.25 4.25,
+                          -10 58.75 4.25,
+                          -10 -1.25 4.25,
+                          10 58.75 4.25,
+                          10 58.75 4.25,
+                          10 -1.25 4.25,
+                          10 58.75 -5.75,
+                          10 8.75 -20.75,
+                          10 58.75 -5.75,
+                          10 -1.25 4.25,
+                          10 58.75 4.25,
+                          10 58.75 -5.75,
+                          -10 58.75 -5.75,
+                          10 8.75 -20.75,
+                          -10 58.75 -5.75,
+                          10 58.75 -5.75,
+                          -10 58.75 4.25,
+                          10 58.75 4.25,
+                          -10 58.75 -5.75,
+                          -10 8.75 -20.75,
+                          -10 58.75 4.25,
+                          -10 58.75 -5.75,
+                          10 8.75 -20.75,
+                          -10 8.75 -20.75,
+                          -10 58.75 -5.75 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/middle_l1.iv b/data/RobotAPI/robots/Armar3/collisionModel/middle_l1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..5afda54b141a25ca9d66e31c2fd044bb974b901a
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/middle_l1.iv
@@ -0,0 +1,110 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 -1.57
+	} 
+	Transform {
+		translation -4.25 0 0
+		rotation 0 1 0 0
+	} 
+    Separator {
+        Normal {
+            vector      [ -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 10.67 -2.4 3.75,
+                          -5 -2.4 -21.25,
+                          10.67 -2.4 -21.25,
+                          -5 42.25 -21.25,
+                          10.67 -2.4 -21.25,
+                          -5 -2.4 -21.25,
+                          10.67 42.25 -21.25,
+                          10.67 -2.4 3.75,
+                          10.67 -2.4 -21.25,
+                          -5 42.25 -21.25,
+                          10.67 42.25 -21.25,
+                          10.67 -2.4 -21.25,
+                          10.67 -2.4 3.75,
+                          -5 -2.4 3.75,
+                          -5 -2.4 -21.25,
+                          -5 42.25 3.75,
+                          -5 -2.4 -21.25,
+                          -5 -2.4 3.75,
+                          -5 42.25 -21.25,
+                          -5 -2.4 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 3.75,
+                          -5 -2.4 3.75,
+                          10.67 -2.4 3.75,
+                          -5 42.25 3.75,
+                          -5 -2.4 3.75,
+                          10.67 42.25 3.75,
+                          10.67 42.25 3.75,
+                          10.67 -2.4 3.75,
+                          10.67 42.25 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 3.75,
+                          10.67 42.25 -21.25,
+                          -5 42.25 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 -21.25 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/middle_l2.iv b/data/RobotAPI/robots/Armar3/collisionModel/middle_l2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..40ccb7b24f987b0e7ba4a33eb5986affba684b9c
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/middle_l2.iv
@@ -0,0 +1,130 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0 0 1
+    }
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 -1.57
+	} 
+    Separator {
+        Normal {
+            vector      [ 0 -1 1.30104e-16,
+                          0 -1 1.30104e-16,
+                          0 -1 1.30104e-16,
+                          -6.76542e-17 8.50015e-17 -1,
+                          -6.76542e-17 8.50015e-17 -1,
+                          -6.76542e-17 8.50015e-17 -1,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          0 -1 1.30104e-16,
+                          0 -1 1.30104e-16,
+                          0 -1 1.30104e-16,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -6.76542e-17 8.50015e-17 -1,
+                          -6.76542e-17 8.50015e-17 -1,
+                          -6.76542e-17 8.50015e-17 -1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          0 1 -1.30104e-16,
+                          0 1 -1.30104e-16,
+                          0 1 -1.30104e-16,
+                          -6.4801e-17 0.287348 -0.957826,
+                          -6.4801e-17 0.287348 -0.957826,
+                          -6.4801e-17 0.287348 -0.957826,
+                          0 1 -1.30104e-16,
+                          0 1 -1.30104e-16,
+                          0 1 -1.30104e-16,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -6.4801e-17 0.287348 -0.957826,
+                          -6.4801e-17 0.287348 -0.957826,
+                          -6.4801e-17 0.287348 -0.957826 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 10 -1.25 4.25,
+                          -10 -1.25 -20.75,
+                          10 -1.25 -20.75,
+                          10 8.75 -20.75,
+                          10 -1.25 -20.75,
+                          -10 -1.25 -20.75,
+                          10 8.75 -20.75,
+                          10 -1.25 4.25,
+                          10 -1.25 -20.75,
+                          10 -1.25 4.25,
+                          -10 -1.25 4.25,
+                          -10 -1.25 -20.75,
+                          -10 58.75 4.25,
+                          -10 -1.25 -20.75,
+                          -10 -1.25 4.25,
+                          -10 8.75 -20.75,
+                          -10 -1.25 -20.75,
+                          -10 58.75 4.25,
+                          10 8.75 -20.75,
+                          -10 -1.25 -20.75,
+                          -10 8.75 -20.75,
+                          10 58.75 4.25,
+                          -10 -1.25 4.25,
+                          10 -1.25 4.25,
+                          -10 58.75 4.25,
+                          -10 -1.25 4.25,
+                          10 58.75 4.25,
+                          10 58.75 4.25,
+                          10 -1.25 4.25,
+                          10 58.75 -5.75,
+                          10 8.75 -20.75,
+                          10 58.75 -5.75,
+                          10 -1.25 4.25,
+                          10 58.75 4.25,
+                          10 58.75 -5.75,
+                          -10 58.75 -5.75,
+                          10 8.75 -20.75,
+                          -10 58.75 -5.75,
+                          10 58.75 -5.75,
+                          -10 58.75 4.25,
+                          10 58.75 4.25,
+                          -10 58.75 -5.75,
+                          -10 8.75 -20.75,
+                          -10 58.75 4.25,
+                          -10 58.75 -5.75,
+                          10 8.75 -20.75,
+                          -10 8.75 -20.75,
+                          -10 58.75 -5.75 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/middle_r1.iv b/data/RobotAPI/robots/Armar3/collisionModel/middle_r1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..ea65ade440bca4da11e054f2f321b52dba485128
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/middle_r1.iv
@@ -0,0 +1,110 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 -1.57
+	} 
+#	Transform {
+#		translation 0 0 0
+#		rotation 0 1 0 0
+#	} 
+    Separator {
+        Normal {
+            vector      [ -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 10.67 -2.4 3.75,
+                          -5 -2.4 -21.25,
+                          10.67 -2.4 -21.25,
+                          -5 42.25 -21.25,
+                          10.67 -2.4 -21.25,
+                          -5 -2.4 -21.25,
+                          10.67 42.25 -21.25,
+                          10.67 -2.4 3.75,
+                          10.67 -2.4 -21.25,
+                          -5 42.25 -21.25,
+                          10.67 42.25 -21.25,
+                          10.67 -2.4 -21.25,
+                          10.67 -2.4 3.75,
+                          -5 -2.4 3.75,
+                          -5 -2.4 -21.25,
+                          -5 42.25 3.75,
+                          -5 -2.4 -21.25,
+                          -5 -2.4 3.75,
+                          -5 42.25 -21.25,
+                          -5 -2.4 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 3.75,
+                          -5 -2.4 3.75,
+                          10.67 -2.4 3.75,
+                          -5 42.25 3.75,
+                          -5 -2.4 3.75,
+                          10.67 42.25 3.75,
+                          10.67 42.25 3.75,
+                          10.67 -2.4 3.75,
+                          10.67 42.25 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 3.75,
+                          10.67 42.25 -21.25,
+                          -5 42.25 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 -21.25 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/middle_r2.iv b/data/RobotAPI/robots/Armar3/collisionModel/middle_r2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..40ccb7b24f987b0e7ba4a33eb5986affba684b9c
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/middle_r2.iv
@@ -0,0 +1,130 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0 0 1
+    }
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 -1.57
+	} 
+    Separator {
+        Normal {
+            vector      [ 0 -1 1.30104e-16,
+                          0 -1 1.30104e-16,
+                          0 -1 1.30104e-16,
+                          -6.76542e-17 8.50015e-17 -1,
+                          -6.76542e-17 8.50015e-17 -1,
+                          -6.76542e-17 8.50015e-17 -1,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          0 -1 1.30104e-16,
+                          0 -1 1.30104e-16,
+                          0 -1 1.30104e-16,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -6.76542e-17 8.50015e-17 -1,
+                          -6.76542e-17 8.50015e-17 -1,
+                          -6.76542e-17 8.50015e-17 -1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          0 1 -1.30104e-16,
+                          0 1 -1.30104e-16,
+                          0 1 -1.30104e-16,
+                          -6.4801e-17 0.287348 -0.957826,
+                          -6.4801e-17 0.287348 -0.957826,
+                          -6.4801e-17 0.287348 -0.957826,
+                          0 1 -1.30104e-16,
+                          0 1 -1.30104e-16,
+                          0 1 -1.30104e-16,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -6.4801e-17 0.287348 -0.957826,
+                          -6.4801e-17 0.287348 -0.957826,
+                          -6.4801e-17 0.287348 -0.957826 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 10 -1.25 4.25,
+                          -10 -1.25 -20.75,
+                          10 -1.25 -20.75,
+                          10 8.75 -20.75,
+                          10 -1.25 -20.75,
+                          -10 -1.25 -20.75,
+                          10 8.75 -20.75,
+                          10 -1.25 4.25,
+                          10 -1.25 -20.75,
+                          10 -1.25 4.25,
+                          -10 -1.25 4.25,
+                          -10 -1.25 -20.75,
+                          -10 58.75 4.25,
+                          -10 -1.25 -20.75,
+                          -10 -1.25 4.25,
+                          -10 8.75 -20.75,
+                          -10 -1.25 -20.75,
+                          -10 58.75 4.25,
+                          10 8.75 -20.75,
+                          -10 -1.25 -20.75,
+                          -10 8.75 -20.75,
+                          10 58.75 4.25,
+                          -10 -1.25 4.25,
+                          10 -1.25 4.25,
+                          -10 58.75 4.25,
+                          -10 -1.25 4.25,
+                          10 58.75 4.25,
+                          10 58.75 4.25,
+                          10 -1.25 4.25,
+                          10 58.75 -5.75,
+                          10 8.75 -20.75,
+                          10 58.75 -5.75,
+                          10 -1.25 4.25,
+                          10 58.75 4.25,
+                          10 58.75 -5.75,
+                          -10 58.75 -5.75,
+                          10 8.75 -20.75,
+                          -10 58.75 -5.75,
+                          10 58.75 -5.75,
+                          -10 58.75 4.25,
+                          10 58.75 4.25,
+                          -10 58.75 -5.75,
+                          -10 8.75 -20.75,
+                          -10 58.75 4.25,
+                          -10 58.75 -5.75,
+                          10 8.75 -20.75,
+                          -10 8.75 -20.75,
+                          -10 58.75 -5.75 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/palm1_l.iv b/data/RobotAPI/robots/Armar3/collisionModel/palm1_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..f36a9e89ff6fc53e4048bde9d0900e39b980ae49
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/palm1_l.iv
@@ -0,0 +1,187 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.25 0.25 0.25
+    }
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 -1.57
+	} 
+    Separator {
+        Normal {
+            vector      [ -1.17961e-16 -1.4589e-14 -1,
+                          -1.17961e-16 -1.4589e-14 -1,
+                          -1.17961e-16 -1.4589e-14 -1,
+                          -2.22045e-16 1 -1.45717e-14,
+                          -2.22045e-16 1 -1.45717e-14,
+                          -2.22045e-16 1 -1.45717e-14,
+                          -1.17961e-16 -1.4589e-14 -1,
+                          -1.17961e-16 -1.4589e-14 -1,
+                          -1.17961e-16 -1.4589e-14 -1,
+                          1 1.11022e-16 -1.21431e-17,
+                          1 1.11022e-16 -1.21431e-17,
+                          1 1.11022e-16 -1.21431e-17,
+                          -2.22045e-16 1 -1.45717e-14,
+                          -2.22045e-16 1 -1.45717e-14,
+                          -2.22045e-16 1 -1.45717e-14,
+                          -1 -1.11022e-16 1.21431e-17,
+                          -1 -1.11022e-16 1.21431e-17,
+                          -1 -1.11022e-16 1.21431e-17,
+                          -1 -1.11022e-16 1.21431e-17,
+                          -1 -1.11022e-16 1.21431e-17,
+                          -1 -1.11022e-16 1.21431e-17,
+                          2.22045e-16 -1 1.45717e-14,
+                          2.22045e-16 -1 1.45717e-14,
+                          2.22045e-16 -1 1.45717e-14,
+                          2.22045e-16 -1 1.45717e-14,
+                          2.22045e-16 -1 1.45717e-14,
+                          2.22045e-16 -1 1.45717e-14,
+                          1 1.11022e-16 -1.21431e-17,
+                          1 1.11022e-16 -1.21431e-17,
+                          1 1.11022e-16 -1.21431e-17,
+                          1.17961e-16 1.4589e-14 1,
+                          1.17961e-16 1.4589e-14 1,
+                          1.17961e-16 1.4589e-14 1,
+                          1.17961e-16 1.4589e-14 1,
+                          1.17961e-16 1.4589e-14 1,
+                          1.17961e-16 1.4589e-14 1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -10.8 -18.5 -18.2,
+                          -10.8 23.5 -18.2,
+                          33.5 23.5 -18.2,
+                          -10.8 23.5 45.8,
+                          33.5 23.5 -18.2,
+                          -10.8 23.5 -18.2,
+                          33.5 -18.5 -18.2,
+                          -10.8 -18.5 -18.2,
+                          33.5 23.5 -18.2,
+                          33.5 23.5 45.8,
+                          33.5 -18.5 -18.2,
+                          33.5 23.5 -18.2,
+                          -10.8 23.5 45.8,
+                          33.5 23.5 45.8,
+                          33.5 23.5 -18.2,
+                          -10.8 -18.5 45.8,
+                          -10.8 23.5 -18.2,
+                          -10.8 -18.5 -18.2,
+                          -10.8 23.5 45.8,
+                          -10.8 23.5 -18.2,
+                          -10.8 -18.5 45.8,
+                          33.5 -18.5 45.8,
+                          -10.8 -18.5 -18.2,
+                          33.5 -18.5 -18.2,
+                          -10.8 -18.5 45.8,
+                          -10.8 -18.5 -18.2,
+                          33.5 -18.5 45.8,
+                          33.5 -18.5 45.8,
+                          33.5 -18.5 -18.2,
+                          33.5 23.5 45.8,
+                          -10.8 23.5 45.8,
+                          33.5 -18.5 45.8,
+                          33.5 23.5 45.8,
+                          -10.8 23.5 45.8,
+                          -10.8 -18.5 45.8,
+                          33.5 -18.5 45.8 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 1 1.11022e-16 -1.21431e-17,
+                          1 1.11022e-16 -1.21431e-17,
+                          1 1.11022e-16 -1.21431e-17,
+                          7.90251e-17 -0.326359 0.945246,
+                          7.90251e-17 -0.326359 0.945246,
+                          7.90251e-17 -0.326359 0.945246,
+                          1 1.11022e-16 -1.21431e-17,
+                          1 1.11022e-16 -1.21431e-17,
+                          1 1.11022e-16 -1.21431e-17,
+                          2.22045e-16 -1 1.45717e-14,
+                          2.22045e-16 -1 1.45717e-14,
+                          2.22045e-16 -1 1.45717e-14,
+                          2.22045e-16 -1 1.45717e-14,
+                          2.22045e-16 -1 1.45717e-14,
+                          2.22045e-16 -1 1.45717e-14,
+                          -2.22045e-16 1 -1.45717e-14,
+                          -2.22045e-16 1 -1.45717e-14,
+                          -2.22045e-16 1 -1.45717e-14,
+                          7.90251e-17 -0.326359 0.945246,
+                          7.90251e-17 -0.326359 0.945246,
+                          7.90251e-17 -0.326359 0.945246,
+                          -6.93889e-18 -1.45335e-14 -1,
+                          -6.93889e-18 -1.45335e-14 -1,
+                          -6.93889e-18 -1.45335e-14 -1,
+                          -2.22045e-16 1 -1.45717e-14,
+                          -2.22045e-16 1 -1.45717e-14,
+                          -2.22045e-16 1 -1.45717e-14,
+                          -6.93889e-18 -1.45335e-14 -1,
+                          -6.93889e-18 -1.45335e-14 -1,
+                          -6.93889e-18 -1.45335e-14 -1,
+                          -1 -1.11022e-16 1.21431e-17,
+                          -1 -1.11022e-16 1.21431e-17,
+                          -1 -1.11022e-16 1.21431e-17,
+                          -1 -1.11022e-16 1.21431e-17,
+                          -1 -1.11022e-16 1.21431e-17,
+                          -1 -1.11022e-16 1.21431e-17 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 33.5 -18.5 17.2,
+                          33.5 -18.5 41.6,
+                          33.5 -66 25.2,
+                          31.5 -66 25.2,
+                          33.5 -66 25.2,
+                          33.5 -18.5 41.6,
+                          33.5 -66 17.2,
+                          33.5 -18.5 17.2,
+                          33.5 -66 25.2,
+                          31.5 -66 17.2,
+                          33.5 -66 17.2,
+                          33.5 -66 25.2,
+                          31.5 -66 17.2,
+                          33.5 -66 25.2,
+                          31.5 -66 25.2,
+                          31.5 -18.5 41.6,
+                          33.5 -18.5 41.6,
+                          33.5 -18.5 17.2,
+                          31.5 -18.5 41.6,
+                          31.5 -66 25.2,
+                          33.5 -18.5 41.6,
+                          31.5 -18.5 17.2,
+                          33.5 -18.5 17.2,
+                          33.5 -66 17.2,
+                          31.5 -18.5 41.6,
+                          33.5 -18.5 17.2,
+                          31.5 -18.5 17.2,
+                          31.5 -18.5 17.2,
+                          33.5 -66 17.2,
+                          31.5 -66 17.2,
+                          31.5 -18.5 41.6,
+                          31.5 -66 17.2,
+                          31.5 -66 25.2,
+                          31.5 -18.5 41.6,
+                          31.5 -18.5 17.2,
+                          31.5 -66 17.2 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/palm1_r.iv b/data/RobotAPI/robots/Armar3/collisionModel/palm1_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..c8c655c1d7897236e7f18b412c2941865fb05dba
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/palm1_r.iv
@@ -0,0 +1,191 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.25 0.25 0.25
+    }
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 -1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 3.14
+	} 
+    Separator {
+        Normal {
+            vector      [ -6.93889e-18 -1.45856e-14 1,
+                          -6.93889e-18 -1.45856e-14 1,
+                          -6.93889e-18 -1.45856e-14 1,
+                          1 1.66533e-16 3.29597e-17,
+                          1 1.66533e-16 3.29597e-17,
+                          1 1.66533e-16 3.29597e-17,
+                          -1.11022e-16 1 1.46185e-14,
+                          -1.11022e-16 1 1.46185e-14,
+                          -1.11022e-16 1 1.46185e-14,
+                          1 1.66533e-16 3.29597e-17,
+                          1 1.66533e-16 3.29597e-17,
+                          1 1.66533e-16 3.29597e-17,
+                          -6.93889e-18 -1.45856e-14 1,
+                          -6.93889e-18 -1.45856e-14 1,
+                          -6.93889e-18 -1.45856e-14 1,
+                          1.11022e-16 -1 -1.46185e-14,
+                          1.11022e-16 -1 -1.46185e-14,
+                          1.11022e-16 -1 -1.46185e-14,
+                          1.11022e-16 -1 -1.46185e-14,
+                          1.11022e-16 -1 -1.46185e-14,
+                          1.11022e-16 -1 -1.46185e-14,
+                          -1 -1.66533e-16 -3.29597e-17,
+                          -1 -1.66533e-16 -3.29597e-17,
+                          -1 -1.66533e-16 -3.29597e-17,
+                          -1 -1.66533e-16 -3.29597e-17,
+                          -1 -1.66533e-16 -3.29597e-17,
+                          -1 -1.66533e-16 -3.29597e-17,
+                          -1.11022e-16 1 1.46185e-14,
+                          -1.11022e-16 1 1.46185e-14,
+                          -1.11022e-16 1 1.46185e-14,
+                          6.93889e-18 1.45856e-14 -1,
+                          6.93889e-18 1.45856e-14 -1,
+                          6.93889e-18 1.45856e-14 -1,
+                          6.93889e-18 1.45856e-14 -1,
+                          6.93889e-18 1.45856e-14 -1,
+                          6.93889e-18 1.45856e-14 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -10.8 23.5 18.2,
+                          33.5 -18.5 18.2,
+                          33.5 23.5 18.2,
+                          33.5 -18.5 -45.8,
+                          33.5 23.5 18.2,
+                          33.5 -18.5 18.2,
+                          33.5 23.5 -45.8,
+                          -10.8 23.5 18.2,
+                          33.5 23.5 18.2,
+                          33.5 -18.5 -45.8,
+                          33.5 23.5 -45.8,
+                          33.5 23.5 18.2,
+                          -10.8 23.5 18.2,
+                          -10.8 -18.5 18.2,
+                          33.5 -18.5 18.2,
+                          -10.8 -18.5 -45.8,
+                          33.5 -18.5 18.2,
+                          -10.8 -18.5 18.2,
+                          33.5 -18.5 -45.8,
+                          33.5 -18.5 18.2,
+                          -10.8 -18.5 -45.8,
+                          -10.8 23.5 -45.8,
+                          -10.8 -18.5 18.2,
+                          -10.8 23.5 18.2,
+                          -10.8 -18.5 -45.8,
+                          -10.8 -18.5 18.2,
+                          -10.8 23.5 -45.8,
+                          -10.8 23.5 -45.8,
+                          -10.8 23.5 18.2,
+                          33.5 23.5 -45.8,
+                          -10.8 -18.5 -45.8,
+                          -10.8 23.5 -45.8,
+                          33.5 23.5 -45.8,
+                          33.5 -18.5 -45.8,
+                          -10.8 -18.5 -45.8,
+                          33.5 23.5 -45.8 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 1 1.66533e-16 3.29597e-17,
+                          1 1.66533e-16 3.29597e-17,
+                          1 1.66533e-16 3.29597e-17,
+                          1.11022e-16 -1 -1.46185e-14,
+                          1.11022e-16 -1 -1.46185e-14,
+                          1.11022e-16 -1 -1.46185e-14,
+                          -6.21513e-17 -0.326359 -0.945246,
+                          -6.21513e-17 -0.326359 -0.945246,
+                          -6.21513e-17 -0.326359 -0.945246,
+                          -6.21513e-17 -0.326359 -0.945246,
+                          -6.21513e-17 -0.326359 -0.945246,
+                          -6.21513e-17 -0.326359 -0.945246,
+                          1 1.66533e-16 3.29597e-17,
+                          1 1.66533e-16 3.29597e-17,
+                          1 1.66533e-16 3.29597e-17,
+                          1.04083e-16 -1.453e-14 1,
+                          1.04083e-16 -1.453e-14 1,
+                          1.04083e-16 -1.453e-14 1,
+                          1.11022e-16 -1 -1.46185e-14,
+                          1.11022e-16 -1 -1.46185e-14,
+                          1.11022e-16 -1 -1.46185e-14,
+                          -1.11022e-16 1 1.46185e-14,
+                          -1.11022e-16 1 1.46185e-14,
+                          -1.11022e-16 1 1.46185e-14,
+                          1.04083e-16 -1.453e-14 1,
+                          1.04083e-16 -1.453e-14 1,
+                          1.04083e-16 -1.453e-14 1,
+                          -1.11022e-16 1 1.46185e-14,
+                          -1.11022e-16 1 1.46185e-14,
+                          -1.11022e-16 1 1.46185e-14,
+                          -1 -1.66533e-16 -3.29597e-17,
+                          -1 -1.66533e-16 -3.29597e-17,
+                          -1 -1.66533e-16 -3.29597e-17,
+                          -1 -1.66533e-16 -3.29597e-17,
+                          -1 -1.66533e-16 -3.29597e-17,
+                          -1 -1.66533e-16 -3.29597e-17 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 33.5 -18.5 -41.6,
+                          33.5 -66 -17.2,
+                          33.5 -66 -25.2,
+                          31.5 -66 -25.2,
+                          33.5 -66 -25.2,
+                          33.5 -66 -17.2,
+                          31.5 -18.5 -41.6,
+                          33.5 -18.5 -41.6,
+                          33.5 -66 -25.2,
+                          31.5 -18.5 -41.6,
+                          33.5 -66 -25.2,
+                          31.5 -66 -25.2,
+                          33.5 -18.5 -41.6,
+                          33.5 -18.5 -17.2,
+                          33.5 -66 -17.2,
+                          31.5 -66 -17.2,
+                          33.5 -66 -17.2,
+                          33.5 -18.5 -17.2,
+                          31.5 -66 -17.2,
+                          31.5 -66 -25.2,
+                          33.5 -66 -17.2,
+                          31.5 -18.5 -17.2,
+                          33.5 -18.5 -17.2,
+                          33.5 -18.5 -41.6,
+                          31.5 -66 -17.2,
+                          33.5 -18.5 -17.2,
+                          31.5 -18.5 -17.2,
+                          31.5 -18.5 -17.2,
+                          33.5 -18.5 -41.6,
+                          31.5 -18.5 -41.6,
+                          31.5 -18.5 -17.2,
+                          31.5 -18.5 -41.6,
+                          31.5 -66 -25.2,
+                          31.5 -66 -17.2,
+                          31.5 -18.5 -17.2,
+                          31.5 -66 -25.2 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/palm2_l.iv b/data/RobotAPI/robots/Armar3/collisionModel/palm2_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..5d0fff8ef82c43e332a9bb2c58495d6a73c38a3e
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/palm2_l.iv
@@ -0,0 +1,106 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.392 0.012 0.012
+    }
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+    Separator {
+        Normal {
+            vector      [ -1 1.22125e-15 -4.09395e-16,
+                          -1 1.22125e-15 -4.09395e-16,
+                          -1 1.22125e-15 -4.09395e-16,
+                          -7.77156e-16 -1 1.25941e-15,
+                          -7.77156e-16 -1 1.25941e-15,
+                          -7.77156e-16 -1 1.25941e-15,
+                          -3.86843e-16 1.39819e-15 1,
+                          -3.86843e-16 1.39819e-15 1,
+                          -3.86843e-16 1.39819e-15 1,
+                          -7.77156e-16 -1 1.25941e-15,
+                          -7.77156e-16 -1 1.25941e-15,
+                          -7.77156e-16 -1 1.25941e-15,
+                          -1 1.22125e-15 -4.09395e-16,
+                          -1 1.22125e-15 -4.09395e-16,
+                          -1 1.22125e-15 -4.09395e-16,
+                          3.86843e-16 -1.39819e-15 -1,
+                          3.86843e-16 -1.39819e-15 -1,
+                          3.86843e-16 -1.39819e-15 -1,
+                          3.86843e-16 -1.39819e-15 -1,
+                          3.86843e-16 -1.39819e-15 -1,
+                          3.86843e-16 -1.39819e-15 -1,
+                          7.77156e-16 1 -1.25941e-15,
+                          7.77156e-16 1 -1.25941e-15,
+                          7.77156e-16 1 -1.25941e-15,
+                          7.77156e-16 1 -1.25941e-15,
+                          7.77156e-16 1 -1.25941e-15,
+                          7.77156e-16 1 -1.25941e-15,
+                          -3.86843e-16 1.39819e-15 1,
+                          -3.86843e-16 1.39819e-15 1,
+                          -3.86843e-16 1.39819e-15 1,
+                          1 -1.22125e-15 4.09395e-16,
+                          1 -1.22125e-15 4.09395e-16,
+                          1 -1.22125e-15 4.09395e-16,
+                          1 -1.22125e-15 4.09395e-16,
+                          1 -1.22125e-15 4.09395e-16,
+                          1 -1.22125e-15 4.09395e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -79.5 42.25 20.75,
+                          -79.5 4.25 -4.25,
+                          -79.5 4.25 20.75,
+                          10 4.25 -4.25,
+                          -79.5 4.25 20.75,
+                          -79.5 4.25 -4.25,
+                          10 4.25 20.75,
+                          -79.5 42.25 20.75,
+                          -79.5 4.25 20.75,
+                          10 4.25 -4.25,
+                          10 4.25 20.75,
+                          -79.5 4.25 20.75,
+                          -79.5 42.25 20.75,
+                          -79.5 42.25 -4.25,
+                          -79.5 4.25 -4.25,
+                          10 42.25 -4.25,
+                          -79.5 4.25 -4.25,
+                          -79.5 42.25 -4.25,
+                          10 4.25 -4.25,
+                          -79.5 4.25 -4.25,
+                          10 42.25 -4.25,
+                          10 42.25 20.75,
+                          -79.5 42.25 -4.25,
+                          -79.5 42.25 20.75,
+                          10 42.25 -4.25,
+                          -79.5 42.25 -4.25,
+                          10 42.25 20.75,
+                          10 42.25 20.75,
+                          -79.5 42.25 20.75,
+                          10 4.25 20.75,
+                          10 42.25 -4.25,
+                          10 42.25 20.75,
+                          10 4.25 20.75,
+                          10 4.25 -4.25,
+                          10 42.25 -4.25,
+                          10 4.25 20.75 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/palm2_r.iv b/data/RobotAPI/robots/Armar3/collisionModel/palm2_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..ab71de90870e50ac867a08f8d417b67483e91f75
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/palm2_r.iv
@@ -0,0 +1,110 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.392 0.012 0.012
+    }
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 3.14
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+	} 
+    Separator {
+        Normal {
+            vector      [ -1 1.11022e-15 -3.46945e-17,
+                          -1 1.11022e-15 -3.46945e-17,
+                          -1 1.11022e-15 -3.46945e-17,
+                          3.46945e-18 -4.33681e-17 -1,
+                          3.46945e-18 -4.33681e-17 -1,
+                          3.46945e-18 -4.33681e-17 -1,
+                          -1 1.11022e-15 -3.46945e-17,
+                          -1 1.11022e-15 -3.46945e-17,
+                          -1 1.11022e-15 -3.46945e-17,
+                          -3.88578e-16 -1 1.56125e-17,
+                          -3.88578e-16 -1 1.56125e-17,
+                          -3.88578e-16 -1 1.56125e-17,
+                          3.46945e-18 -4.33681e-17 -1,
+                          3.46945e-18 -4.33681e-17 -1,
+                          3.46945e-18 -4.33681e-17 -1,
+                          3.88578e-16 1 -1.56125e-17,
+                          3.88578e-16 1 -1.56125e-17,
+                          3.88578e-16 1 -1.56125e-17,
+                          3.88578e-16 1 -1.56125e-17,
+                          3.88578e-16 1 -1.56125e-17,
+                          3.88578e-16 1 -1.56125e-17,
+                          -3.46945e-18 4.33681e-17 1,
+                          -3.46945e-18 4.33681e-17 1,
+                          -3.46945e-18 4.33681e-17 1,
+                          -3.46945e-18 4.33681e-17 1,
+                          -3.46945e-18 4.33681e-17 1,
+                          -3.46945e-18 4.33681e-17 1,
+                          -3.88578e-16 -1 1.56125e-17,
+                          -3.88578e-16 -1 1.56125e-17,
+                          -3.88578e-16 -1 1.56125e-17,
+                          1 -1.11022e-15 3.46945e-17,
+                          1 -1.11022e-15 3.46945e-17,
+                          1 -1.11022e-15 3.46945e-17,
+                          1 -1.11022e-15 3.46945e-17,
+                          1 -1.11022e-15 3.46945e-17,
+                          1 -1.11022e-15 3.46945e-17 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -79.5 42.25 4.25,
+                          -79.5 42.25 -20.75,
+                          -79.5 4.25 -20.75,
+                          10 42.25 -20.75,
+                          -79.5 4.25 -20.75,
+                          -79.5 42.25 -20.75,
+                          -79.5 4.25 4.25,
+                          -79.5 42.25 4.25,
+                          -79.5 4.25 -20.75,
+                          10 4.25 -20.75,
+                          -79.5 4.25 4.25,
+                          -79.5 4.25 -20.75,
+                          10 42.25 -20.75,
+                          10 4.25 -20.75,
+                          -79.5 4.25 -20.75,
+                          10 42.25 4.25,
+                          -79.5 42.25 -20.75,
+                          -79.5 42.25 4.25,
+                          10 42.25 -20.75,
+                          -79.5 42.25 -20.75,
+                          10 42.25 4.25,
+                          10 4.25 4.25,
+                          -79.5 42.25 4.25,
+                          -79.5 4.25 4.25,
+                          10 42.25 4.25,
+                          -79.5 42.25 4.25,
+                          10 4.25 4.25,
+                          10 4.25 4.25,
+                          -79.5 4.25 4.25,
+                          10 4.25 -20.75,
+                          10 42.25 -20.75,
+                          10 4.25 4.25,
+                          10 4.25 -20.75,
+                          10 42.25 -20.75,
+                          10 42.25 4.25,
+                          10 4.25 4.25 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/pinky_l1.iv b/data/RobotAPI/robots/Armar3/collisionModel/pinky_l1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..5afda54b141a25ca9d66e31c2fd044bb974b901a
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/pinky_l1.iv
@@ -0,0 +1,110 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 -1.57
+	} 
+	Transform {
+		translation -4.25 0 0
+		rotation 0 1 0 0
+	} 
+    Separator {
+        Normal {
+            vector      [ -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 10.67 -2.4 3.75,
+                          -5 -2.4 -21.25,
+                          10.67 -2.4 -21.25,
+                          -5 42.25 -21.25,
+                          10.67 -2.4 -21.25,
+                          -5 -2.4 -21.25,
+                          10.67 42.25 -21.25,
+                          10.67 -2.4 3.75,
+                          10.67 -2.4 -21.25,
+                          -5 42.25 -21.25,
+                          10.67 42.25 -21.25,
+                          10.67 -2.4 -21.25,
+                          10.67 -2.4 3.75,
+                          -5 -2.4 3.75,
+                          -5 -2.4 -21.25,
+                          -5 42.25 3.75,
+                          -5 -2.4 -21.25,
+                          -5 -2.4 3.75,
+                          -5 42.25 -21.25,
+                          -5 -2.4 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 3.75,
+                          -5 -2.4 3.75,
+                          10.67 -2.4 3.75,
+                          -5 42.25 3.75,
+                          -5 -2.4 3.75,
+                          10.67 42.25 3.75,
+                          10.67 42.25 3.75,
+                          10.67 -2.4 3.75,
+                          10.67 42.25 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 3.75,
+                          10.67 42.25 -21.25,
+                          -5 42.25 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 -21.25 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/pinky_l2.iv b/data/RobotAPI/robots/Armar3/collisionModel/pinky_l2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..805e4803cf962385d44429d52de832d9878e47c7
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/pinky_l2.iv
@@ -0,0 +1,130 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0 0 1
+    }
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+	} 
+    Separator {
+        Normal {
+            vector      [ -5.55112e-17 -1 1.249e-16,
+                          -5.55112e-17 -1 1.249e-16,
+                          -5.55112e-17 -1 1.249e-16,
+                          9.19403e-17 -5.0307e-17 1,
+                          9.19403e-17 -5.0307e-17 1,
+                          9.19403e-17 -5.0307e-17 1,
+                          -1 0 4.16334e-17,
+                          -1 0 4.16334e-17,
+                          -1 0 4.16334e-17,
+                          -5.55112e-17 -1 1.249e-16,
+                          -5.55112e-17 -1 1.249e-16,
+                          -5.55112e-17 -1 1.249e-16,
+                          1 0 -4.16334e-17,
+                          1 0 -4.16334e-17,
+                          1 0 -4.16334e-17,
+                          1 0 -4.16334e-17,
+                          1 0 -4.16334e-17,
+                          1 0 -4.16334e-17,
+                          9.19403e-17 -5.0307e-17 1,
+                          9.19403e-17 -5.0307e-17 1,
+                          9.19403e-17 -5.0307e-17 1,
+                          -9.19403e-17 5.0307e-17 -1,
+                          -9.19403e-17 5.0307e-17 -1,
+                          -9.19403e-17 5.0307e-17 -1,
+                          -9.19403e-17 5.0307e-17 -1,
+                          -9.19403e-17 5.0307e-17 -1,
+                          -9.19403e-17 5.0307e-17 -1,
+                          -1 0 4.16334e-17,
+                          -1 0 4.16334e-17,
+                          -1 0 4.16334e-17,
+                          -1 0 4.16334e-17,
+                          -1 0 4.16334e-17,
+                          -1 0 4.16334e-17,
+                          5.55112e-17 1 -1.249e-16,
+                          5.55112e-17 1 -1.249e-16,
+                          5.55112e-17 1 -1.249e-16,
+                          1.04014e-16 0.287348 0.957826,
+                          1.04014e-16 0.287348 0.957826,
+                          1.04014e-16 0.287348 0.957826,
+                          5.55112e-17 1 -1.249e-16,
+                          5.55112e-17 1 -1.249e-16,
+                          5.55112e-17 1 -1.249e-16,
+                          1 0 -4.16334e-17,
+                          1 0 -4.16334e-17,
+                          1 0 -4.16334e-17,
+                          1.04014e-16 0.287348 0.957826,
+                          1.04014e-16 0.287348 0.957826,
+                          1.04014e-16 0.287348 0.957826 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -10 -16.25 -4.25,
+                          10 -16.25 20.75,
+                          -10 -16.25 20.75,
+                          -10 -6.25 20.75,
+                          -10 -16.25 20.75,
+                          10 -16.25 20.75,
+                          -10 -6.25 20.75,
+                          -10 -16.25 -4.25,
+                          -10 -16.25 20.75,
+                          -10 -16.25 -4.25,
+                          10 -16.25 -4.25,
+                          10 -16.25 20.75,
+                          10 43.75 -4.25,
+                          10 -16.25 20.75,
+                          10 -16.25 -4.25,
+                          10 -6.25 20.75,
+                          10 -16.25 20.75,
+                          10 43.75 -4.25,
+                          -10 -6.25 20.75,
+                          10 -16.25 20.75,
+                          10 -6.25 20.75,
+                          -10 43.75 -4.25,
+                          10 -16.25 -4.25,
+                          -10 -16.25 -4.25,
+                          10 43.75 -4.25,
+                          10 -16.25 -4.25,
+                          -10 43.75 -4.25,
+                          -10 43.75 -4.25,
+                          -10 -16.25 -4.25,
+                          -10 43.75 5.75,
+                          -10 -6.25 20.75,
+                          -10 43.75 5.75,
+                          -10 -16.25 -4.25,
+                          -10 43.75 -4.25,
+                          -10 43.75 5.75,
+                          10 43.75 5.75,
+                          -10 -6.25 20.75,
+                          10 43.75 5.75,
+                          -10 43.75 5.75,
+                          10 43.75 -4.25,
+                          -10 43.75 -4.25,
+                          10 43.75 5.75,
+                          10 -6.25 20.75,
+                          10 43.75 -4.25,
+                          10 43.75 5.75,
+                          -10 -6.25 20.75,
+                          10 -6.25 20.75,
+                          10 43.75 5.75 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/pinky_r1.iv b/data/RobotAPI/robots/Armar3/collisionModel/pinky_r1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..ea65ade440bca4da11e054f2f321b52dba485128
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/pinky_r1.iv
@@ -0,0 +1,110 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 -1.57
+	} 
+#	Transform {
+#		translation 0 0 0
+#		rotation 0 1 0 0
+#	} 
+    Separator {
+        Normal {
+            vector      [ -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 10.67 -2.4 3.75,
+                          -5 -2.4 -21.25,
+                          10.67 -2.4 -21.25,
+                          -5 42.25 -21.25,
+                          10.67 -2.4 -21.25,
+                          -5 -2.4 -21.25,
+                          10.67 42.25 -21.25,
+                          10.67 -2.4 3.75,
+                          10.67 -2.4 -21.25,
+                          -5 42.25 -21.25,
+                          10.67 42.25 -21.25,
+                          10.67 -2.4 -21.25,
+                          10.67 -2.4 3.75,
+                          -5 -2.4 3.75,
+                          -5 -2.4 -21.25,
+                          -5 42.25 3.75,
+                          -5 -2.4 -21.25,
+                          -5 -2.4 3.75,
+                          -5 42.25 -21.25,
+                          -5 -2.4 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 3.75,
+                          -5 -2.4 3.75,
+                          10.67 -2.4 3.75,
+                          -5 42.25 3.75,
+                          -5 -2.4 3.75,
+                          10.67 42.25 3.75,
+                          10.67 42.25 3.75,
+                          10.67 -2.4 3.75,
+                          10.67 42.25 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 3.75,
+                          10.67 42.25 -21.25,
+                          -5 42.25 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 -21.25 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/pinky_r2.iv b/data/RobotAPI/robots/Armar3/collisionModel/pinky_r2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..805e4803cf962385d44429d52de832d9878e47c7
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/pinky_r2.iv
@@ -0,0 +1,130 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0 0 1
+    }
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+	} 
+    Separator {
+        Normal {
+            vector      [ -5.55112e-17 -1 1.249e-16,
+                          -5.55112e-17 -1 1.249e-16,
+                          -5.55112e-17 -1 1.249e-16,
+                          9.19403e-17 -5.0307e-17 1,
+                          9.19403e-17 -5.0307e-17 1,
+                          9.19403e-17 -5.0307e-17 1,
+                          -1 0 4.16334e-17,
+                          -1 0 4.16334e-17,
+                          -1 0 4.16334e-17,
+                          -5.55112e-17 -1 1.249e-16,
+                          -5.55112e-17 -1 1.249e-16,
+                          -5.55112e-17 -1 1.249e-16,
+                          1 0 -4.16334e-17,
+                          1 0 -4.16334e-17,
+                          1 0 -4.16334e-17,
+                          1 0 -4.16334e-17,
+                          1 0 -4.16334e-17,
+                          1 0 -4.16334e-17,
+                          9.19403e-17 -5.0307e-17 1,
+                          9.19403e-17 -5.0307e-17 1,
+                          9.19403e-17 -5.0307e-17 1,
+                          -9.19403e-17 5.0307e-17 -1,
+                          -9.19403e-17 5.0307e-17 -1,
+                          -9.19403e-17 5.0307e-17 -1,
+                          -9.19403e-17 5.0307e-17 -1,
+                          -9.19403e-17 5.0307e-17 -1,
+                          -9.19403e-17 5.0307e-17 -1,
+                          -1 0 4.16334e-17,
+                          -1 0 4.16334e-17,
+                          -1 0 4.16334e-17,
+                          -1 0 4.16334e-17,
+                          -1 0 4.16334e-17,
+                          -1 0 4.16334e-17,
+                          5.55112e-17 1 -1.249e-16,
+                          5.55112e-17 1 -1.249e-16,
+                          5.55112e-17 1 -1.249e-16,
+                          1.04014e-16 0.287348 0.957826,
+                          1.04014e-16 0.287348 0.957826,
+                          1.04014e-16 0.287348 0.957826,
+                          5.55112e-17 1 -1.249e-16,
+                          5.55112e-17 1 -1.249e-16,
+                          5.55112e-17 1 -1.249e-16,
+                          1 0 -4.16334e-17,
+                          1 0 -4.16334e-17,
+                          1 0 -4.16334e-17,
+                          1.04014e-16 0.287348 0.957826,
+                          1.04014e-16 0.287348 0.957826,
+                          1.04014e-16 0.287348 0.957826 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -10 -16.25 -4.25,
+                          10 -16.25 20.75,
+                          -10 -16.25 20.75,
+                          -10 -6.25 20.75,
+                          -10 -16.25 20.75,
+                          10 -16.25 20.75,
+                          -10 -6.25 20.75,
+                          -10 -16.25 -4.25,
+                          -10 -16.25 20.75,
+                          -10 -16.25 -4.25,
+                          10 -16.25 -4.25,
+                          10 -16.25 20.75,
+                          10 43.75 -4.25,
+                          10 -16.25 20.75,
+                          10 -16.25 -4.25,
+                          10 -6.25 20.75,
+                          10 -16.25 20.75,
+                          10 43.75 -4.25,
+                          -10 -6.25 20.75,
+                          10 -16.25 20.75,
+                          10 -6.25 20.75,
+                          -10 43.75 -4.25,
+                          10 -16.25 -4.25,
+                          -10 -16.25 -4.25,
+                          10 43.75 -4.25,
+                          10 -16.25 -4.25,
+                          -10 43.75 -4.25,
+                          -10 43.75 -4.25,
+                          -10 -16.25 -4.25,
+                          -10 43.75 5.75,
+                          -10 -6.25 20.75,
+                          -10 43.75 5.75,
+                          -10 -16.25 -4.25,
+                          -10 43.75 -4.25,
+                          -10 43.75 5.75,
+                          10 43.75 5.75,
+                          -10 -6.25 20.75,
+                          10 43.75 5.75,
+                          -10 43.75 5.75,
+                          10 43.75 -4.25,
+                          -10 43.75 -4.25,
+                          10 43.75 5.75,
+                          10 -6.25 20.75,
+                          10 43.75 -4.25,
+                          10 43.75 5.75,
+                          -10 -6.25 20.75,
+                          10 -6.25 20.75,
+                          10 43.75 5.75 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/platform.iv b/data/RobotAPI/robots/Armar3/collisionModel/platform.iv
new file mode 100644
index 0000000000000000000000000000000000000000..59e60c34a8151285be4dbb03269c376432a5827c
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/platform.iv
@@ -0,0 +1,263 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.54 0.87 0.89
+    } 
+    RotationXYZ {
+      axis X
+      angle 1.57
+    }
+    RotationXYZ{
+      axis Z
+      angle -1.57
+     }
+# Transform {
+#  rotation 0 1 0 1.57
+# }
+#  Transform {
+#  rotation 1 0 0 3.1415
+# }
+
+    Material {
+        diffuseColor    0.54 0.87 0.89
+    }
+    Separator {
+        Normal {
+            vector      [ -0.156249 -3.78809e-17 -0.987718,
+                          -0.156249 -3.78809e-17 -0.987718,
+                          -0.156249 -3.78809e-17 -0.987718,
+                          -2.51675e-16 0.605083 -0.796162,
+                          -2.51675e-16 0.605083 -0.796162,
+                          -2.51675e-16 0.605083 -0.796162,
+                          -0.156249 -3.78809e-17 -0.987718,
+                          -0.156249 -3.78809e-17 -0.987718,
+                          -0.156249 -3.78809e-17 -0.987718,
+                          -3.16111e-16 -3.8352e-17 -1,
+                          -3.16111e-16 -3.8352e-17 -1,
+                          -3.16111e-16 -3.8352e-17 -1,
+                          -2.51675e-16 0.605083 -0.796162,
+                          -2.51675e-16 0.605083 -0.796162,
+                          -2.51675e-16 0.605083 -0.796162,
+                          -3.16111e-16 -3.8352e-17 -1,
+                          -3.16111e-16 -3.8352e-17 -1,
+                          -3.16111e-16 -3.8352e-17 -1,
+                          -0.156249 -3.78809e-17 -0.987718,
+                          -0.156249 -3.78809e-17 -0.987718,
+                          -0.156249 -3.78809e-17 -0.987718,
+                          -0.0844431 0.996428 -1.15216e-17,
+                          -0.0844431 0.996428 -1.15216e-17,
+                          -0.0844431 0.996428 -1.15216e-17,
+                          -0.156249 -3.78809e-17 -0.987718,
+                          -0.156249 -3.78809e-17 -0.987718,
+                          -0.156249 -3.78809e-17 -0.987718,
+                          -0.0844431 0.996428 -1.15216e-17,
+                          -0.0844431 0.996428 -1.15216e-17,
+                          -0.0844431 0.996428 -1.15216e-17,
+                          -0.0844431 0.996428 -1.15216e-17,
+                          -0.0844431 0.996428 -1.15216e-17,
+                          -0.0844431 0.996428 -1.15216e-17,
+                          -1 0 3.16111e-16,
+                          -1 0 3.16111e-16,
+                          -1 0 3.16111e-16,
+                          -0.0844431 0.996428 -1.15216e-17,
+                          -0.0844431 0.996428 -1.15216e-17,
+                          -0.0844431 0.996428 -1.15216e-17,
+                          -0.0844431 -0.996428 6.49083e-17,
+                          -0.0844431 -0.996428 6.49083e-17,
+                          -0.0844431 -0.996428 6.49083e-17,
+                          -1 0 3.16111e-16,
+                          -1 0 3.16111e-16,
+                          -1 0 3.16111e-16,
+                          -2.51675e-16 -0.605083 -0.796162,
+                          -2.51675e-16 -0.605083 -0.796162,
+                          -2.51675e-16 -0.605083 -0.796162,
+                          -2.51675e-16 -0.605083 -0.796162,
+                          -2.51675e-16 -0.605083 -0.796162,
+                          -2.51675e-16 -0.605083 -0.796162,
+                          -0.0844431 -0.996428 6.49083e-17,
+                          -0.0844431 -0.996428 6.49083e-17,
+                          -0.0844431 -0.996428 6.49083e-17,
+                          -0.0844431 -0.996428 6.49083e-17,
+                          -0.0844431 -0.996428 6.49083e-17,
+                          -0.0844431 -0.996428 6.49083e-17,
+                          1 0 -3.16111e-16,
+                          1 0 -3.16111e-16,
+                          1 0 -3.16111e-16,
+                          3.16111e-16 3.8352e-17 1,
+                          3.16111e-16 3.8352e-17 1,
+                          3.16111e-16 3.8352e-17 1,
+                          2.32636e-16 -0.677057 0.735931,
+                          2.32636e-16 -0.677057 0.735931,
+                          2.32636e-16 -0.677057 0.735931,
+                          1 0 -3.16111e-16,
+                          1 0 -3.16111e-16,
+                          1 0 -3.16111e-16,
+                          2.32636e-16 0.677057 0.735931,
+                          2.32636e-16 0.677057 0.735931,
+                          2.32636e-16 0.677057 0.735931,
+                          3.16111e-16 3.8352e-17 1,
+                          3.16111e-16 3.8352e-17 1,
+                          3.16111e-16 3.8352e-17 1,
+                          2.32636e-16 0.677057 0.735931,
+                          2.32636e-16 0.677057 0.735931,
+                          2.32636e-16 0.677057 0.735931,
+                          1 0 -3.16111e-16,
+                          1 0 -3.16111e-16,
+                          1 0 -3.16111e-16,
+                          1 0 -3.16111e-16,
+                          1 0 -3.16111e-16,
+                          1 0 -3.16111e-16,
+                          1 0 -3.16111e-16,
+                          1 0 -3.16111e-16,
+                          1 0 -3.16111e-16,
+                          1 0 -3.16111e-16,
+                          1 0 -3.16111e-16,
+                          1 0 -3.16111e-16,
+                          -0.0844431 -0.996428 6.49083e-17,
+                          -0.0844431 -0.996428 6.49083e-17,
+                          -0.0844431 -0.996428 6.49083e-17,
+                          2.32636e-16 -0.677057 0.735931,
+                          2.32636e-16 -0.677057 0.735931,
+                          2.32636e-16 -0.677057 0.735931,
+                          -0.291807 3.66828e-17 0.956477,
+                          -0.291807 3.66828e-17 0.956477,
+                          -0.291807 3.66828e-17 0.956477,
+                          -0.291807 3.66828e-17 0.956477,
+                          -0.291807 3.66828e-17 0.956477,
+                          -0.291807 3.66828e-17 0.956477,
+                          -0.291807 3.66828e-17 0.956477,
+                          -0.291807 3.66828e-17 0.956477,
+                          -0.291807 3.66828e-17 0.956477,
+                          -0.291807 3.66828e-17 0.956477,
+                          -0.291807 3.66828e-17 0.956477,
+                          -0.291807 3.66828e-17 0.956477 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -853.553 -255.665 -222.125,
+                          -853.553 255.665 -222.125,
+                          -189.643 117.474 -327.15,
+                          2.43179e-13 328 -167.15,
+                          -189.643 117.474 -327.15,
+                          -853.553 255.665 -222.125,
+                          -189.643 -117.474 -327.15,
+                          -853.553 -255.665 -222.125,
+                          -189.643 117.474 -327.15,
+                          1.92601e-13 -117.474 -327.15,
+                          -189.643 -117.474 -327.15,
+                          -189.643 117.474 -327.15,
+                          1.92601e-13 117.474 -327.15,
+                          -189.643 117.474 -327.15,
+                          2.43179e-13 328 -167.15,
+                          1.92601e-13 -117.474 -327.15,
+                          -189.643 117.474 -327.15,
+                          1.92601e-13 117.474 -327.15,
+                          -885 -253 -217.15,
+                          -885 253 -217.15,
+                          -853.553 255.665 -222.125,
+                          -600.443 277.115 189.664,
+                          -853.553 255.665 -222.125,
+                          -885 253 -217.15,
+                          -853.553 -255.665 -222.125,
+                          -885 -253 -217.15,
+                          -853.553 255.665 -222.125,
+                          2.43179e-13 328 -167.15,
+                          -853.553 255.665 -222.125,
+                          3.41174e-13 328 142.85,
+                          -600.443 277.115 189.664,
+                          3.41174e-13 328 142.85,
+                          -853.553 255.665 -222.125,
+                          -885 253 102.85,
+                          -885 253 -217.15,
+                          -885 -253 -217.15,
+                          -600.443 277.115 189.664,
+                          -885 253 -217.15,
+                          -885 253 102.85,
+                          -885 -253 102.85,
+                          -885 -253 -217.15,
+                          -853.553 -255.665 -222.125,
+                          -885 253 102.85,
+                          -885 -253 -217.15,
+                          -885 -253 102.85,
+                          1.92601e-13 -117.474 -327.15,
+                          -853.553 -255.665 -222.125,
+                          -189.643 -117.474 -327.15,
+                          2.43179e-13 -328 -167.15,
+                          -853.553 -255.665 -222.125,
+                          1.92601e-13 -117.474 -327.15,
+                          -600.443 -277.115 189.664,
+                          -853.553 -255.665 -222.125,
+                          2.43179e-13 -328 -167.15,
+                          -885 -253 102.85,
+                          -853.553 -255.665 -222.125,
+                          -600.443 -277.115 189.664,
+                          3.41174e-13 -328 142.85,
+                          4.01235e-13 121.478 332.85,
+                          4.01235e-13 -121.478 332.85,
+                          -131.111 -121.478 332.85,
+                          4.01235e-13 -121.478 332.85,
+                          4.01235e-13 121.478 332.85,
+                          -131.111 -121.478 332.85,
+                          3.41174e-13 -328 142.85,
+                          4.01235e-13 -121.478 332.85,
+                          3.41174e-13 -328 142.85,
+                          3.41174e-13 328 142.85,
+                          4.01235e-13 121.478 332.85,
+                          -600.443 277.115 189.664,
+                          4.01235e-13 121.478 332.85,
+                          3.41174e-13 328 142.85,
+                          -131.111 121.478 332.85,
+                          -131.111 -121.478 332.85,
+                          4.01235e-13 121.478 332.85,
+                          -131.111 121.478 332.85,
+                          4.01235e-13 121.478 332.85,
+                          -600.443 277.115 189.664,
+                          2.43179e-13 -328 -167.15,
+                          2.43179e-13 328 -167.15,
+                          3.41174e-13 328 142.85,
+                          3.41174e-13 -328 142.85,
+                          2.43179e-13 -328 -167.15,
+                          3.41174e-13 328 142.85,
+                          1.92601e-13 -117.474 -327.15,
+                          1.92601e-13 117.474 -327.15,
+                          2.43179e-13 328 -167.15,
+                          2.43179e-13 -328 -167.15,
+                          1.92601e-13 -117.474 -327.15,
+                          2.43179e-13 328 -167.15,
+                          -600.443 -277.115 189.664,
+                          2.43179e-13 -328 -167.15,
+                          3.41174e-13 -328 142.85,
+                          -600.443 -277.115 189.664,
+                          3.41174e-13 -328 142.85,
+                          -131.111 -121.478 332.85,
+                          -600.443 277.115 189.664,
+                          -600.443 -277.115 189.664,
+                          -131.111 -121.478 332.85,
+                          -131.111 121.478 332.85,
+                          -600.443 277.115 189.664,
+                          -131.111 -121.478 332.85,
+                          -885 253 102.85,
+                          -885 -253 102.85,
+                          -600.443 -277.115 189.664,
+                          -600.443 277.115 189.664,
+                          -885 253 102.85,
+                          -600.443 -277.115 189.664 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/ring_l1.iv b/data/RobotAPI/robots/Armar3/collisionModel/ring_l1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..5afda54b141a25ca9d66e31c2fd044bb974b901a
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/ring_l1.iv
@@ -0,0 +1,110 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 -1.57
+	} 
+	Transform {
+		translation -4.25 0 0
+		rotation 0 1 0 0
+	} 
+    Separator {
+        Normal {
+            vector      [ -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 10.67 -2.4 3.75,
+                          -5 -2.4 -21.25,
+                          10.67 -2.4 -21.25,
+                          -5 42.25 -21.25,
+                          10.67 -2.4 -21.25,
+                          -5 -2.4 -21.25,
+                          10.67 42.25 -21.25,
+                          10.67 -2.4 3.75,
+                          10.67 -2.4 -21.25,
+                          -5 42.25 -21.25,
+                          10.67 42.25 -21.25,
+                          10.67 -2.4 -21.25,
+                          10.67 -2.4 3.75,
+                          -5 -2.4 3.75,
+                          -5 -2.4 -21.25,
+                          -5 42.25 3.75,
+                          -5 -2.4 -21.25,
+                          -5 -2.4 3.75,
+                          -5 42.25 -21.25,
+                          -5 -2.4 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 3.75,
+                          -5 -2.4 3.75,
+                          10.67 -2.4 3.75,
+                          -5 42.25 3.75,
+                          -5 -2.4 3.75,
+                          10.67 42.25 3.75,
+                          10.67 42.25 3.75,
+                          10.67 -2.4 3.75,
+                          10.67 42.25 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 3.75,
+                          10.67 42.25 -21.25,
+                          -5 42.25 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 -21.25 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/ring_l2.iv b/data/RobotAPI/robots/Armar3/collisionModel/ring_l2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..8b1d59dcbd8d10bf880a4963af848e76c7611041
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/ring_l2.iv
@@ -0,0 +1,130 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0 0 1
+    }
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+	} 
+    Separator {
+        Normal {
+            vector      [ 2.22045e-16 -1 -5.20417e-18,
+                          2.22045e-16 -1 -5.20417e-18,
+                          2.22045e-16 -1 -5.20417e-18,
+                          6.245e-17 2.42861e-17 1,
+                          6.245e-17 2.42861e-17 1,
+                          6.245e-17 2.42861e-17 1,
+                          -1 1.11022e-16 1.56125e-17,
+                          -1 1.11022e-16 1.56125e-17,
+                          -1 1.11022e-16 1.56125e-17,
+                          2.22045e-16 -1 -5.20417e-18,
+                          2.22045e-16 -1 -5.20417e-18,
+                          2.22045e-16 -1 -5.20417e-18,
+                          1 -1.11022e-16 -1.56125e-17,
+                          1 -1.11022e-16 -1.56125e-17,
+                          1 -1.11022e-16 -1.56125e-17,
+                          1 -1.11022e-16 -1.56125e-17,
+                          1 -1.11022e-16 -1.56125e-17,
+                          1 -1.11022e-16 -1.56125e-17,
+                          6.245e-17 2.42861e-17 1,
+                          6.245e-17 2.42861e-17 1,
+                          6.245e-17 2.42861e-17 1,
+                          -6.245e-17 -2.42861e-17 -1,
+                          -6.245e-17 -2.42861e-17 -1,
+                          -6.245e-17 -2.42861e-17 -1,
+                          -6.245e-17 -2.42861e-17 -1,
+                          -6.245e-17 -2.42861e-17 -1,
+                          -6.245e-17 -2.42861e-17 -1,
+                          -1 1.11022e-16 1.56125e-17,
+                          -1 1.11022e-16 1.56125e-17,
+                          -1 1.11022e-16 1.56125e-17,
+                          -1 1.11022e-16 1.56125e-17,
+                          -1 1.11022e-16 1.56125e-17,
+                          -1 1.11022e-16 1.56125e-17,
+                          -2.22045e-16 1 5.20417e-18,
+                          -2.22045e-16 1 5.20417e-18,
+                          -2.22045e-16 1 5.20417e-18,
+                          -3.98775e-18 0.287348 0.957826,
+                          -3.98775e-18 0.287348 0.957826,
+                          -3.98775e-18 0.287348 0.957826,
+                          -2.22045e-16 1 5.20417e-18,
+                          -2.22045e-16 1 5.20417e-18,
+                          -2.22045e-16 1 5.20417e-18,
+                          1 -1.11022e-16 -1.56125e-17,
+                          1 -1.11022e-16 -1.56125e-17,
+                          1 -1.11022e-16 -1.56125e-17,
+                          -3.98775e-18 0.287348 0.957826,
+                          -3.98775e-18 0.287348 0.957826,
+                          -3.98775e-18 0.287348 0.957826 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -10 -8.75 -4.25,
+                          10 -8.75 20.75,
+                          -10 -8.75 20.75,
+                          -10 1.25 20.75,
+                          -10 -8.75 20.75,
+                          10 -8.75 20.75,
+                          -10 1.25 20.75,
+                          -10 -8.75 -4.25,
+                          -10 -8.75 20.75,
+                          -10 -8.75 -4.25,
+                          10 -8.75 -4.25,
+                          10 -8.75 20.75,
+                          10 51.25 -4.25,
+                          10 -8.75 20.75,
+                          10 -8.75 -4.25,
+                          10 1.25 20.75,
+                          10 -8.75 20.75,
+                          10 51.25 -4.25,
+                          -10 1.25 20.75,
+                          10 -8.75 20.75,
+                          10 1.25 20.75,
+                          -10 51.25 -4.25,
+                          10 -8.75 -4.25,
+                          -10 -8.75 -4.25,
+                          10 51.25 -4.25,
+                          10 -8.75 -4.25,
+                          -10 51.25 -4.25,
+                          -10 51.25 -4.25,
+                          -10 -8.75 -4.25,
+                          -10 51.25 5.75,
+                          -10 1.25 20.75,
+                          -10 51.25 5.75,
+                          -10 -8.75 -4.25,
+                          -10 51.25 -4.25,
+                          -10 51.25 5.75,
+                          10 51.25 5.75,
+                          -10 1.25 20.75,
+                          10 51.25 5.75,
+                          -10 51.25 5.75,
+                          10 51.25 -4.25,
+                          -10 51.25 -4.25,
+                          10 51.25 5.75,
+                          10 1.25 20.75,
+                          10 51.25 -4.25,
+                          10 51.25 5.75,
+                          -10 1.25 20.75,
+                          10 1.25 20.75,
+                          10 51.25 5.75 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/ring_r1.iv b/data/RobotAPI/robots/Armar3/collisionModel/ring_r1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..1c0c9c155d2f97e953764670127009e425ac246c
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/ring_r1.iv
@@ -0,0 +1,106 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 -1.57
+	} 
+    Separator {
+        Normal {
+            vector      [ -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 10.67 -2.4 3.75,
+                          -5 -2.4 -21.25,
+                          10.67 -2.4 -21.25,
+                          -5 42.25 -21.25,
+                          10.67 -2.4 -21.25,
+                          -5 -2.4 -21.25,
+                          10.67 42.25 -21.25,
+                          10.67 -2.4 3.75,
+                          10.67 -2.4 -21.25,
+                          -5 42.25 -21.25,
+                          10.67 42.25 -21.25,
+                          10.67 -2.4 -21.25,
+                          10.67 -2.4 3.75,
+                          -5 -2.4 3.75,
+                          -5 -2.4 -21.25,
+                          -5 42.25 3.75,
+                          -5 -2.4 -21.25,
+                          -5 -2.4 3.75,
+                          -5 42.25 -21.25,
+                          -5 -2.4 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 3.75,
+                          -5 -2.4 3.75,
+                          10.67 -2.4 3.75,
+                          -5 42.25 3.75,
+                          -5 -2.4 3.75,
+                          10.67 42.25 3.75,
+                          10.67 42.25 3.75,
+                          10.67 -2.4 3.75,
+                          10.67 42.25 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 3.75,
+                          10.67 42.25 -21.25,
+                          -5 42.25 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 -21.25 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/ring_r2.iv b/data/RobotAPI/robots/Armar3/collisionModel/ring_r2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..8b1d59dcbd8d10bf880a4963af848e76c7611041
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/ring_r2.iv
@@ -0,0 +1,130 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0 0 1
+    }
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+	} 
+    Separator {
+        Normal {
+            vector      [ 2.22045e-16 -1 -5.20417e-18,
+                          2.22045e-16 -1 -5.20417e-18,
+                          2.22045e-16 -1 -5.20417e-18,
+                          6.245e-17 2.42861e-17 1,
+                          6.245e-17 2.42861e-17 1,
+                          6.245e-17 2.42861e-17 1,
+                          -1 1.11022e-16 1.56125e-17,
+                          -1 1.11022e-16 1.56125e-17,
+                          -1 1.11022e-16 1.56125e-17,
+                          2.22045e-16 -1 -5.20417e-18,
+                          2.22045e-16 -1 -5.20417e-18,
+                          2.22045e-16 -1 -5.20417e-18,
+                          1 -1.11022e-16 -1.56125e-17,
+                          1 -1.11022e-16 -1.56125e-17,
+                          1 -1.11022e-16 -1.56125e-17,
+                          1 -1.11022e-16 -1.56125e-17,
+                          1 -1.11022e-16 -1.56125e-17,
+                          1 -1.11022e-16 -1.56125e-17,
+                          6.245e-17 2.42861e-17 1,
+                          6.245e-17 2.42861e-17 1,
+                          6.245e-17 2.42861e-17 1,
+                          -6.245e-17 -2.42861e-17 -1,
+                          -6.245e-17 -2.42861e-17 -1,
+                          -6.245e-17 -2.42861e-17 -1,
+                          -6.245e-17 -2.42861e-17 -1,
+                          -6.245e-17 -2.42861e-17 -1,
+                          -6.245e-17 -2.42861e-17 -1,
+                          -1 1.11022e-16 1.56125e-17,
+                          -1 1.11022e-16 1.56125e-17,
+                          -1 1.11022e-16 1.56125e-17,
+                          -1 1.11022e-16 1.56125e-17,
+                          -1 1.11022e-16 1.56125e-17,
+                          -1 1.11022e-16 1.56125e-17,
+                          -2.22045e-16 1 5.20417e-18,
+                          -2.22045e-16 1 5.20417e-18,
+                          -2.22045e-16 1 5.20417e-18,
+                          -3.98775e-18 0.287348 0.957826,
+                          -3.98775e-18 0.287348 0.957826,
+                          -3.98775e-18 0.287348 0.957826,
+                          -2.22045e-16 1 5.20417e-18,
+                          -2.22045e-16 1 5.20417e-18,
+                          -2.22045e-16 1 5.20417e-18,
+                          1 -1.11022e-16 -1.56125e-17,
+                          1 -1.11022e-16 -1.56125e-17,
+                          1 -1.11022e-16 -1.56125e-17,
+                          -3.98775e-18 0.287348 0.957826,
+                          -3.98775e-18 0.287348 0.957826,
+                          -3.98775e-18 0.287348 0.957826 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -10 -8.75 -4.25,
+                          10 -8.75 20.75,
+                          -10 -8.75 20.75,
+                          -10 1.25 20.75,
+                          -10 -8.75 20.75,
+                          10 -8.75 20.75,
+                          -10 1.25 20.75,
+                          -10 -8.75 -4.25,
+                          -10 -8.75 20.75,
+                          -10 -8.75 -4.25,
+                          10 -8.75 -4.25,
+                          10 -8.75 20.75,
+                          10 51.25 -4.25,
+                          10 -8.75 20.75,
+                          10 -8.75 -4.25,
+                          10 1.25 20.75,
+                          10 -8.75 20.75,
+                          10 51.25 -4.25,
+                          -10 1.25 20.75,
+                          10 -8.75 20.75,
+                          10 1.25 20.75,
+                          -10 51.25 -4.25,
+                          10 -8.75 -4.25,
+                          -10 -8.75 -4.25,
+                          10 51.25 -4.25,
+                          10 -8.75 -4.25,
+                          -10 51.25 -4.25,
+                          -10 51.25 -4.25,
+                          -10 -8.75 -4.25,
+                          -10 51.25 5.75,
+                          -10 1.25 20.75,
+                          -10 51.25 5.75,
+                          -10 -8.75 -4.25,
+                          -10 51.25 -4.25,
+                          -10 51.25 5.75,
+                          10 51.25 5.75,
+                          -10 1.25 20.75,
+                          10 51.25 5.75,
+                          -10 51.25 5.75,
+                          10 51.25 -4.25,
+                          -10 51.25 -4.25,
+                          10 51.25 5.75,
+                          10 1.25 20.75,
+                          10 51.25 -4.25,
+                          10 51.25 5.75,
+                          -10 1.25 20.75,
+                          10 1.25 20.75,
+                          10 51.25 5.75 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/shoulder_l.iv b/data/RobotAPI/robots/Armar3/collisionModel/shoulder_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..e4f6d8edbe5361ac48c2fb5bcd5d73a458b16320
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/shoulder_l.iv
@@ -0,0 +1,161 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.6 0.6 0.6
+    }
+	  Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	}
+	  Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+	}
+	  Transform {
+		translation 0 -110 0
+		rotation 0 0 0 0
+	  }
+
+    Separator {
+        Normal {
+            vector      [ -0.999893 -0.0146287 -7.98353e-16,
+                          -0.999893 -0.0146287 -7.98353e-16,
+                          -0.999893 -0.0146287 -7.98353e-16,
+                          -0.00982371 0.671467 -0.740969,
+                          -0.00982371 0.671467 -0.740969,
+                          -0.00982371 0.671467 -0.740969,
+                          -0.999893 -0.0146287 -7.98353e-16,
+                          -0.999893 -0.0146287 -7.98353e-16,
+                          -0.999893 -0.0146287 -7.98353e-16,
+                          -0.999893 -0.0146287 -7.98353e-16,
+                          -0.999893 -0.0146287 -7.98353e-16,
+                          -0.999893 -0.0146287 -7.98353e-16,
+                          6.99961e-16 -5.55112e-16 -1,
+                          6.99961e-16 -5.55112e-16 -1,
+                          6.99961e-16 -5.55112e-16 -1,
+                          -0.00982371 0.671467 -0.740969,
+                          -0.00982371 0.671467 -0.740969,
+                          -0.00982371 0.671467 -0.740969,
+                          -0.0146287 0.999893 -5.55112e-16,
+                          -0.0146287 0.999893 -5.55112e-16,
+                          -0.0146287 0.999893 -5.55112e-16,
+                          -0.0146287 0.999893 -5.55112e-16,
+                          -0.0146287 0.999893 -5.55112e-16,
+                          -0.0146287 0.999893 -5.55112e-16,
+                          -0.00615312 0.420576 0.907236,
+                          -0.00615312 0.420576 0.907236,
+                          -0.00615312 0.420576 0.907236,
+                          -0.00615312 0.420576 0.907236,
+                          -0.00615312 0.420576 0.907236,
+                          -0.00615312 0.420576 0.907236,
+                          -0.999893 -0.0146287 -7.98353e-16,
+                          -0.999893 -0.0146287 -7.98353e-16,
+                          -0.999893 -0.0146287 -7.98353e-16,
+                          -6.99961e-16 5.55112e-16 1,
+                          -6.99961e-16 5.55112e-16 1,
+                          -6.99961e-16 5.55112e-16 1,
+                          -6.99961e-16 5.55112e-16 1,
+                          -6.99961e-16 5.55112e-16 1,
+                          -6.99961e-16 5.55112e-16 1,
+                          0.0146287 -0.999893 5.55112e-16,
+                          0.0146287 -0.999893 5.55112e-16,
+                          0.0146287 -0.999893 5.55112e-16,
+                          0.0146287 -0.999893 5.55112e-16,
+                          0.0146287 -0.999893 5.55112e-16,
+                          0.0146287 -0.999893 5.55112e-16,
+                          6.99961e-16 -5.55112e-16 -1,
+                          6.99961e-16 -5.55112e-16 -1,
+                          6.99961e-16 -5.55112e-16 -1,
+                          0.999893 0.0146287 7.98353e-16,
+                          0.999893 0.0146287 7.98353e-16,
+                          0.999893 0.0146287 7.98353e-16,
+                          0.999893 0.0146287 7.98353e-16,
+                          0.999893 0.0146287 7.98353e-16,
+                          0.999893 0.0146287 7.98353e-16,
+                          0.999893 0.0146287 7.98353e-16,
+                          0.999893 0.0146287 7.98353e-16,
+                          0.999893 0.0146287 7.98353e-16,
+                          0.999893 0.0146287 7.98353e-16,
+                          0.999893 0.0146287 7.98353e-16,
+                          0.999893 0.0146287 7.98353e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -90.6638 144.425 21.9262,
+                          -90.6638 144.425 -15.3995,
+                          -89.6032 71.933 -81.1061,
+                          84.3175 146.985 -15.3995,
+                          -89.6032 71.933 -81.1061,
+                          -90.6638 144.425 -15.3995,
+                          -89.4027 58.2284 61.8939,
+                          -90.6638 144.425 21.9262,
+                          -89.6032 71.933 -81.1061,
+                          -88.5646 0.940611 -81.1061,
+                          -89.4027 58.2284 61.8939,
+                          -89.6032 71.933 -81.1061,
+                          85.3781 74.493 -81.1061,
+                          -88.5646 0.940611 -81.1061,
+                          -89.6032 71.933 -81.1061,
+                          84.3175 146.985 -15.3995,
+                          85.3781 74.493 -81.1061,
+                          -89.6032 71.933 -81.1061,
+                          84.3175 146.985 21.9262,
+                          -90.6638 144.425 -15.3995,
+                          -90.6638 144.425 21.9262,
+                          84.3175 146.985 -15.3995,
+                          -90.6638 144.425 -15.3995,
+                          84.3175 146.985 21.9262,
+                          85.5786 60.7885 61.8939,
+                          -90.6638 144.425 21.9262,
+                          -89.4027 58.2284 61.8939,
+                          85.5786 60.7885 61.8939,
+                          84.3175 146.985 21.9262,
+                          -90.6638 144.425 21.9262,
+                          -88.5646 0.940611 -81.1061,
+                          -88.5646 0.940611 61.8939,
+                          -89.4027 58.2284 61.8939,
+                          86.4167 3.50062 61.8939,
+                          -89.4027 58.2284 61.8939,
+                          -88.5646 0.940611 61.8939,
+                          86.4167 3.50062 61.8939,
+                          85.5786 60.7885 61.8939,
+                          -89.4027 58.2284 61.8939,
+                          86.4167 3.50062 -81.1061,
+                          -88.5646 0.940611 61.8939,
+                          -88.5646 0.940611 -81.1061,
+                          86.4167 3.50062 -81.1061,
+                          86.4167 3.50062 61.8939,
+                          -88.5646 0.940611 61.8939,
+                          85.3781 74.493 -81.1061,
+                          86.4167 3.50062 -81.1061,
+                          -88.5646 0.940611 -81.1061,
+                          84.3175 146.985 -15.3995,
+                          84.3175 146.985 21.9262,
+                          85.5786 60.7885 61.8939,
+                          85.3781 74.493 -81.1061,
+                          85.5786 60.7885 61.8939,
+                          86.4167 3.50062 61.8939,
+                          84.3175 146.985 -15.3995,
+                          85.5786 60.7885 61.8939,
+                          85.3781 74.493 -81.1061,
+                          85.3781 74.493 -81.1061,
+                          86.4167 3.50062 61.8939,
+                          86.4167 3.50062 -81.1061 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
+
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/shoulder_r.iv b/data/RobotAPI/robots/Armar3/collisionModel/shoulder_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..7d3a46b37a4147a49bcf356d2a7c268cfc538973
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/shoulder_r.iv
@@ -0,0 +1,162 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.6 0.6 0.6
+    } 
+
+  Transform {
+	translation 0 0 0
+	rotation 1 0 0 -1.57
+  }
+  	  Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+}
+  Transform {
+	translation 0 -110 0
+	rotation 0 0 0 0
+  }
+    Separator {
+        Normal {
+            vector      [ -0.999893 -0.0146287 -7.98353e-16,
+                          -0.999893 -0.0146287 -7.98353e-16,
+                          -0.999893 -0.0146287 -7.98353e-16,
+                          -0.00982371 0.671467 -0.740969,
+                          -0.00982371 0.671467 -0.740969,
+                          -0.00982371 0.671467 -0.740969,
+                          -0.999893 -0.0146287 -7.98353e-16,
+                          -0.999893 -0.0146287 -7.98353e-16,
+                          -0.999893 -0.0146287 -7.98353e-16,
+                          -0.999893 -0.0146287 -7.98353e-16,
+                          -0.999893 -0.0146287 -7.98353e-16,
+                          -0.999893 -0.0146287 -7.98353e-16,
+                          6.99961e-16 -5.55112e-16 -1,
+                          6.99961e-16 -5.55112e-16 -1,
+                          6.99961e-16 -5.55112e-16 -1,
+                          -0.00982371 0.671467 -0.740969,
+                          -0.00982371 0.671467 -0.740969,
+                          -0.00982371 0.671467 -0.740969,
+                          -0.0146287 0.999893 -5.55112e-16,
+                          -0.0146287 0.999893 -5.55112e-16,
+                          -0.0146287 0.999893 -5.55112e-16,
+                          -0.0146287 0.999893 -5.55112e-16,
+                          -0.0146287 0.999893 -5.55112e-16,
+                          -0.0146287 0.999893 -5.55112e-16,
+                          -0.00615312 0.420576 0.907236,
+                          -0.00615312 0.420576 0.907236,
+                          -0.00615312 0.420576 0.907236,
+                          -0.00615312 0.420576 0.907236,
+                          -0.00615312 0.420576 0.907236,
+                          -0.00615312 0.420576 0.907236,
+                          -0.999893 -0.0146287 -7.98353e-16,
+                          -0.999893 -0.0146287 -7.98353e-16,
+                          -0.999893 -0.0146287 -7.98353e-16,
+                          -6.99961e-16 5.55112e-16 1,
+                          -6.99961e-16 5.55112e-16 1,
+                          -6.99961e-16 5.55112e-16 1,
+                          -6.99961e-16 5.55112e-16 1,
+                          -6.99961e-16 5.55112e-16 1,
+                          -6.99961e-16 5.55112e-16 1,
+                          0.0146287 -0.999893 5.55112e-16,
+                          0.0146287 -0.999893 5.55112e-16,
+                          0.0146287 -0.999893 5.55112e-16,
+                          0.0146287 -0.999893 5.55112e-16,
+                          0.0146287 -0.999893 5.55112e-16,
+                          0.0146287 -0.999893 5.55112e-16,
+                          6.99961e-16 -5.55112e-16 -1,
+                          6.99961e-16 -5.55112e-16 -1,
+                          6.99961e-16 -5.55112e-16 -1,
+                          0.999893 0.0146287 7.98353e-16,
+                          0.999893 0.0146287 7.98353e-16,
+                          0.999893 0.0146287 7.98353e-16,
+                          0.999893 0.0146287 7.98353e-16,
+                          0.999893 0.0146287 7.98353e-16,
+                          0.999893 0.0146287 7.98353e-16,
+                          0.999893 0.0146287 7.98353e-16,
+                          0.999893 0.0146287 7.98353e-16,
+                          0.999893 0.0146287 7.98353e-16,
+                          0.999893 0.0146287 7.98353e-16,
+                          0.999893 0.0146287 7.98353e-16,
+                          0.999893 0.0146287 7.98353e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -90.6638 144.425 21.9262,
+                          -90.6638 144.425 -15.3995,
+                          -89.6032 71.933 -81.1061,
+                          84.3175 146.985 -15.3995,
+                          -89.6032 71.933 -81.1061,
+                          -90.6638 144.425 -15.3995,
+                          -89.4027 58.2284 61.8939,
+                          -90.6638 144.425 21.9262,
+                          -89.6032 71.933 -81.1061,
+                          -88.5646 0.940611 -81.1061,
+                          -89.4027 58.2284 61.8939,
+                          -89.6032 71.933 -81.1061,
+                          85.3781 74.493 -81.1061,
+                          -88.5646 0.940611 -81.1061,
+                          -89.6032 71.933 -81.1061,
+                          84.3175 146.985 -15.3995,
+                          85.3781 74.493 -81.1061,
+                          -89.6032 71.933 -81.1061,
+                          84.3175 146.985 21.9262,
+                          -90.6638 144.425 -15.3995,
+                          -90.6638 144.425 21.9262,
+                          84.3175 146.985 -15.3995,
+                          -90.6638 144.425 -15.3995,
+                          84.3175 146.985 21.9262,
+                          85.5786 60.7885 61.8939,
+                          -90.6638 144.425 21.9262,
+                          -89.4027 58.2284 61.8939,
+                          85.5786 60.7885 61.8939,
+                          84.3175 146.985 21.9262,
+                          -90.6638 144.425 21.9262,
+                          -88.5646 0.940611 -81.1061,
+                          -88.5646 0.940611 61.8939,
+                          -89.4027 58.2284 61.8939,
+                          86.4167 3.50062 61.8939,
+                          -89.4027 58.2284 61.8939,
+                          -88.5646 0.940611 61.8939,
+                          86.4167 3.50062 61.8939,
+                          85.5786 60.7885 61.8939,
+                          -89.4027 58.2284 61.8939,
+                          86.4167 3.50062 -81.1061,
+                          -88.5646 0.940611 61.8939,
+                          -88.5646 0.940611 -81.1061,
+                          86.4167 3.50062 -81.1061,
+                          86.4167 3.50062 61.8939,
+                          -88.5646 0.940611 61.8939,
+                          85.3781 74.493 -81.1061,
+                          86.4167 3.50062 -81.1061,
+                          -88.5646 0.940611 -81.1061,
+                          84.3175 146.985 -15.3995,
+                          84.3175 146.985 21.9262,
+                          85.5786 60.7885 61.8939,
+                          85.3781 74.493 -81.1061,
+                          85.5786 60.7885 61.8939,
+                          86.4167 3.50062 61.8939,
+                          84.3175 146.985 -15.3995,
+                          85.5786 60.7885 61.8939,
+                          85.3781 74.493 -81.1061,
+                          85.3781 74.493 -81.1061,
+                          86.4167 3.50062 61.8939,
+                          86.4167 3.50062 -81.1061 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
+
+
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/thumb_l1.iv b/data/RobotAPI/robots/Armar3/collisionModel/thumb_l1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..f49f640c61abd582fc841aff68d153afe9f6bc67
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/thumb_l1.iv
@@ -0,0 +1,106 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 1.57
+	} 
+	Transform {
+		translation -4.25 0 0
+		rotation 0 1 0 0
+	} 
+    Separator {
+        Normal {
+            vector      [ -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 10.67 -2.4 3.75,
+                          -5 -2.4 -21.25,
+                          10.67 -2.4 -21.25,
+                          -5 42.25 -21.25,
+                          10.67 -2.4 -21.25,
+                          -5 -2.4 -21.25,
+                          10.67 42.25 -21.25,
+                          10.67 -2.4 3.75,
+                          10.67 -2.4 -21.25,
+                          -5 42.25 -21.25,
+                          10.67 42.25 -21.25,
+                          10.67 -2.4 -21.25,
+                          10.67 -2.4 3.75,
+                          -5 -2.4 3.75,
+                          -5 -2.4 -21.25,
+                          -5 42.25 3.75,
+                          -5 -2.4 -21.25,
+                          -5 -2.4 3.75,
+                          -5 42.25 -21.25,
+                          -5 -2.4 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 3.75,
+                          -5 -2.4 3.75,
+                          10.67 -2.4 3.75,
+                          -5 42.25 3.75,
+                          -5 -2.4 3.75,
+                          10.67 42.25 3.75,
+                          10.67 42.25 3.75,
+                          10.67 -2.4 3.75,
+                          10.67 42.25 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 3.75,
+                          10.67 42.25 -21.25,
+                          -5 42.25 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 -21.25 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/thumb_l2.iv b/data/RobotAPI/robots/Armar3/collisionModel/thumb_l2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..080bc6471561f097ac6a30d13d0d2b8cd275e16d
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/thumb_l2.iv
@@ -0,0 +1,127 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0 0 1
+    }
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 1.57
+	} 
+
+    Separator {
+        Normal {
+            vector      [ 0 -1 1.30104e-16,
+                          0 -1 1.30104e-16,
+                          0 -1 1.30104e-16,
+                          -6.76542e-17 8.50015e-17 -1,
+                          -6.76542e-17 8.50015e-17 -1,
+                          -6.76542e-17 8.50015e-17 -1,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          0 -1 1.30104e-16,
+                          0 -1 1.30104e-16,
+                          0 -1 1.30104e-16,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -6.76542e-17 8.50015e-17 -1,
+                          -6.76542e-17 8.50015e-17 -1,
+                          -6.76542e-17 8.50015e-17 -1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          0 1 -1.30104e-16,
+                          0 1 -1.30104e-16,
+                          0 1 -1.30104e-16,
+                          -6.4801e-17 0.287348 -0.957826,
+                          -6.4801e-17 0.287348 -0.957826,
+                          -6.4801e-17 0.287348 -0.957826,
+                          0 1 -1.30104e-16,
+                          0 1 -1.30104e-16,
+                          0 1 -1.30104e-16,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -6.4801e-17 0.287348 -0.957826,
+                          -6.4801e-17 0.287348 -0.957826,
+                          -6.4801e-17 0.287348 -0.957826 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 10 -1.25 4.25,
+                          -10 -1.25 -20.75,
+                          10 -1.25 -20.75,
+                          10 8.75 -20.75,
+                          10 -1.25 -20.75,
+                          -10 -1.25 -20.75,
+                          10 8.75 -20.75,
+                          10 -1.25 4.25,
+                          10 -1.25 -20.75,
+                          10 -1.25 4.25,
+                          -10 -1.25 4.25,
+                          -10 -1.25 -20.75,
+                          -10 58.75 4.25,
+                          -10 -1.25 -20.75,
+                          -10 -1.25 4.25,
+                          -10 8.75 -20.75,
+                          -10 -1.25 -20.75,
+                          -10 58.75 4.25,
+                          10 8.75 -20.75,
+                          -10 -1.25 -20.75,
+                          -10 8.75 -20.75,
+                          10 58.75 4.25,
+                          -10 -1.25 4.25,
+                          10 -1.25 4.25,
+                          -10 58.75 4.25,
+                          -10 -1.25 4.25,
+                          10 58.75 4.25,
+                          10 58.75 4.25,
+                          10 -1.25 4.25,
+                          10 58.75 -5.75,
+                          10 8.75 -20.75,
+                          10 58.75 -5.75,
+                          10 -1.25 4.25,
+                          10 58.75 4.25,
+                          10 58.75 -5.75,
+                          -10 58.75 -5.75,
+                          10 8.75 -20.75,
+                          -10 58.75 -5.75,
+                          10 58.75 -5.75,
+                          -10 58.75 4.25,
+                          10 58.75 4.25,
+                          -10 58.75 -5.75,
+                          -10 8.75 -20.75,
+                          -10 58.75 4.25,
+                          -10 58.75 -5.75,
+                          10 8.75 -20.75,
+                          -10 8.75 -20.75,
+                          -10 58.75 -5.75 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/thumb_r1.iv b/data/RobotAPI/robots/Armar3/collisionModel/thumb_r1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..f1e1766094378140e23a36fc8cddcf7e537663af
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/thumb_r1.iv
@@ -0,0 +1,103 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 1.57
+	} 
+
+    Separator {
+        Normal {
+            vector      [ -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          5.55112e-17 7.45931e-17 -1,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -2.77556e-16 -1 -1.66533e-16,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          -5.55112e-17 -7.45931e-17 1,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16,
+                          2.77556e-16 1 1.66533e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 10.67 -2.4 3.75,
+                          -5 -2.4 -21.25,
+                          10.67 -2.4 -21.25,
+                          -5 42.25 -21.25,
+                          10.67 -2.4 -21.25,
+                          -5 -2.4 -21.25,
+                          10.67 42.25 -21.25,
+                          10.67 -2.4 3.75,
+                          10.67 -2.4 -21.25,
+                          -5 42.25 -21.25,
+                          10.67 42.25 -21.25,
+                          10.67 -2.4 -21.25,
+                          10.67 -2.4 3.75,
+                          -5 -2.4 3.75,
+                          -5 -2.4 -21.25,
+                          -5 42.25 3.75,
+                          -5 -2.4 -21.25,
+                          -5 -2.4 3.75,
+                          -5 42.25 -21.25,
+                          -5 -2.4 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 3.75,
+                          -5 -2.4 3.75,
+                          10.67 -2.4 3.75,
+                          -5 42.25 3.75,
+                          -5 -2.4 3.75,
+                          10.67 42.25 3.75,
+                          10.67 42.25 3.75,
+                          10.67 -2.4 3.75,
+                          10.67 42.25 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 3.75,
+                          10.67 42.25 -21.25,
+                          -5 42.25 -21.25,
+                          -5 42.25 3.75,
+                          10.67 42.25 -21.25 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/thumb_r2.iv b/data/RobotAPI/robots/Armar3/collisionModel/thumb_r2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..080bc6471561f097ac6a30d13d0d2b8cd275e16d
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/thumb_r2.iv
@@ -0,0 +1,127 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0 0 1
+    }
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 1.57
+	} 
+
+    Separator {
+        Normal {
+            vector      [ 0 -1 1.30104e-16,
+                          0 -1 1.30104e-16,
+                          0 -1 1.30104e-16,
+                          -6.76542e-17 8.50015e-17 -1,
+                          -6.76542e-17 8.50015e-17 -1,
+                          -6.76542e-17 8.50015e-17 -1,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          0 -1 1.30104e-16,
+                          0 -1 1.30104e-16,
+                          0 -1 1.30104e-16,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -6.76542e-17 8.50015e-17 -1,
+                          -6.76542e-17 8.50015e-17 -1,
+                          -6.76542e-17 8.50015e-17 -1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          6.76542e-17 -8.50015e-17 1,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          1 -1.66533e-16 -6.07153e-17,
+                          0 1 -1.30104e-16,
+                          0 1 -1.30104e-16,
+                          0 1 -1.30104e-16,
+                          -6.4801e-17 0.287348 -0.957826,
+                          -6.4801e-17 0.287348 -0.957826,
+                          -6.4801e-17 0.287348 -0.957826,
+                          0 1 -1.30104e-16,
+                          0 1 -1.30104e-16,
+                          0 1 -1.30104e-16,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -1 1.66533e-16 6.07153e-17,
+                          -6.4801e-17 0.287348 -0.957826,
+                          -6.4801e-17 0.287348 -0.957826,
+                          -6.4801e-17 0.287348 -0.957826 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 10 -1.25 4.25,
+                          -10 -1.25 -20.75,
+                          10 -1.25 -20.75,
+                          10 8.75 -20.75,
+                          10 -1.25 -20.75,
+                          -10 -1.25 -20.75,
+                          10 8.75 -20.75,
+                          10 -1.25 4.25,
+                          10 -1.25 -20.75,
+                          10 -1.25 4.25,
+                          -10 -1.25 4.25,
+                          -10 -1.25 -20.75,
+                          -10 58.75 4.25,
+                          -10 -1.25 -20.75,
+                          -10 -1.25 4.25,
+                          -10 8.75 -20.75,
+                          -10 -1.25 -20.75,
+                          -10 58.75 4.25,
+                          10 8.75 -20.75,
+                          -10 -1.25 -20.75,
+                          -10 8.75 -20.75,
+                          10 58.75 4.25,
+                          -10 -1.25 4.25,
+                          10 -1.25 4.25,
+                          -10 58.75 4.25,
+                          -10 -1.25 4.25,
+                          10 58.75 4.25,
+                          10 58.75 4.25,
+                          10 -1.25 4.25,
+                          10 58.75 -5.75,
+                          10 8.75 -20.75,
+                          10 58.75 -5.75,
+                          10 -1.25 4.25,
+                          10 58.75 4.25,
+                          10 58.75 -5.75,
+                          -10 58.75 -5.75,
+                          10 8.75 -20.75,
+                          -10 58.75 -5.75,
+                          10 58.75 -5.75,
+                          -10 58.75 4.25,
+                          10 58.75 4.25,
+                          -10 58.75 -5.75,
+                          -10 8.75 -20.75,
+                          -10 58.75 4.25,
+                          -10 58.75 -5.75,
+                          10 8.75 -20.75,
+                          -10 8.75 -20.75,
+                          -10 58.75 -5.75 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/torso.iv b/data/RobotAPI/robots/Armar3/collisionModel/torso.iv
new file mode 100644
index 0000000000000000000000000000000000000000..f861754e0b08ea4116419ca1de70cadf6f0c72f3
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/torso.iv
@@ -0,0 +1,307 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.24 0.77 1
+    }
+   RotationXYZ{
+     axis Z
+     angle -1.57
+   }
+
+#Transform{
+#  translation 0 0 52
+#}
+
+# Transform {
+#   rotation 0 1 0 3.1415
+# }
+
+    Separator {
+        Normal {
+            vector      [ 2.05088e-16 0 -1,
+                          2.05088e-16 0 -1,
+                          2.05088e-16 0 -1,
+                          -1.83691e-16 -1 2.22045e-16,
+                          -1.83691e-16 -1 2.22045e-16,
+                          -1.83691e-16 -1 2.22045e-16,
+                          -1 1.83691e-16 -2.05088e-16,
+                          -1 1.83691e-16 -2.05088e-16,
+                          -1 1.83691e-16 -2.05088e-16,
+                          -1.83691e-16 -1 2.22045e-16,
+                          -1.83691e-16 -1 2.22045e-16,
+                          -1.83691e-16 -1 2.22045e-16,
+                          2.05088e-16 0 -1,
+                          2.05088e-16 0 -1,
+                          2.05088e-16 0 -1,
+                          1 -1.83691e-16 2.05088e-16,
+                          1 -1.83691e-16 2.05088e-16,
+                          1 -1.83691e-16 2.05088e-16,
+                          1 -1.83691e-16 2.05088e-16,
+                          1 -1.83691e-16 2.05088e-16,
+                          1 -1.83691e-16 2.05088e-16,
+                          1.83691e-16 1 -2.22045e-16,
+                          1.83691e-16 1 -2.22045e-16,
+                          1.83691e-16 1 -2.22045e-16,
+                          1.83691e-16 1 -2.22045e-16,
+                          1.83691e-16 1 -2.22045e-16,
+                          1.83691e-16 1 -2.22045e-16,
+                          -1 1.83691e-16 -2.05088e-16,
+                          -1 1.83691e-16 -2.05088e-16,
+                          -1 1.83691e-16 -2.05088e-16,
+                          -2.05088e-16 0 1,
+                          -2.05088e-16 0 1,
+                          -2.05088e-16 0 1,
+                          1 -1.83691e-16 2.05088e-16,
+                          1 -1.83691e-16 2.05088e-16,
+                          1 -1.83691e-16 2.05088e-16,
+                          -2.05088e-16 0 1,
+                          -2.05088e-16 0 1,
+                          -2.05088e-16 0 1,
+                          1.83691e-16 1 -2.22045e-16,
+                          1.83691e-16 1 -2.22045e-16,
+                          1.83691e-16 1 -2.22045e-16,
+                          1 -1.83691e-16 2.05088e-16,
+                          1 -1.83691e-16 2.05088e-16,
+                          1 -1.83691e-16 2.05088e-16,
+                          1.83691e-16 1 -2.22045e-16,
+                          1.83691e-16 1 -2.22045e-16,
+                          1.83691e-16 1 -2.22045e-16,
+                          -2.05088e-16 0 1,
+                          -2.05088e-16 0 1,
+                          -2.05088e-16 0 1,
+                          -1.83691e-16 -1 2.22045e-16,
+                          -1.83691e-16 -1 2.22045e-16,
+                          -1.83691e-16 -1 2.22045e-16,
+                          -2.05088e-16 0 1,
+                          -2.05088e-16 0 1,
+                          -2.05088e-16 0 1,
+                          -2.05088e-16 0 1,
+                          -2.05088e-16 0 1,
+                          -2.05088e-16 0 1,
+                          -2.05088e-16 0 1,
+                          -2.05088e-16 0 1,
+                          -2.05088e-16 0 1,
+                          -1 1.83691e-16 -2.05088e-16,
+                          -1 1.83691e-16 -2.05088e-16,
+                          -1 1.83691e-16 -2.05088e-16,
+                          -1.83691e-16 -1 2.22045e-16,
+                          -1.83691e-16 -1 2.22045e-16,
+                          -1.83691e-16 -1 2.22045e-16,
+                          -1 1.83691e-16 -2.05088e-16,
+                          -1 1.83691e-16 -2.05088e-16,
+                          -1 1.83691e-16 -2.05088e-16,
+                          -2.05088e-16 0 1,
+                          -2.05088e-16 0 1,
+                          -2.05088e-16 0 1,
+                          -2.05088e-16 0 1,
+                          -2.05088e-16 0 1,
+                          -2.05088e-16 0 1,
+                          -1.83691e-16 -1 2.22045e-16,
+                          -1.83691e-16 -1 2.22045e-16,
+                          -1.83691e-16 -1 2.22045e-16,
+                          -1 1.83691e-16 -2.05088e-16,
+                          -1 1.83691e-16 -2.05088e-16,
+                          -1 1.83691e-16 -2.05088e-16,
+                          -1 1.83691e-16 -2.05088e-16,
+                          -1 1.83691e-16 -2.05088e-16,
+                          -1 1.83691e-16 -2.05088e-16,
+                          1 -1.83691e-16 2.05088e-16,
+                          1 -1.83691e-16 2.05088e-16,
+                          1 -1.83691e-16 2.05088e-16,
+                          -1.83691e-16 -1 2.22045e-16,
+                          -1.83691e-16 -1 2.22045e-16,
+                          -1.83691e-16 -1 2.22045e-16,
+                          1.83691e-16 1 -2.22045e-16,
+                          1.83691e-16 1 -2.22045e-16,
+                          1.83691e-16 1 -2.22045e-16,
+                          1 -1.83691e-16 2.05088e-16,
+                          1 -1.83691e-16 2.05088e-16,
+                          1 -1.83691e-16 2.05088e-16,
+                          1.83691e-16 1 -2.22045e-16,
+                          1.83691e-16 1 -2.22045e-16,
+                          1.83691e-16 1 -2.22045e-16,
+                          -2.67662e-16 -0.4741 0.880471,
+                          -2.67662e-16 -0.4741 0.880471,
+                          -2.67662e-16 -0.4741 0.880471,
+                          -1 1.83691e-16 -2.05088e-16,
+                          -1 1.83691e-16 -2.05088e-16,
+                          -1 1.83691e-16 -2.05088e-16,
+                          1 -1.83691e-16 2.05088e-16,
+                          1 -1.83691e-16 2.05088e-16,
+                          1 -1.83691e-16 2.05088e-16,
+                          1 -1.83691e-16 2.05088e-16,
+                          1 -1.83691e-16 2.05088e-16,
+                          1 -1.83691e-16 2.05088e-16,
+                          -2.67662e-16 -0.4741 0.880471,
+                          -2.67662e-16 -0.4741 0.880471,
+                          -2.67662e-16 -0.4741 0.880471,
+                          -9.34866e-17 0.4741 0.880471,
+                          -9.34866e-17 0.4741 0.880471,
+                          -9.34866e-17 0.4741 0.880471,
+                          -9.34866e-17 0.4741 0.880471,
+                          -9.34866e-17 0.4741 0.880471,
+                          -9.34866e-17 0.4741 0.880471,
+                          -1 1.83691e-16 -2.05088e-16,
+                          -1 1.83691e-16 -2.05088e-16,
+                          -1 1.83691e-16 -2.05088e-16,
+                          -2.05088e-16 0 1,
+                          -2.05088e-16 0 1,
+                          -2.05088e-16 0 1,
+                          -2.05088e-16 0 1,
+                          -2.05088e-16 0 1,
+                          -2.05088e-16 0 1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -96 183 3.59534e-13,
+                          165.584 -177 4.93118e-13,
+                          -96 -177 4.3947e-13,
+                          165.584 -177 368,
+                          -96 -177 4.3947e-13,
+                          165.584 -177 4.93118e-13,
+                          -96 -177 368,
+                          -96 183 3.59534e-13,
+                          -96 -177 4.3947e-13,
+                          165.584 -177 368,
+                          -96 -177 368,
+                          -96 -177 4.3947e-13,
+                          -96 183 3.59534e-13,
+                          165.584 183 4.13182e-13,
+                          165.584 -177 4.93118e-13,
+                          165.584 183 368,
+                          165.584 -177 4.93118e-13,
+                          165.584 183 4.13182e-13,
+                          165.584 183 368,
+                          165.584 -177 368,
+                          165.584 -177 4.93118e-13,
+                          -96 183 368,
+                          165.584 183 4.13182e-13,
+                          -96 183 3.59534e-13,
+                          -96 183 368,
+                          165.584 183 368,
+                          165.584 183 4.13182e-13,
+                          -96 183 368,
+                          -96 183 3.59534e-13,
+                          -96 -177 368,
+                          89 79.36 573,
+                          165.584 -112 573,
+                          165.584 118 573,
+                          165.584 -112 403,
+                          165.584 118 573,
+                          165.584 -112 573,
+                          89 79.36 573,
+                          165.584 118 573,
+                          -96 118 573,
+                          -96 118 403,
+                          -96 118 573,
+                          165.584 118 573,
+                          165.584 -112 403,
+                          165.584 118 403,
+                          165.584 118 573,
+                          -96 118 403,
+                          165.584 118 573,
+                          165.584 118 403,
+                          -43 -82.64 573,
+                          -96 -112 573,
+                          165.584 -112 573,
+                          165.584 -112 403,
+                          165.584 -112 573,
+                          -96 -112 573,
+                          89 -82.64 573,
+                          -43 -82.64 573,
+                          165.584 -112 573,
+                          89 79.36 573,
+                          89 -82.64 573,
+                          165.584 -112 573,
+                          -43 -82.64 573,
+                          -96 118 573,
+                          -96 -112 573,
+                          -96 118 403,
+                          -96 -112 573,
+                          -96 118 573,
+                          -96 -112 403,
+                          165.584 -112 403,
+                          -96 -112 573,
+                          -96 -112 403,
+                          -96 -112 573,
+                          -96 118 403,
+                          -43 79.36 573,
+                          -96 118 573,
+                          -43 -82.64 573,
+                          -43 79.36 573,
+                          89 79.36 573,
+                          -96 118 573,
+                          -43 -82.64 638,
+                          -43 -82.64 573,
+                          89 -82.64 573,
+                          -43 79.36 638,
+                          -43 79.36 573,
+                          -43 -82.64 573,
+                          -43 79.36 638,
+                          -43 -82.64 573,
+                          -43 -82.64 638,
+                          89 -82.64 638,
+                          89 -82.64 573,
+                          89 79.36 573,
+                          89 -82.64 638,
+                          -43 -82.64 638,
+                          89 -82.64 573,
+                          89 79.36 638,
+                          89 79.36 573,
+                          -43 79.36 573,
+                          89 -82.64 638,
+                          89 79.36 573,
+                          89 79.36 638,
+                          89 79.36 638,
+                          -43 79.36 573,
+                          -43 79.36 638,
+                          -96 -112 403,
+                          -96 -177 368,
+                          165.584 -177 368,
+                          -96 -112 403,
+                          -96 183 368,
+                          -96 -177 368,
+                          165.584 183 368,
+                          165.584 118 403,
+                          165.584 -177 368,
+                          165.584 -112 403,
+                          165.584 -177 368,
+                          165.584 118 403,
+                          -96 -112 403,
+                          165.584 -177 368,
+                          165.584 -112 403,
+                          -96 183 368,
+                          165.584 118 403,
+                          165.584 183 368,
+                          -96 118 403,
+                          165.584 118 403,
+                          -96 183 368,
+                          -96 -112 403,
+                          -96 118 403,
+                          -96 183 368,
+                          89 79.36 638,
+                          -43 79.36 638,
+                          -43 -82.64 638,
+                          89 -82.64 638,
+                          89 79.36 638,
+                          -43 -82.64 638 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/underarm_l.iv b/data/RobotAPI/robots/Armar3/collisionModel/underarm_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..84087a8e7d9c80114b7bacc23c33a6fc23bc31bc
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/underarm_l.iv
@@ -0,0 +1,155 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    1 1 1
+    }
+	Transform {
+		translation 0 0 -46.5
+		rotation 0 0 0 0 
+	}
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 3.14
+	}
+	Separator {
+        Normal {
+            vector      [ -2.7842e-18 1.11022e-16 -1,
+                          -2.7842e-18 1.11022e-16 -1,
+                          -2.7842e-18 1.11022e-16 -1,
+                          1 5.43805e-17 4.45624e-18,
+                          1 5.43805e-17 4.45624e-18,
+                          0.5 0.866025 5.03022e-17,
+                          -2.7842e-18 1.11022e-16 -1,
+                          -2.7842e-18 1.11022e-16 -1,
+                          -2.7842e-18 1.11022e-16 -1,
+                          -2.7842e-18 1.11022e-16 -1,
+                          -2.7842e-18 1.11022e-16 -1,
+                          -2.7842e-18 1.11022e-16 -1,
+                          0.5 -0.866025 -4.58459e-17,
+                          0.5 -0.866025 -4.58459e-17,
+                          1 -1.90541e-16 4.45624e-18,
+                          0.5 -0.866025 -4.58459e-17,
+                          1 -1.90541e-16 4.45624e-18,
+                          1 -1.90541e-16 4.45624e-18,
+                          0.5 0.866025 5.03022e-17,
+                          0.5 0.866025 5.03022e-17,
+                          -0.5 0.866025 4.58459e-17,
+                          0.5 0.866025 5.03022e-17,
+                          1 5.43805e-17 4.45624e-18,
+                          0.5 0.866025 5.03022e-17,
+                          -0.5 0.866025 4.58459e-17,
+                          -0.5 0.866025 4.58459e-17,
+                          -1 6.80802e-17 -4.45624e-18,
+                          0.5 0.866025 5.03022e-17,
+                          -0.5 0.866025 4.58459e-17,
+                          -0.5 0.866025 4.58459e-17,
+                          -2.7842e-18 1.11022e-16 -1,
+                          -2.7842e-18 1.11022e-16 -1,
+                          -2.7842e-18 1.11022e-16 -1,
+                          -1 6.80802e-17 -4.45624e-18,
+                          -1 6.80802e-17 -4.45624e-18,
+                          -0.5 -0.866025 -5.03022e-17,
+                          -0.5 0.866025 4.58459e-17,
+                          -1 6.80802e-17 -4.45624e-18,
+                          -1 6.80802e-17 -4.45624e-18,
+                          -0.5 -0.866025 -5.03022e-17,
+                          -0.5 -0.866025 -5.03022e-17,
+                          0.5 -0.866025 -4.58459e-17,
+                          -1 6.80802e-17 -4.45624e-18,
+                          -0.5 -0.866025 -5.03022e-17,
+                          -0.5 -0.866025 -5.03022e-17,
+                          -0.5 -0.866025 -5.03022e-17,
+                          0.5 -0.866025 -4.58459e-17,
+                          0.5 -0.866025 -4.58459e-17,
+                          2.7842e-18 -1.11022e-16 1,
+                          2.7842e-18 -1.11022e-16 1,
+                          2.7842e-18 -1.11022e-16 1,
+                          2.7842e-18 -1.11022e-16 1,
+                          2.7842e-18 -1.11022e-16 1,
+                          2.7842e-18 -1.11022e-16 1,
+                          2.7842e-18 -1.11022e-16 1,
+                          2.7842e-18 -1.11022e-16 1,
+                          2.7842e-18 -1.11022e-16 1,
+                          2.7842e-18 -1.11022e-16 1,
+                          2.7842e-18 -1.11022e-16 1,
+                          2.7842e-18 -1.11022e-16 1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -23.5013 40.702 -46.5,
+                          23.5013 40.702 -46.5,
+                          47 9.62762e-14 -46.5,
+                          47 6.96309e-14 193.5,
+                          47 9.62762e-14 -46.5,
+                          23.5013 40.702 -46.5,
+                          -47 1.02676e-13 -46.5,
+                          -23.5013 40.702 -46.5,
+                          47 9.62762e-14 -46.5,
+                          23.5013 -40.702 -46.5,
+                          -47 1.02676e-13 -46.5,
+                          47 9.62762e-14 -46.5,
+                          23.5013 -40.702 193.5,
+                          23.5013 -40.702 -46.5,
+                          47 9.62762e-14 -46.5,
+                          23.5013 -40.702 193.5,
+                          47 9.62762e-14 -46.5,
+                          47 6.96309e-14 193.5,
+                          23.5013 40.702 193.5,
+                          23.5013 40.702 -46.5,
+                          -23.5013 40.702 -46.5,
+                          23.5013 40.702 193.5,
+                          47 6.96309e-14 193.5,
+                          23.5013 40.702 -46.5,
+                          -23.5013 40.702 193.5,
+                          -23.5013 40.702 -46.5,
+                          -47 1.02676e-13 -46.5,
+                          23.5013 40.702 193.5,
+                          -23.5013 40.702 -46.5,
+                          -23.5013 40.702 193.5,
+                          23.5013 -40.702 -46.5,
+                          -23.5013 -40.702 -46.5,
+                          -47 1.02676e-13 -46.5,
+                          -47 7.60304e-14 193.5,
+                          -47 1.02676e-13 -46.5,
+                          -23.5013 -40.702 -46.5,
+                          -23.5013 40.702 193.5,
+                          -47 1.02676e-13 -46.5,
+                          -47 7.60304e-14 193.5,
+                          -23.5013 -40.702 193.5,
+                          -23.5013 -40.702 -46.5,
+                          23.5013 -40.702 -46.5,
+                          -47 7.60304e-14 193.5,
+                          -23.5013 -40.702 -46.5,
+                          -23.5013 -40.702 193.5,
+                          -23.5013 -40.702 193.5,
+                          23.5013 -40.702 -46.5,
+                          23.5013 -40.702 193.5,
+                          -23.5013 -40.702 193.5,
+                          23.5013 -40.702 193.5,
+                          47 6.96309e-14 193.5,
+                          -47 7.60304e-14 193.5,
+                          -23.5013 -40.702 193.5,
+                          47 6.96309e-14 193.5,
+                          23.5013 40.702 193.5,
+                          -47 7.60304e-14 193.5,
+                          47 6.96309e-14 193.5,
+                          23.5013 40.702 193.5,
+                          -23.5013 40.702 193.5,
+                          -47 7.60304e-14 193.5 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/underarm_r.iv b/data/RobotAPI/robots/Armar3/collisionModel/underarm_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..e742c3fcfb285e541a0fc3dd5e448fb05c75a871
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/underarm_r.iv
@@ -0,0 +1,156 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    1 1 1
+    }
+    
+    Transform {
+		translation 0 0 -46.5
+		rotation 0 0 0 0 
+	}
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 3.14 
+	}
+    Separator {
+        Normal {
+            vector      [ -2.7842e-18 1.11022e-16 -1,
+                          -2.7842e-18 1.11022e-16 -1,
+                          -2.7842e-18 1.11022e-16 -1,
+                          1 5.43805e-17 4.45624e-18,
+                          1 5.43805e-17 4.45624e-18,
+                          0.5 0.866025 5.03022e-17,
+                          -2.7842e-18 1.11022e-16 -1,
+                          -2.7842e-18 1.11022e-16 -1,
+                          -2.7842e-18 1.11022e-16 -1,
+                          -2.7842e-18 1.11022e-16 -1,
+                          -2.7842e-18 1.11022e-16 -1,
+                          -2.7842e-18 1.11022e-16 -1,
+                          0.5 -0.866025 -4.58459e-17,
+                          0.5 -0.866025 -4.58459e-17,
+                          1 -1.90541e-16 4.45624e-18,
+                          0.5 -0.866025 -4.58459e-17,
+                          1 -1.90541e-16 4.45624e-18,
+                          1 -1.90541e-16 4.45624e-18,
+                          0.5 0.866025 5.03022e-17,
+                          0.5 0.866025 5.03022e-17,
+                          -0.5 0.866025 4.58459e-17,
+                          0.5 0.866025 5.03022e-17,
+                          1 5.43805e-17 4.45624e-18,
+                          0.5 0.866025 5.03022e-17,
+                          -0.5 0.866025 4.58459e-17,
+                          -0.5 0.866025 4.58459e-17,
+                          -1 6.80802e-17 -4.45624e-18,
+                          0.5 0.866025 5.03022e-17,
+                          -0.5 0.866025 4.58459e-17,
+                          -0.5 0.866025 4.58459e-17,
+                          -2.7842e-18 1.11022e-16 -1,
+                          -2.7842e-18 1.11022e-16 -1,
+                          -2.7842e-18 1.11022e-16 -1,
+                          -1 6.80802e-17 -4.45624e-18,
+                          -1 6.80802e-17 -4.45624e-18,
+                          -0.5 -0.866025 -5.03022e-17,
+                          -0.5 0.866025 4.58459e-17,
+                          -1 6.80802e-17 -4.45624e-18,
+                          -1 6.80802e-17 -4.45624e-18,
+                          -0.5 -0.866025 -5.03022e-17,
+                          -0.5 -0.866025 -5.03022e-17,
+                          0.5 -0.866025 -4.58459e-17,
+                          -1 6.80802e-17 -4.45624e-18,
+                          -0.5 -0.866025 -5.03022e-17,
+                          -0.5 -0.866025 -5.03022e-17,
+                          -0.5 -0.866025 -5.03022e-17,
+                          0.5 -0.866025 -4.58459e-17,
+                          0.5 -0.866025 -4.58459e-17,
+                          2.7842e-18 -1.11022e-16 1,
+                          2.7842e-18 -1.11022e-16 1,
+                          2.7842e-18 -1.11022e-16 1,
+                          2.7842e-18 -1.11022e-16 1,
+                          2.7842e-18 -1.11022e-16 1,
+                          2.7842e-18 -1.11022e-16 1,
+                          2.7842e-18 -1.11022e-16 1,
+                          2.7842e-18 -1.11022e-16 1,
+                          2.7842e-18 -1.11022e-16 1,
+                          2.7842e-18 -1.11022e-16 1,
+                          2.7842e-18 -1.11022e-16 1,
+                          2.7842e-18 -1.11022e-16 1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -23.5013 40.702 -46.5,
+                          23.5013 40.702 -46.5,
+                          47 9.62762e-14 -46.5,
+                          47 6.96309e-14 193.5,
+                          47 9.62762e-14 -46.5,
+                          23.5013 40.702 -46.5,
+                          -47 1.02676e-13 -46.5,
+                          -23.5013 40.702 -46.5,
+                          47 9.62762e-14 -46.5,
+                          23.5013 -40.702 -46.5,
+                          -47 1.02676e-13 -46.5,
+                          47 9.62762e-14 -46.5,
+                          23.5013 -40.702 193.5,
+                          23.5013 -40.702 -46.5,
+                          47 9.62762e-14 -46.5,
+                          23.5013 -40.702 193.5,
+                          47 9.62762e-14 -46.5,
+                          47 6.96309e-14 193.5,
+                          23.5013 40.702 193.5,
+                          23.5013 40.702 -46.5,
+                          -23.5013 40.702 -46.5,
+                          23.5013 40.702 193.5,
+                          47 6.96309e-14 193.5,
+                          23.5013 40.702 -46.5,
+                          -23.5013 40.702 193.5,
+                          -23.5013 40.702 -46.5,
+                          -47 1.02676e-13 -46.5,
+                          23.5013 40.702 193.5,
+                          -23.5013 40.702 -46.5,
+                          -23.5013 40.702 193.5,
+                          23.5013 -40.702 -46.5,
+                          -23.5013 -40.702 -46.5,
+                          -47 1.02676e-13 -46.5,
+                          -47 7.60304e-14 193.5,
+                          -47 1.02676e-13 -46.5,
+                          -23.5013 -40.702 -46.5,
+                          -23.5013 40.702 193.5,
+                          -47 1.02676e-13 -46.5,
+                          -47 7.60304e-14 193.5,
+                          -23.5013 -40.702 193.5,
+                          -23.5013 -40.702 -46.5,
+                          23.5013 -40.702 -46.5,
+                          -47 7.60304e-14 193.5,
+                          -23.5013 -40.702 -46.5,
+                          -23.5013 -40.702 193.5,
+                          -23.5013 -40.702 193.5,
+                          23.5013 -40.702 -46.5,
+                          23.5013 -40.702 193.5,
+                          -23.5013 -40.702 193.5,
+                          23.5013 -40.702 193.5,
+                          47 6.96309e-14 193.5,
+                          -47 7.60304e-14 193.5,
+                          -23.5013 -40.702 193.5,
+                          47 6.96309e-14 193.5,
+                          23.5013 40.702 193.5,
+                          -47 7.60304e-14 193.5,
+                          47 6.96309e-14 193.5,
+                          23.5013 40.702 193.5,
+                          -23.5013 40.702 193.5,
+                          -47 7.60304e-14 193.5 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/upperarm_l.iv b/data/RobotAPI/robots/Armar3/collisionModel/upperarm_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..b3387c8b623fce522cbfcbc06c52e15fa3f25c70
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/upperarm_l.iv
@@ -0,0 +1,204 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+
+    Material {
+        diffuseColor    1 1 1
+    }
+    	Transform {
+		translation 0 0 0
+		rotation 1 0 0 -1.57
+	}
+	Transform {
+		translation 0 25.3 0
+	}
+    Separator {
+        Normal {
+            vector      [ -3.74956e-17 -1 -1.73465e-18,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          1 -3.37289e-17 -1.73473e-18,
+                          1 -3.37289e-17 -1.73473e-18,
+                          0.707107 5.58844e-18 -0.707107,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          0.707107 -5.32882e-17 0.707107,
+                          0.707107 -5.32882e-17 0.707107,
+                          1 -3.37289e-17 2.43187e-16,
+                          0.707107 -5.32882e-17 0.707107,
+                          1 -3.37289e-17 2.43187e-16,
+                          1 -3.37289e-17 2.43187e-16,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          0.707107 5.58844e-18 -0.707107,
+                          0.707107 5.58844e-18 -0.707107,
+                          1.72253e-16 4.16321e-17 -1,
+                          0.707107 5.58844e-18 -0.707107,
+                          1 -3.37289e-17 -1.73473e-18,
+                          0.707107 5.58844e-18 -0.707107,
+                          1.72253e-16 4.16321e-17 -1,
+                          1.72253e-16 4.16321e-17 -1,
+                          -0.707107 5.32882e-17 -0.707107,
+                          0.707107 5.58844e-18 -0.707107,
+                          1.72253e-16 4.16321e-17 -1,
+                          1.72253e-16 4.16321e-17 -1,
+                          -0.707107 5.32882e-17 -0.707107,
+                          -0.707107 5.32882e-17 -0.707107,
+                          -1 3.37289e-17 -1.20726e-16,
+                          1.72253e-16 4.16321e-17 -1,
+                          -0.707107 5.32882e-17 -0.707107,
+                          -0.707107 5.32882e-17 -0.707107,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          -1 3.37289e-17 -1.20726e-16,
+                          -1 3.37289e-17 -1.20726e-16,
+                          -0.707107 -5.58844e-18 0.707107,
+                          -0.707107 5.32882e-17 -0.707107,
+                          -1 3.37289e-17 -1.20726e-16,
+                          -1 3.37289e-17 -1.20726e-16,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          -0.707107 -5.58844e-18 0.707107,
+                          -0.707107 -5.58844e-18 0.707107,
+                          -2.94713e-16 -4.16321e-17 1,
+                          -1 3.37289e-17 -1.20726e-16,
+                          -0.707107 -5.58844e-18 0.707107,
+                          -0.707107 -5.58844e-18 0.707107,
+                          -2.94713e-16 -4.16321e-17 1,
+                          -2.94713e-16 -4.16321e-17 1,
+                          0.707107 -5.32882e-17 0.707107,
+                          -0.707107 -5.58844e-18 0.707107,
+                          -2.94713e-16 -4.16321e-17 1,
+                          -2.94713e-16 -4.16321e-17 1,
+                          -2.94713e-16 -4.16321e-17 1,
+                          0.707107 -5.32882e-17 0.707107,
+                          0.707107 -5.32882e-17 0.707107,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -28.284 1.15818e-13 -28.284,
+                          28.284 1.1391e-13 -28.284,
+                          40 1.12338e-13 1.18516e-13,
+                          40 284 1.19009e-13,
+                          40 1.12338e-13 1.18516e-13,
+                          28.284 1.1391e-13 -28.284,
+                          -40 1.15036e-13 1.08858e-13,
+                          -28.284 1.15818e-13 -28.284,
+                          40 1.12338e-13 1.18516e-13,
+                          28.284 1.11555e-13 28.284,
+                          -40 1.15036e-13 1.08858e-13,
+                          40 1.12338e-13 1.18516e-13,
+                          28.284 284 28.284,
+                          28.284 1.11555e-13 28.284,
+                          40 1.12338e-13 1.18516e-13,
+                          28.284 284 28.284,
+                          40 1.12338e-13 1.18516e-13,
+                          40 284 1.19009e-13,
+                          -28.284 1.15818e-13 -28.284,
+                          7.79444e-14 1.15352e-13 -40,
+                          28.284 1.1391e-13 -28.284,
+                          28.284 284 -28.284,
+                          28.284 1.1391e-13 -28.284,
+                          7.79444e-14 1.15352e-13 -40,
+                          28.284 284 -28.284,
+                          40 284 1.19009e-13,
+                          28.284 1.1391e-13 -28.284,
+                          8.85931e-14 284 -40,
+                          7.79444e-14 1.15352e-13 -40,
+                          -28.284 1.15818e-13 -28.284,
+                          28.284 284 -28.284,
+                          7.79444e-14 1.15352e-13 -40,
+                          8.85931e-14 284 -40,
+                          -28.284 284 -28.284,
+                          -28.284 1.15818e-13 -28.284,
+                          -40 1.15036e-13 1.08858e-13,
+                          8.85931e-14 284 -40,
+                          -28.284 1.15818e-13 -28.284,
+                          -28.284 284 -28.284,
+                          28.284 1.11555e-13 28.284,
+                          -28.284 1.13463e-13 28.284,
+                          -40 1.15036e-13 1.08858e-13,
+                          -40 284 1.0935e-13,
+                          -40 1.15036e-13 1.08858e-13,
+                          -28.284 1.13463e-13 28.284,
+                          -28.284 284 -28.284,
+                          -40 1.15036e-13 1.08858e-13,
+                          -40 284 1.0935e-13,
+                          28.284 1.11555e-13 28.284,
+                          5.92657e-14 1.12022e-13 40,
+                          -28.284 1.13463e-13 28.284,
+                          -28.284 284 28.284,
+                          -28.284 1.13463e-13 28.284,
+                          5.92657e-14 1.12022e-13 40,
+                          -40 284 1.0935e-13,
+                          -28.284 1.13463e-13 28.284,
+                          -28.284 284 28.284,
+                          6.99145e-14 284 40,
+                          5.92657e-14 1.12022e-13 40,
+                          28.284 1.11555e-13 28.284,
+                          -28.284 284 28.284,
+                          5.92657e-14 1.12022e-13 40,
+                          6.99145e-14 284 40,
+                          6.99145e-14 284 40,
+                          28.284 1.11555e-13 28.284,
+                          28.284 284 28.284,
+                          -28.284 284 28.284,
+                          28.284 284 28.284,
+                          40 284 1.19009e-13,
+                          -40 284 1.0935e-13,
+                          -28.284 284 28.284,
+                          40 284 1.19009e-13,
+                          28.284 284 -28.284,
+                          -40 284 1.0935e-13,
+                          40 284 1.19009e-13,
+                          -28.284 284 28.284,
+                          6.99145e-14 284 40,
+                          28.284 284 28.284,
+                          28.284 284 -28.284,
+                          -28.284 284 -28.284,
+                          -40 284 1.0935e-13,
+                          28.284 284 -28.284,
+                          8.85931e-14 284 -40,
+                          -28.284 284 -28.284 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/upperarm_r.iv b/data/RobotAPI/robots/Armar3/collisionModel/upperarm_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..abb0dd11d52195869afcc6b98ecd4f01cb62df30
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/upperarm_r.iv
@@ -0,0 +1,204 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+
+    Material {
+        diffuseColor    1 1 1
+    }
+    Transform {
+		translation 0 0 0
+		rotation 1 0 0 -1.57
+	}
+	Transform {
+		translation 0 25.3 0
+	}
+	Separator {
+        Normal {
+            vector      [ -3.74956e-17 -1 -1.73465e-18,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          1 -3.37289e-17 -1.73473e-18,
+                          1 -3.37289e-17 -1.73473e-18,
+                          0.707107 5.58844e-18 -0.707107,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          0.707107 -5.32882e-17 0.707107,
+                          0.707107 -5.32882e-17 0.707107,
+                          1 -3.37289e-17 2.43187e-16,
+                          0.707107 -5.32882e-17 0.707107,
+                          1 -3.37289e-17 2.43187e-16,
+                          1 -3.37289e-17 2.43187e-16,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          0.707107 5.58844e-18 -0.707107,
+                          0.707107 5.58844e-18 -0.707107,
+                          1.72253e-16 4.16321e-17 -1,
+                          0.707107 5.58844e-18 -0.707107,
+                          1 -3.37289e-17 -1.73473e-18,
+                          0.707107 5.58844e-18 -0.707107,
+                          1.72253e-16 4.16321e-17 -1,
+                          1.72253e-16 4.16321e-17 -1,
+                          -0.707107 5.32882e-17 -0.707107,
+                          0.707107 5.58844e-18 -0.707107,
+                          1.72253e-16 4.16321e-17 -1,
+                          1.72253e-16 4.16321e-17 -1,
+                          -0.707107 5.32882e-17 -0.707107,
+                          -0.707107 5.32882e-17 -0.707107,
+                          -1 3.37289e-17 -1.20726e-16,
+                          1.72253e-16 4.16321e-17 -1,
+                          -0.707107 5.32882e-17 -0.707107,
+                          -0.707107 5.32882e-17 -0.707107,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          -1 3.37289e-17 -1.20726e-16,
+                          -1 3.37289e-17 -1.20726e-16,
+                          -0.707107 -5.58844e-18 0.707107,
+                          -0.707107 5.32882e-17 -0.707107,
+                          -1 3.37289e-17 -1.20726e-16,
+                          -1 3.37289e-17 -1.20726e-16,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          -3.74956e-17 -1 -1.73465e-18,
+                          -0.707107 -5.58844e-18 0.707107,
+                          -0.707107 -5.58844e-18 0.707107,
+                          -2.94713e-16 -4.16321e-17 1,
+                          -1 3.37289e-17 -1.20726e-16,
+                          -0.707107 -5.58844e-18 0.707107,
+                          -0.707107 -5.58844e-18 0.707107,
+                          -2.94713e-16 -4.16321e-17 1,
+                          -2.94713e-16 -4.16321e-17 1,
+                          0.707107 -5.32882e-17 0.707107,
+                          -0.707107 -5.58844e-18 0.707107,
+                          -2.94713e-16 -4.16321e-17 1,
+                          -2.94713e-16 -4.16321e-17 1,
+                          -2.94713e-16 -4.16321e-17 1,
+                          0.707107 -5.32882e-17 0.707107,
+                          0.707107 -5.32882e-17 0.707107,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18,
+                          3.74956e-17 1 1.73465e-18 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -28.284 1.15818e-13 -28.284,
+                          28.284 1.1391e-13 -28.284,
+                          40 1.12338e-13 1.18516e-13,
+                          40 284 1.19009e-13,
+                          40 1.12338e-13 1.18516e-13,
+                          28.284 1.1391e-13 -28.284,
+                          -40 1.15036e-13 1.08858e-13,
+                          -28.284 1.15818e-13 -28.284,
+                          40 1.12338e-13 1.18516e-13,
+                          28.284 1.11555e-13 28.284,
+                          -40 1.15036e-13 1.08858e-13,
+                          40 1.12338e-13 1.18516e-13,
+                          28.284 284 28.284,
+                          28.284 1.11555e-13 28.284,
+                          40 1.12338e-13 1.18516e-13,
+                          28.284 284 28.284,
+                          40 1.12338e-13 1.18516e-13,
+                          40 284 1.19009e-13,
+                          -28.284 1.15818e-13 -28.284,
+                          7.79444e-14 1.15352e-13 -40,
+                          28.284 1.1391e-13 -28.284,
+                          28.284 284 -28.284,
+                          28.284 1.1391e-13 -28.284,
+                          7.79444e-14 1.15352e-13 -40,
+                          28.284 284 -28.284,
+                          40 284 1.19009e-13,
+                          28.284 1.1391e-13 -28.284,
+                          8.85931e-14 284 -40,
+                          7.79444e-14 1.15352e-13 -40,
+                          -28.284 1.15818e-13 -28.284,
+                          28.284 284 -28.284,
+                          7.79444e-14 1.15352e-13 -40,
+                          8.85931e-14 284 -40,
+                          -28.284 284 -28.284,
+                          -28.284 1.15818e-13 -28.284,
+                          -40 1.15036e-13 1.08858e-13,
+                          8.85931e-14 284 -40,
+                          -28.284 1.15818e-13 -28.284,
+                          -28.284 284 -28.284,
+                          28.284 1.11555e-13 28.284,
+                          -28.284 1.13463e-13 28.284,
+                          -40 1.15036e-13 1.08858e-13,
+                          -40 284 1.0935e-13,
+                          -40 1.15036e-13 1.08858e-13,
+                          -28.284 1.13463e-13 28.284,
+                          -28.284 284 -28.284,
+                          -40 1.15036e-13 1.08858e-13,
+                          -40 284 1.0935e-13,
+                          28.284 1.11555e-13 28.284,
+                          5.92657e-14 1.12022e-13 40,
+                          -28.284 1.13463e-13 28.284,
+                          -28.284 284 28.284,
+                          -28.284 1.13463e-13 28.284,
+                          5.92657e-14 1.12022e-13 40,
+                          -40 284 1.0935e-13,
+                          -28.284 1.13463e-13 28.284,
+                          -28.284 284 28.284,
+                          6.99145e-14 284 40,
+                          5.92657e-14 1.12022e-13 40,
+                          28.284 1.11555e-13 28.284,
+                          -28.284 284 28.284,
+                          5.92657e-14 1.12022e-13 40,
+                          6.99145e-14 284 40,
+                          6.99145e-14 284 40,
+                          28.284 1.11555e-13 28.284,
+                          28.284 284 28.284,
+                          -28.284 284 28.284,
+                          28.284 284 28.284,
+                          40 284 1.19009e-13,
+                          -40 284 1.0935e-13,
+                          -28.284 284 28.284,
+                          40 284 1.19009e-13,
+                          28.284 284 -28.284,
+                          -40 284 1.0935e-13,
+                          40 284 1.19009e-13,
+                          -28.284 284 28.284,
+                          6.99145e-14 284 40,
+                          28.284 284 28.284,
+                          28.284 284 -28.284,
+                          -28.284 284 -28.284,
+                          -40 284 1.0935e-13,
+                          28.284 284 -28.284,
+                          8.85931e-14 284 -40,
+                          -28.284 284 -28.284 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/wrist1_l.iv b/data/RobotAPI/robots/Armar3/collisionModel/wrist1_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..7ce1897c7faf757ae43c75e03fea8f8c7f598de3
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/wrist1_l.iv
@@ -0,0 +1,37 @@
+#Inventor V2.1 ascii
+
+Separator {
+
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 1.57
+	} 
+#File {name armar/hands/axis_arrows.iv }
+
+	Separator
+	{
+	    Units {
+            units MILLIMETERS
+    }
+
+		Transform
+		{
+			translation  0 0 -21
+			rotation 1 0 0 0
+		}
+		Material {
+			diffuseColor    1 0.8 0.4
+			transparency 0.5
+		}
+		Cube
+		{
+			width 57
+			height 57
+			depth 60
+		}
+	}
+}
diff --git a/data/RobotAPI/robots/Armar3/collisionModel/wrist2_l.iv b/data/RobotAPI/robots/Armar3/collisionModel/wrist2_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..7ce1897c7faf757ae43c75e03fea8f8c7f598de3
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/collisionModel/wrist2_l.iv
@@ -0,0 +1,37 @@
+#Inventor V2.1 ascii
+
+Separator {
+
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 1.57
+	} 
+#File {name armar/hands/axis_arrows.iv }
+
+	Separator
+	{
+	    Units {
+            units MILLIMETERS
+    }
+
+		Transform
+		{
+			translation  0 0 -21
+			rotation 1 0 0 0
+		}
+		Material {
+			diffuseColor    1 0.8 0.4
+			transparency 0.5
+		}
+		Cube
+		{
+			width 57
+			height 57
+			depth 60
+		}
+	}
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/armar/hands/handlink_green_conv.wrl b/data/RobotAPI/robots/Armar3/convexModel/armar/hands/handlink_green_conv.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..4806a69592564869414f23d70f40d7b6323eac1d
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/armar/hands/handlink_green_conv.wrl
@@ -0,0 +1,52 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            -22.4766 1.02616 -32, -22.4998 8.55604e-014 -35, 22.4766 1.02616 -32, 22.4998 8.14172e-014 -35, 
+            -4 29 -36, 4 -29 -36, -4 -29 -36, 4 29 -36, 
+            11.0305 -29 -3.25208, 7.65391e-014 -29 11.4998, 9.20978 -29 6.88671, -11.0305 -29 -3.25208, 
+            -9.20978 -29 6.88671, 7.09084e-014 29 11.4998, -9.20978 29 6.88671, 9.20978 29 6.88671, 
+            -11.0305 29 -3.25208, 11.0305 29 -3.25208
+          ]
+        }
+        coordIndex
+        [
+          5,7,3,-1, 6,11,1,-1, 4,6,1,-1, 14,0,12,-1, 0,11,12,-1, 0,1,11,-1, 
+          8,5,3,-1, 16,0,14,-1, 16,4,1,-1, 1,0,16,-1, 17,3,7,-1, 17,15,2,-1, 
+          3,17,2,-1, 2,15,10,-1, 8,2,10,-1, 2,8,3,-1, 4,5,6,-1, 4,7,5,-1, 
+          8,10,9,-1, 8,11,6,-1, 5,8,6,-1, 12,11,8,-1, 8,9,12,-1, 13,12,9,-1, 
+          13,14,12,-1, 4,15,7,-1, 14,13,15,-1, 15,4,16,-1, 15,16,14,-1, 15,17,7,-1, 
+          15,9,10,-1, 15,13,9,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/armar/hands/handlink_red_conv.wrl b/data/RobotAPI/robots/Armar3/convexModel/armar/hands/handlink_red_conv.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..c0c85117ede25234946fdff69d69fe62cbf117f9
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/armar/hands/handlink_red_conv.wrl
@@ -0,0 +1,50 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            27.5 8.34085e-014 -9.49987, 27.5 8.5851e-014 9.49987, 28.5 -22 5, 28.5 -22 -5, 
+            28.5 22 -5, 28.5 22 5, -27.5 22 5, 7.45206e-014 22 12, 
+            8.03921e-014 22 -12, -27.5 22 -5, -27.5 -22 -5, 7.59207e-014 -22 -12, 
+            7.88663e-014 -22 12, -27.5 -22 5, -27.5 8.69845e-014 -9.49987, -27.5 8.24326e-014 9.49987
+          ]
+        }
+        coordIndex
+        [
+          6,15,7,-1, 12,15,13,-1, 12,7,15,-1, 0,4,3,-1, 0,8,4,-1, 3,11,0,-1, 
+          0,11,8,-1, 1,2,5,-1, 1,5,7,-1, 1,12,2,-1, 12,1,7,-1, 14,9,8,-1, 
+          8,11,14,-1, 11,10,14,-1, 2,3,4,-1, 2,4,5,-1, 6,5,4,-1, 7,5,6,-1, 
+          6,8,9,-1, 4,8,6,-1, 2,10,3,-1, 10,11,3,-1, 12,10,2,-1, 10,12,13,-1, 
+          14,10,13,-1, 13,15,14,-1, 14,15,6,-1, 14,6,9,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/armar/hands/metacarpals_conv.wrl b/data/RobotAPI/robots/Armar3/convexModel/armar/hands/metacarpals_conv.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..ec199da48eed5c4ed17be33d88c548a65a4cecbc
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/armar/hands/metacarpals_conv.wrl
@@ -0,0 +1,52 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            -42.25 2.25 2.5, -37.6 2.25 -5, 2.4 2.25 -5, 2.4 2.25 5, 
+            -37.6 2.25 5, -42.25 2.25 -2.5, -37.6 -2.25 5, -42.25 -2.25 2.5, 
+            -42.25 -2.25 -2.5, -37.6 -2.25 -5, 2.37907 -0.291737 5, 1.21165 -1.98485 5.00008, 
+            -12 -3.75 5, 2.30391 -0.754205 -5, 0.813474 -2.0719 -5.00005, -29.5153 -3.75018 -4.99729, 
+            -29.1823 -3.74998 4.99954, -9.25325 -3.74728 -4.96859, -7.03843 -3.74906 2.70092, -33.101 -3.75845 1.15241
+          ]
+        }
+        coordIndex
+        [
+          14,11,18,-1, 6,7,16,-1, 15,8,9,-1, 18,11,12,-1, 17,14,18,-1, 8,19,7,-1, 
+          19,16,7,-1, 19,8,15,-1, 1,0,2,-1, 3,2,0,-1, 3,0,4,-1, 5,0,1,-1, 
+          4,0,6,-1, 6,0,7,-1, 8,0,5,-1, 0,8,7,-1, 8,5,1,-1, 9,8,1,-1, 
+          3,10,2,-1, 2,10,13,-1, 4,11,3,-1, 16,11,6,-1, 6,11,4,-1, 16,12,11,-1, 
+          10,3,11,-1, 13,11,14,-1, 10,11,13,-1, 1,2,14,-1, 17,15,14,-1, 9,14,15,-1, 
+          9,1,14,-1, 13,14,2,-1, 18,15,17,-1, 16,15,12,-1, 12,15,18,-1, 19,15,16,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/armar/hands/palm1_l_conv.wrl b/data/RobotAPI/robots/Armar3/convexModel/armar/hands/palm1_l_conv.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..5c73d61fa4caf185c722abc3cea6c85e031733fa
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/armar/hands/palm1_l_conv.wrl
@@ -0,0 +1,48 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            -18.5 -38.5 -2.66454e-015, 18.5 -38.5 -6.66134e-016, -23.5124 -41.3768 33.4922, 13.3308 10.8411 -9.08804, 
+            16.1904 -6.49717 31.5042, -17.5597 6.54184 -5.89561, -15.9133 -6.33958 31.4128, 0.0205968 1.48635 -12.5142, 
+            68.4883 -23.6013 33.4646, -23.8137 -19.8751 33.5032, -0.60131 -53.3117 32.7342, 66.5701 -17.3933 33.5096
+          ]
+        }
+        coordIndex
+        [
+          8,10,1,-1, 3,8,1,-1, 11,8,3,-1, 1,7,3,-1, 0,10,2,-1, 3,5,6,-1, 
+          0,7,1,-1, 3,7,5,-1, 5,7,0,-1, 5,9,6,-1, 9,4,6,-1, 2,9,0,-1, 
+          0,9,5,-1, 0,1,10,-1, 3,6,4,-1, 3,4,11,-1, 10,8,11,-1, 9,2,11,-1, 
+          2,10,11,-1, 4,9,11,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/armar/hands/palm1_r_conv.wrl b/data/RobotAPI/robots/Armar3/convexModel/armar/hands/palm1_r_conv.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..4b648662c8f55fed339aa14a202c990203f0101f
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/armar/hands/palm1_r_conv.wrl
@@ -0,0 +1,52 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            16.7567 1.89485 5.82853, 13.0882 11.9058 5.04174, -17.5738 4.94468 5.79025, -12.5606 14.108 -3.2542, 
+            0.501579 20.6323 0.529517, -0.113528 -52.7653 -31.0137, -18.5 -38.5 -4.44089e-016, 18.5 -38.5 -4.44089e-016, 
+            -23.8061 -38.2781 -33.436, -23.7957 -19.8388 -33.5071, 68.3495 -19.755 -33.5059, -15.8 -6.45 -31.5, 
+            15.8 -6.45 -31.5, 68.5216 -23.5911 -33.4868, 19.8215 -40.9 -33.5, 3.36627 19.4258 4.51424, 
+            0.0346062 1.413 12.4932, -15.0617 -46.4276 -33.4981, 62.0141 -16.4696 -33.4994
+          ]
+        }
+        coordIndex
+        [
+          12,11,4,-1, 11,3,4,-1, 7,16,6,-1, 6,17,5,-1, 12,4,18,-1, 0,16,7,-1, 
+          4,10,18,-1, 15,10,4,-1, 16,2,6,-1, 5,13,7,-1, 14,13,5,-1, 10,1,0,-1, 
+          0,13,10,-1, 13,0,7,-1, 11,18,9,-1, 1,10,15,-1, 1,16,0,-1, 6,8,17,-1, 
+          15,2,16,-1, 3,2,15,-1, 9,3,11,-1, 15,16,1,-1, 9,2,3,-1, 3,15,4,-1, 
+          6,5,7,-1, 6,2,8,-1, 8,2,9,-1, 12,18,11,-1, 10,17,18,-1, 18,17,9,-1, 
+          14,5,17,-1, 14,17,13,-1, 10,13,17,-1, 8,9,17,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/armar/hands/palm2_l_conv.wrl b/data/RobotAPI/robots/Armar3/convexModel/armar/hands/palm2_l_conv.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..a757f837de2a5f9e06295bf0f057d9a4adf1d5f1
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/armar/hands/palm2_l_conv.wrl
@@ -0,0 +1,48 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            -42.0681 -2.34763 -2.60728, -42.1723 2.25012 -4.9722, 2.4 2.25 -5, -42.491 2.25024 77.8233, 
+            2.7915 2.04237 29.9905, -4.25427 2.25003 77.9286, -42.5227 -2.24049 76.4546, -7.83856 -4.25081 80.0011, 
+            -7.84609 -4.24976 -10.7783, -3.8 -2.25 75, 2.05365 -1.73434 -5.06457, -32.184 -4.25016 79.6603
+          ]
+        }
+        coordIndex
+        [
+          7,4,9,-1, 1,6,3,-1, 0,6,1,-1, 8,1,2,-1, 5,4,2,-1, 3,5,1,-1, 
+          1,5,2,-1, 11,3,6,-1, 10,7,8,-1, 3,7,5,-1, 11,7,3,-1, 10,4,7,-1, 
+          5,7,9,-1, 1,8,0,-1, 8,2,10,-1, 10,2,4,-1, 9,4,5,-1, 0,11,6,-1, 
+          7,11,8,-1, 0,8,11,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/armar/hands/palm2_r_conv.wrl b/data/RobotAPI/robots/Armar3/convexModel/armar/hands/palm2_r_conv.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..5b7259bef6d34a5c6e4c36f503229d28c2308a49
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/armar/hands/palm2_r_conv.wrl
@@ -0,0 +1,48 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            32.1224 -4.25231 -10.4567, -2.4 2.25 -5, 3.8 -2.25 75, 4.28171 2.24992 78.0182, 
+            42.45 -2.25 75.3, 42.5078 2.25011 77.7853, -2.4 2.25 32, 42.1538 2.25188 -4.78192, 
+            42.25 -2.2501 -2.50102, 7.8 -4.25 75.5, 7.86569 -4.24863 -11.8715, -2.91081 -1.58332 -3.67394
+          ]
+        }
+        coordIndex
+        [
+          4,9,0,-1, 9,4,5,-1, 8,4,0,-1, 9,3,2,-1, 6,11,2,-1, 11,9,2,-1, 
+          10,7,0,-1, 7,10,1,-1, 5,3,9,-1, 5,1,6,-1, 6,3,5,-1, 5,7,1,-1, 
+          5,8,7,-1, 5,4,8,-1, 11,1,10,-1, 0,7,8,-1, 11,6,1,-1, 6,2,3,-1, 
+          0,9,10,-1, 11,10,9,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/armar/hands/proximal_index_middle_thumb_conv.wrl b/data/RobotAPI/robots/Armar3/convexModel/armar/hands/proximal_index_middle_thumb_conv.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..a88c46fec92e35e34e237df3cf77cb453e1a50a6
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/armar/hands/proximal_index_middle_thumb_conv.wrl
@@ -0,0 +1,57 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            -50.4423 -2.09615 9.15385, -50.4423 -2.09615 -9.15385, -7.09347 -3.75042 3.90676, -35.75 12.75 -1.26352, 
+            -58.75 5.75 4.16326, -58.75 5.75 -4.16326, -35.75 12.75 1.26352, -25.75 12.75 -3, 
+            -25.75 12.75 3, 2.55459 2.19637 4.99159, 2.50914 2.21273 -4.99469, -25.75 -1.25 10, 
+            -46.75 1.93915 10, -46.75 -1.25 10, -25.75 5.64201 10, -58.7009 2.71741 -7.16797, 
+            -58.6897 2.70784 7.17851, -46.75 -4.25 7, -46.75 -4.25 -7, -46.75 -1.25 -10, 
+            -25.75 -1.25 -10, -25.75 5.64201 -10, -46.75 1.93915 -10, -23.8381 -4.23454 -6.88667, 
+            -25.75 -4.25 7, 1.13242 -2.00952 -5.04626, 1.03971 -2.0276 5.04455
+          ]
+        }
+        coordIndex
+        [
+          8,14,9,-1, 6,4,16,-1, 10,21,7,-1, 7,21,22,-1, 22,3,7,-1, 15,22,1,-1, 
+          12,14,8,-1, 12,8,6,-1, 12,6,16,-1, 16,17,0,-1, 17,13,0,-1, 13,12,0,-1, 
+          5,3,15,-1, 15,3,22,-1, 18,15,1,-1, 16,0,12,-1, 26,2,25,-1, 19,1,22,-1, 
+          19,18,1,-1, 26,9,11,-1, 24,23,2,-1, 25,23,20,-1, 23,25,2,-1, 20,10,25,-1, 
+          24,2,26,-1, 26,11,24,-1, 4,3,5,-1, 3,4,6,-1, 7,8,9,-1, 7,9,10,-1, 
+          7,3,6,-1, 8,7,6,-1, 11,12,13,-1, 12,11,14,-1, 15,4,5,-1, 15,16,4,-1, 
+          15,17,16,-1, 15,18,17,-1, 19,21,20,-1, 19,22,21,-1, 23,19,20,-1, 19,23,18,-1, 
+          11,9,14,-1, 24,11,13,-1, 24,13,17,-1, 18,24,17,-1, 23,24,18,-1, 10,20,21,-1, 
+          25,10,9,-1, 9,26,25,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/armar/hands/proximal_pinky_conv.wrl b/data/RobotAPI/robots/Armar3/convexModel/armar/hands/proximal_pinky_conv.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..3cee1a4c0c5884957d688ce3c9a715f5b0993acf
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/armar/hands/proximal_pinky_conv.wrl
@@ -0,0 +1,52 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            -43.4209 2.52175 -7.41341, -20.75 12.75 -1.26352, -43.75 5.75 4.16326, -43.75 5.75 -4.16326, 
+            -11.5985 13.5476 2.14361, 5.49407 -0.325212 4.6571, 2.4 2.25 -5, -10.75 12.75 -3, 
+            -10.75 5.64201 10, -42.1114 1.75582 8.40348, -10.9098 -1.23412 10.0214, -10.75 -4.25 7, 
+            -31.75 -4.25 7, -31.75 -4.25 -7, -10.75 -4.25 -7, -10.9358 -1.22367 -10.0327, 
+            -31.75 1.93915 -10, -10.75 5.64201 -10, 2.19193 -1.80223 -5.02926
+          ]
+        }
+        coordIndex
+        [
+          2,9,4,-1, 6,17,7,-1, 7,17,16,-1, 1,7,16,-1, 11,5,10,-1, 4,8,5,-1, 
+          4,9,8,-1, 10,9,12,-1, 0,3,1,-1, 0,1,16,-1, 15,0,16,-1, 0,15,13,-1, 
+          15,18,14,-1, 2,1,3,-1, 1,2,4,-1, 4,5,6,-1, 6,7,4,-1, 7,1,4,-1, 
+          10,8,9,-1, 12,11,10,-1, 0,2,3,-1, 2,0,9,-1, 13,11,12,-1, 13,14,11,-1, 
+          13,9,0,-1, 13,12,9,-1, 5,8,10,-1, 16,17,15,-1, 13,15,14,-1, 18,6,5,-1, 
+          18,15,17,-1, 18,17,6,-1, 11,14,18,-1, 18,5,11,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/armar/hands/proximal_ring_conv.wrl b/data/RobotAPI/robots/Armar3/convexModel/armar/hands/proximal_ring_conv.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..434f866a0c59dba56d43854f464aa526a20b1cfb
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/armar/hands/proximal_ring_conv.wrl
@@ -0,0 +1,52 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            -51.25 5.75 4.16326, -49.2735 6.40436 -3.86207, -28.25 12.75 1.26352, -18.4554 -1.23462 -10.0253, 
+            -18.25 5.64201 -10, -49.7817 1.83906 -8.30407, -39.25 -4.25 -7, -18.25 -4.25 -7, 
+            -18.25 12.75 -3, -18.25 12.75 3, 2.51178 2.19657 4.99308, 2.56274 2.17412 -4.98716, 
+            -18.4554 -1.23462 10.0253, -49.6462 1.74425 8.40741, -18.25 5.64201 10, -18.25 -4.25 7, 
+            -39.25 -4.25 7, 1.09203 -2.11773 4.90299, 1.00888 -2.12524 -4.91476
+          ]
+        }
+        coordIndex
+        [
+          9,13,14,-1, 13,9,2,-1, 2,0,13,-1, 7,3,18,-1, 4,8,11,-1, 4,5,8,-1, 
+          1,8,5,-1, 14,10,9,-1, 12,15,17,-1, 5,3,6,-1, 11,18,3,-1, 12,17,10,-1, 
+          12,13,16,-1, 2,1,0,-1, 4,3,5,-1, 6,3,7,-1, 2,8,1,-1, 9,8,2,-1, 
+          1,5,0,-1, 0,5,13,-1, 10,8,9,-1, 8,10,11,-1, 13,12,14,-1, 4,11,3,-1, 
+          18,17,7,-1, 7,17,15,-1, 6,7,16,-1, 15,16,7,-1, 15,12,16,-1, 5,16,13,-1, 
+          5,6,16,-1, 12,10,14,-1, 11,17,18,-1, 10,17,11,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/armar/head/head_base_conv.wrl b/data/RobotAPI/robots/Armar3/convexModel/armar/head/head_base_conv.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..de0417fe3173194e2fdb36a93994970f69c8e9a6
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/armar/head/head_base_conv.wrl
@@ -0,0 +1,49 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            -41.1039 43.7602 617.779, 7.81597e-014 -42.5 611, -46.0363 -42.5693 617.615, 4.26326e-014 42.5 611, 
+            29.1231 17.298 540.366, -29.2075 42.4747 540, -0.00505374 42.4953 540.001, -0.00127362 -42.4919 540.005, 
+            -46.4495 -42.4599 540, -47 42.5 596, -99.8249 17.9598 540.03, -99.2888 -17.4764 540.037, 
+            29.1468 -17.2774 540.006, -56.7568 -42.5 580.598
+          ]
+        }
+        coordIndex
+        [
+          2,0,10,-1, 9,5,10,-1, 13,11,8,-1, 2,11,13,-1, 2,1,0,-1, 0,1,3,-1, 
+          3,1,4,-1, 4,1,12,-1, 6,3,4,-1, 2,10,11,-1, 9,0,3,-1, 9,3,6,-1, 
+          5,9,6,-1, 10,0,9,-1, 10,5,12,-1, 12,5,6,-1, 12,6,4,-1, 12,7,8,-1, 
+          8,11,12,-1, 12,11,10,-1, 12,1,7,-1, 8,7,13,-1, 13,7,1,-1, 13,1,2,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/armar/head/head_conv.wrl b/data/RobotAPI/robots/Armar3/convexModel/armar/head/head_conv.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..6c4ca129132d0b2748bf174d41d49cc0c66fa924
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/armar/head/head_conv.wrl
@@ -0,0 +1,59 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            76.2284 111.549 -41.7805, 67.6107 85.0493 114.224, -70.7087 133.938 72.1921, -28.042 146.167 95.3655, 
+            -111.471 36.2776 -34.3022, 62.9263 134.203 92.8143, -64.7468 130.394 -40.7527, 114.307 34.0121 -31.7969, 
+            54.6149 -27.1168 122.592, -74.9926 5.09897 -35.204, 77.0703 8.27037 -32.1692, 70.815 -20.8217 -17.8304, 
+            73.9144 -50.4021 22.8227, 71.1742 143.95 28.0985, -56.8438 -28.7732 121.064, 78.8132 -27.175 99.0056, 
+            -27.9918 166.733 68.4598, -62.034 151.967 -18.4861, -71.3292 78.5465 106.784, 24.1388 174.416 34.9113, 
+            59.1917 -60.2835 79.917, -74.4022 -38.2505 -7.24999, -69.464 -63.3037 75.2388, -77.7596 -21.5607 101.949, 
+            -118.271 61.9954 -3.85212, 47.4841 88.0041 124.11, -52.7927 89.2714 123.58, -2.74027 -42.1388 139.665, 
+            61.6339 149.482 -22.072, -77.589 65.115 -43.1315, 78.406 65.1858 -43.165, 118.327 62.416 -3.98868
+          ]
+        }
+        coordIndex
+        [
+          5,3,25,-1, 30,10,9,-1, 17,28,6,-1, 13,31,28,-1, 31,5,1,-1, 3,26,25,-1, 
+          3,5,16,-1, 3,16,2,-1, 6,29,4,-1, 29,30,9,-1, 29,9,4,-1, 30,7,10,-1, 
+          24,6,4,-1, 24,17,6,-1, 28,0,6,-1, 31,7,0,-1, 28,31,0,-1, 15,31,1,-1, 
+          2,26,3,-1, 21,4,9,-1, 30,0,7,-1, 7,15,12,-1, 22,20,27,-1, 20,8,27,-1, 
+          13,19,5,-1, 13,28,19,-1, 5,31,13,-1, 27,26,14,-1, 2,24,18,-1, 14,26,23,-1, 
+          1,5,25,-1, 25,8,1,-1, 16,5,19,-1, 16,17,2,-1, 16,19,17,-1, 8,15,1,-1, 
+          22,27,14,-1, 12,11,7,-1, 21,11,12,-1, 12,22,21,-1, 12,15,20,-1, 15,8,20,-1, 
+          11,21,9,-1, 11,9,10,-1, 11,10,7,-1, 2,17,24,-1, 15,7,31,-1, 25,27,8,-1, 
+          22,23,24,-1, 26,2,18,-1, 18,23,26,-1, 12,20,22,-1, 24,23,18,-1, 22,24,4,-1, 
+          22,4,21,-1, 22,14,23,-1, 25,26,27,-1, 17,19,28,-1, 30,29,6,-1, 6,0,30,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/armar/left_arm/elbow_link_l_conv.wrl b/data/RobotAPI/robots/Armar3/convexModel/armar/left_arm/elbow_link_l_conv.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..6752ae63930cb5c32d64e8a88beb61bcb503601e
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/armar/left_arm/elbow_link_l_conv.wrl
@@ -0,0 +1,52 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            -36.1261 24.3894 -12.0869, -36.3318 8.25542 -27.0525, -36.4752 -13.3378 -23.8698, -27.5 -11.3909 46.5, 
+            -36.5181 10.9736 25.2441, 36.5021 13.7969 25.4252, 33.1924 28.9249 18.88, 36.5 -28.5 25.5, 
+            28.7562 0.6096 47.793, -36.6253 -28.9511 24.7118, 36.5 -28.5 17, -36.3423 28.6794 17.5351, 
+            -11.3909 -27.5 46.5, 11.3909 -27.5 46.5, -36.4983 -24.4048 -12.3621, 36.5056 -8.14029 -11.5467, 
+            38.0272 8.00417 -11.4865, 11.3909 27.5 46.5, -23.5026 21.9188 45.87
+          ]
+        }
+        coordIndex
+        [
+          6,16,0,-1, 5,6,8,-1, 11,6,0,-1, 16,6,5,-1, 13,7,8,-1, 9,7,13,-1, 
+          11,4,18,-1, 12,3,9,-1, 15,14,2,-1, 10,14,15,-1, 16,1,0,-1, 1,16,15,-1, 
+          1,15,2,-1, 6,17,8,-1, 9,3,4,-1, 4,3,18,-1, 7,5,8,-1, 9,10,7,-1, 
+          9,13,12,-1, 9,14,10,-1, 9,11,14,-1, 1,11,0,-1, 4,11,9,-1, 2,14,11,-1, 
+          2,11,1,-1, 7,15,5,-1, 5,15,16,-1, 7,10,15,-1, 12,17,3,-1, 8,17,13,-1, 
+          3,17,18,-1, 12,13,17,-1, 11,17,6,-1, 18,17,11,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/armar/left_arm/shoulder_l_conv.wrl b/data/RobotAPI/robots/Armar3/convexModel/armar/left_arm/shoulder_l_conv.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..eb86bfe2a25f0e3a3777f4ae0fa8311b73071d16
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/armar/left_arm/shoulder_l_conv.wrl
@@ -0,0 +1,52 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            73.2256 82.4698 87.7513, 141.682 16.2229 -86.9985, 133.219 -27.2518 87.9985, 70.23 -60.5055 58.9944, 
+            59.9132 -61.9683 -87.0036, 76.2231 72.3752 -86.9909, 3.23005 -61.992 -87.0058, 0.326489 78.5959 -80.1804, 
+            0.230049 -60.5055 58.9944, 0.230049 49.9945 59.0046, 0.230049 -60.4946 -58.0056, 59.524 -62.0082 87.9942, 
+            3.23005 -62.0082 87.9942, 140.265 19.8945 88.3866, 143.939 -10.9637 -87.001, 143.939 -10.9791 87.999, 
+            73.23 82.507 -74.9923, 1.4556 75.8526 87.9991, 133.508 -27.2814 -87.0955
+          ]
+        }
+        coordIndex
+        [
+          11,2,12,-1, 7,5,6,-1, 5,1,4,-1, 17,7,9,-1, 17,8,12,-1, 2,17,12,-1, 
+          8,17,9,-1, 8,6,12,-1, 10,6,8,-1, 6,4,11,-1, 3,11,4,-1, 10,7,6,-1, 
+          13,0,15,-1, 1,13,14,-1, 2,15,17,-1, 0,17,15,-1, 3,2,11,-1, 17,16,7,-1, 
+          0,16,17,-1, 16,5,7,-1, 5,13,1,-1, 5,16,13,-1, 0,13,16,-1, 18,1,14,-1, 
+          1,18,4,-1, 15,18,14,-1, 2,18,15,-1, 2,3,18,-1, 4,18,3,-1, 5,4,6,-1, 
+          9,7,8,-1, 8,7,10,-1, 12,6,11,-1, 14,13,15,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/armar/left_arm/shoulder_link_l_conv.wrl b/data/RobotAPI/robots/Armar3/convexModel/armar/left_arm/shoulder_link_l_conv.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..b4b2c29a8b7f43694435c7232ad9145124bdf880
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/armar/left_arm/shoulder_link_l_conv.wrl
@@ -0,0 +1,50 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            30 -38 50, -30 -38 50, -40 -75 28, 30 -75 28, 
+            -40 -75 -28, 60.3151 -33.8545 -51.8987, -30 -38 -51, -41.2092 -35.8693 0.0604578, 
+            -30 -7.10543e-015 50, 26.4121 16.4208 50.2057, -12.0605 29.1462 50.0504, -23.6635 19.1544 -51.2677, 
+            6.98506 30.6394 -50.9239, 53.8266 -8.20959 -50.977, 28.8147 -74.908 -26.1639
+          ]
+        }
+        coordIndex
+        [
+          0,3,5,-1, 5,13,9,-1, 9,12,10,-1, 9,13,12,-1, 11,8,10,-1, 0,2,3,-1, 
+          0,1,2,-1, 0,5,9,-1, 4,6,5,-1, 4,5,14,-1, 4,2,7,-1, 8,0,9,-1, 
+          1,0,8,-1, 8,9,10,-1, 8,2,1,-1, 7,2,8,-1, 6,4,11,-1, 11,4,7,-1, 
+          8,11,7,-1, 10,12,11,-1, 11,12,13,-1, 13,5,6,-1, 6,11,13,-1, 2,14,3,-1, 
+          14,2,4,-1, 14,5,3,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/armar/left_arm/underarm_l_conv.wrl b/data/RobotAPI/robots/Armar3/convexModel/armar/left_arm/underarm_l_conv.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..3762b7a593c7400ba121f42e5347963201ef1377
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/armar/left_arm/underarm_l_conv.wrl
@@ -0,0 +1,55 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            -45.5 1.5 20, -31.7337 34.7337 166, -31.7337 34.7337 20, -45.5 1.5 166, 
+            34.7337 -31.7337 20, 34.7337 -31.7337 166, 48.5 1.5 166, 48.5 1.5 20, 
+            -22.5 -8.30662 203.5, -22.5 8.30662 203.5, 22.5 8.30662 203.5, 22.5 -8.30662 203.5, 
+            -22.5 22.5 0, 22.5 22.5 0, 22.5 -22.5 0, -22.5 -22.5 0, 
+            1.5 48.5 20, 1.5 48.5 166, 34.7337 34.7337 20, 34.7337 34.7337 166, 
+            1.5 -45.5 20, 1.5 -45.5 166, -31.7337 -31.7337 20, -31.7337 -31.7337 166
+          ]
+        }
+        coordIndex
+        [
+          10,11,6,-1, 5,6,11,-1, 19,10,6,-1, 10,19,17,-1, 13,7,14,-1, 9,17,1,-1, 
+          9,10,17,-1, 9,1,3,-1, 14,7,4,-1, 8,9,3,-1, 12,0,2,-1, 12,15,0,-1, 
+          13,12,16,-1, 16,12,2,-1, 11,8,21,-1, 21,5,11,-1, 7,13,18,-1, 13,16,18,-1, 
+          20,15,14,-1, 4,20,14,-1, 23,8,3,-1, 23,21,8,-1, 15,20,22,-1, 22,0,15,-1, 
+          0,1,2,-1, 0,3,1,-1, 5,4,6,-1, 4,7,6,-1, 9,8,10,-1, 8,11,10,-1, 
+          12,13,14,-1, 12,14,15,-1, 1,16,2,-1, 16,1,17,-1, 6,7,18,-1, 18,19,6,-1, 
+          18,16,17,-1, 19,18,17,-1, 20,4,5,-1, 21,20,5,-1, 22,20,21,-1, 23,22,21,-1, 
+          3,0,22,-1, 22,23,3,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/armar/left_arm/upperarm_l_conv.wrl b/data/RobotAPI/robots/Armar3/convexModel/armar/left_arm/upperarm_l_conv.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..e0e4d1f17a634f77b93d8848a0821625c92fd8f9
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/armar/left_arm/upperarm_l_conv.wrl
@@ -0,0 +1,54 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            -69.8355 28.1781 26.8894, -229.119 1.54814 38.4039, -69.9264 15.2909 35.6923, -244.141 37.2961 19.2573, 
+            -284.721 39.3677 10.0836, -70.6044 33.2781 -24.1417, -69.1143 39.8983 5.13665, -68.9291 -38.8604 12.1225, 
+            -69.2654 -6.71779 -41.3432, -71.9736 -9.72486 39.4215, -284.107 -22.9446 11.0199, -233.271 -33.2258 21.1604, 
+            -69.157 14.5311 -38.2109, -294.131 36.8744 -33.73, -231.351 -40.172 -8.04525, -71.5599 -33.932 -24.7056, 
+            -295.205 -23.0207 -32.3774, -136.224 -0.94764 -43.3748, 2.72395 -8.84517 13.831, 2.65321 9.83339 -12.58, 
+            4.76682 11.7526 8.27785, 0.704879 -12.8186 -9.53215
+          ]
+        }
+        coordIndex
+        [
+          0,2,20,-1, 18,20,2,-1, 0,6,3,-1, 0,20,6,-1, 0,3,2,-1, 18,2,9,-1, 
+          4,13,16,-1, 7,21,18,-1, 2,1,9,-1, 3,1,2,-1, 3,4,1,-1, 13,6,5,-1, 
+          19,12,5,-1, 8,12,19,-1, 5,12,13,-1, 13,4,6,-1, 6,4,3,-1, 10,4,16,-1, 
+          4,10,1,-1, 13,17,16,-1, 7,15,21,-1, 14,15,7,-1, 18,9,7,-1, 9,11,7,-1, 
+          11,9,1,-1, 20,19,6,-1, 5,6,19,-1, 8,17,12,-1, 10,14,11,-1, 11,14,7,-1, 
+          21,8,19,-1, 1,10,11,-1, 12,17,13,-1, 14,10,16,-1, 17,15,16,-1, 15,14,16,-1, 
+          15,8,21,-1, 15,17,8,-1, 18,19,20,-1, 18,21,19,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/armar/neck/neck_pitch_link_conv.wrl b/data/RobotAPI/robots/Armar3/convexModel/armar/neck/neck_pitch_link_conv.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..ee5ce751f04d92035d2b1e24ffe64e424fd1cbd8
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/armar/neck/neck_pitch_link_conv.wrl
@@ -0,0 +1,51 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            24.2652 -7.27071 -11.7137, 24.6353 -0 11.3899, -18.5 -23 25, 24.5 36 5, 
+            24.5 -36 -5, 24.5 -36 5, -24.9995 -39.9507 -10.1209, 3.78524 79.5368 -1.1784, 
+            -25.0021 0.128458 -14.9224, -25 36 -10, 20.0336 40.0786 -8.24146, -25 -23 25, 
+            -25 36 10, -24.0182 23.2465 26.8282, -25 -43.5 10, 1.29119 -83.2905 2.16129, 
+            -0.831482 -82.7256 -3.28611
+          ]
+        }
+        coordIndex
+        [
+          5,15,4,-1, 0,4,16,-1, 16,4,15,-1, 7,12,13,-1, 2,5,1,-1, 0,6,8,-1, 
+          6,0,16,-1, 3,13,1,-1, 16,14,6,-1, 13,3,7,-1, 7,9,12,-1, 7,3,10,-1, 
+          7,10,9,-1, 0,8,10,-1, 15,11,14,-1, 16,15,14,-1, 2,11,15,-1, 15,5,2,-1, 
+          1,13,2,-1, 0,10,3,-1, 0,5,4,-1, 0,1,5,-1, 0,3,1,-1, 9,10,8,-1, 
+          13,12,11,-1, 11,9,8,-1, 6,14,11,-1, 11,12,9,-1, 11,8,6,-1, 11,2,13,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/armar/neck/neck_roll_link_conv.wrl b/data/RobotAPI/robots/Armar3/convexModel/armar/neck/neck_roll_link_conv.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..f3b439d1f89b9145ecbbca72c52fa2c8d86bf99b
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/armar/neck/neck_roll_link_conv.wrl
@@ -0,0 +1,49 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            -16 -57.5 -100, -4.62206 1.61543e-006 -35.7597, -16 57.5 -100, 4.62206 0 -35.7597, 
+            16 57.5 -100, 16 -57.5 -100, 1.29833e-006 3.73829e-008 -31.9881, -16 57.5 -104, 
+            16 57.5 -104, 6.2234 -57.4801 -130.345, -16 -57.4991 -111.382, -6.37885 -57.3111 -130.054, 
+            16 -57.4782 -111.38
+          ]
+        }
+        coordIndex
+        [
+          2,6,4,-1, 3,4,6,-1, 1,6,2,-1, 0,5,6,-1, 0,6,1,-1, 3,6,5,-1, 
+          10,7,11,-1, 9,8,12,-1, 0,1,2,-1, 3,5,4,-1, 8,7,4,-1, 4,7,2,-1, 
+          8,9,7,-1, 11,7,9,-1, 2,10,0,-1, 7,10,2,-1, 5,12,4,-1, 4,12,8,-1, 
+          10,9,0,-1, 0,9,5,-1, 9,10,11,-1, 9,12,5,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/armar/neck/neck_yaw_link_conv.wrl b/data/RobotAPI/robots/Armar3/convexModel/armar/neck/neck_yaw_link_conv.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..1d93305883a3ddae10139dc0f4837393f4eee390
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/armar/neck/neck_yaw_link_conv.wrl
@@ -0,0 +1,51 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            -12.5 -16.5 7, -12.5 16.5 7, 14.6535 -15.7477 28.1406, 14.6535 15.7477 28.1405, 
+            23.5005 1.83202 2.99503, -6.30819 -34.9618 -77.8439, -25.7791 20.6194 -77.8, -6.03916 35.1048 -78.2021, 
+            14.9649 -31.2039 -77.7664, 31.1705 -15.8656 -76.7877, -25.7791 -20.6194 -77.8, -47.7383 -3.14719 1.96554, 
+            -48.3253 2.58241 3.43642, -32.1726 -7.34303 -77.8, -32.231 7.16717 -77.7979, 30.9571 16.4229 -77.7751, 
+            14.3185 29.7318 -65.8
+          ]
+        }
+        coordIndex
+        [
+          11,5,0,-1, 2,11,0,-1, 5,8,2,-1, 5,2,0,-1, 12,1,7,-1, 6,12,7,-1, 
+          5,11,10,-1, 11,13,10,-1, 14,13,11,-1, 12,6,14,-1, 3,7,1,-1, 12,3,1,-1, 
+          8,9,2,-1, 3,12,2,-1, 2,12,11,-1, 15,16,3,-1, 3,16,7,-1, 15,3,4,-1, 
+          9,15,4,-1, 4,3,2,-1, 2,9,4,-1, 14,11,12,-1, 10,13,15,-1, 13,14,15,-1, 
+          15,9,8,-1, 15,5,10,-1, 15,14,6,-1, 7,15,6,-1, 15,8,5,-1, 16,15,7,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/armar/platform/hd_platform_pitch_link_conv.wrl b/data/RobotAPI/robots/Armar3/convexModel/armar/platform/hd_platform_pitch_link_conv.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..2038431b08211625dd0546110644fc49fd9a6df6
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/armar/platform/hd_platform_pitch_link_conv.wrl
@@ -0,0 +1,54 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            43 188 0, 7.4399e-015 188 -42.9999, 2.3921 188 42.1914, -45.5 157 40.5, 
+            -45.5 -162 40.5, -70.698 -0.566364 11.6518, 41.2071 -137.701 -44.7646, 45.5 157 -40.5, 
+            -41.5 -96 -44.5, -45.5 -162 -40.5, 7 -99.5 86, -45.5 157 -40.5, 
+            45.5 157 40.5, 45.5 -162 40.5, 4.7842 -187 -42.4609, 9.5684 -187 41.9219, 
+            43 -187 0, -43 -187 0, 19.1244 219.8 19.1244, 0.42148 228.029 -23.2069, 
+            -37.489 213.798 11.9237, 62.75 1.0263 -1.07294
+          ]
+        }
+        coordIndex
+        [
+          6,1,7,-1, 15,10,4,-1, 12,13,21,-1, 6,8,1,-1, 6,14,9,-1, 17,4,5,-1, 
+          17,5,9,-1, 10,15,13,-1, 1,19,7,-1, 12,2,10,-1, 10,3,5,-1, 10,2,3,-1, 
+          4,10,5,-1, 20,5,3,-1, 7,0,21,-1, 0,12,21,-1, 16,14,6,-1, 6,21,16,-1, 
+          16,21,13,-1, 11,1,8,-1, 11,20,19,-1, 5,20,11,-1, 17,15,4,-1, 15,16,13,-1, 
+          0,7,19,-1, 18,2,12,-1, 9,14,17,-1, 11,19,1,-1, 18,20,2,-1, 20,3,2,-1, 
+          0,19,18,-1, 0,18,12,-1, 21,6,7,-1, 9,8,6,-1, 5,8,9,-1, 10,13,12,-1, 
+          15,17,14,-1, 15,14,16,-1, 20,18,19,-1, 5,11,8,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/armar/platform/hd_platform_roll_link_conv.wrl b/data/RobotAPI/robots/Armar3/convexModel/armar/platform/hd_platform_roll_link_conv.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..6b06bfe24dcaf758b854f5beb94a02e85eed981b
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/armar/platform/hd_platform_roll_link_conv.wrl
@@ -0,0 +1,52 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            -28.5657 -70.0012 151.032, 82.8521 17.9372 152.434, 125.252 -19.1394 108.493, -119.204 -69.9736 -0.543015, 
+            121.5 -23 8, 121.5 23 8, 115.677 -69.9805 -0.545597, 125.536 14.5245 109.334, 
+            114.516 131 9.993, -29.9578 131 149.772, -118.526 131 9.97051, 35.119 131 137.7, 
+            114.504 130.476 0.00131207, -116.09 -68.958 35.923, -25.9333 99.0299 187.58, 6.61964 93.7347 193.042, 
+            -26.0201 70.7897 187.421, 29.8172 -70.0121 147.027, 115.999 -69.0017 35.9977
+          ]
+        }
+        coordIndex
+        [
+          5,6,12,-1, 10,14,9,-1, 8,11,7,-1, 8,7,12,-1, 5,12,7,-1, 13,14,10,-1, 
+          11,15,7,-1, 13,0,16,-1, 3,0,13,-1, 1,15,17,-1, 15,1,7,-1, 2,17,18,-1, 
+          4,2,6,-1, 1,17,2,-1, 4,6,5,-1, 3,12,6,-1, 11,8,9,-1, 11,9,15,-1, 
+          10,9,8,-1, 10,12,3,-1, 8,12,10,-1, 9,14,15,-1, 3,13,10,-1, 13,16,14,-1, 
+          0,15,16,-1, 16,15,14,-1, 6,17,3,-1, 18,17,6,-1, 17,0,3,-1, 17,15,0,-1, 
+          2,7,1,-1, 6,2,18,-1, 5,2,4,-1, 7,2,5,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/armar/platform/platform_conv.wrl b/data/RobotAPI/robots/Armar3/convexModel/armar/platform/platform_conv.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..a7e2c8277a38044170cc35272d89312e703ca8d6
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/armar/platform/platform_conv.wrl
@@ -0,0 +1,54 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            -777 240 -230, -0.0126703 -328.559 -74.4552, -0.487683 288.02 174.364, -0.858991 340.565 14.0357, 
+            -39.6401 -336.459 13.5245, -0.0651482 -307.973 130.228, -777 -240 -230, -140.493 -164.987 270.16, 
+            -0.0412097 -252.945 217.779, -140.494 164.987 270.16, -777 -240 90, -777 240 90, 
+            -935.448 179.27 -150.677, -39.0193 -0.000132069 -348.998, -953.892 -171.373 -180.87, -64.3448 3.31362e-005 333.358, 
+            -0.0140236 124.401 -320.08, -5.51903 279.346 -189.55, -1.52054 326.952 -79.5664, -0.0566339 -279.605 -189.275, 
+            -0.337348 -122.693 -320.957, 0.00043473 43.6081 328.366
+          ]
+        }
+        coordIndex
+        [
+          6,1,4,-1, 0,14,12,-1, 3,0,11,-1, 9,15,21,-1, 15,9,11,-1, 9,2,11,-1, 
+          0,16,13,-1, 6,19,1,-1, 18,17,0,-1, 11,2,3,-1, 0,3,18,-1, 21,7,8,-1, 
+          21,15,7,-1, 7,15,10,-1, 4,5,10,-1, 10,5,8,-1, 4,1,5,-1, 10,6,4,-1, 
+          8,7,10,-1, 9,21,2,-1, 13,20,6,-1, 19,6,20,-1, 0,17,16,-1, 10,12,14,-1, 
+          11,12,10,-1, 0,12,11,-1, 0,13,6,-1, 16,20,13,-1, 10,14,6,-1, 0,6,14,-1, 
+          10,15,11,-1, 21,8,16,-1, 5,1,16,-1, 2,16,3,-1, 18,16,17,-1, 20,16,19,-1, 
+          1,19,16,-1, 3,16,18,-1, 8,5,16,-1, 21,16,2,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/armar/right_arm/elbow_link_r_conv.wrl b/data/RobotAPI/robots/Armar3/convexModel/armar/right_arm/elbow_link_r_conv.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..6752ae63930cb5c32d64e8a88beb61bcb503601e
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/armar/right_arm/elbow_link_r_conv.wrl
@@ -0,0 +1,52 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            -36.1261 24.3894 -12.0869, -36.3318 8.25542 -27.0525, -36.4752 -13.3378 -23.8698, -27.5 -11.3909 46.5, 
+            -36.5181 10.9736 25.2441, 36.5021 13.7969 25.4252, 33.1924 28.9249 18.88, 36.5 -28.5 25.5, 
+            28.7562 0.6096 47.793, -36.6253 -28.9511 24.7118, 36.5 -28.5 17, -36.3423 28.6794 17.5351, 
+            -11.3909 -27.5 46.5, 11.3909 -27.5 46.5, -36.4983 -24.4048 -12.3621, 36.5056 -8.14029 -11.5467, 
+            38.0272 8.00417 -11.4865, 11.3909 27.5 46.5, -23.5026 21.9188 45.87
+          ]
+        }
+        coordIndex
+        [
+          6,16,0,-1, 5,6,8,-1, 11,6,0,-1, 16,6,5,-1, 13,7,8,-1, 9,7,13,-1, 
+          11,4,18,-1, 12,3,9,-1, 15,14,2,-1, 10,14,15,-1, 16,1,0,-1, 1,16,15,-1, 
+          1,15,2,-1, 6,17,8,-1, 9,3,4,-1, 4,3,18,-1, 7,5,8,-1, 9,10,7,-1, 
+          9,13,12,-1, 9,14,10,-1, 9,11,14,-1, 1,11,0,-1, 4,11,9,-1, 2,14,11,-1, 
+          2,11,1,-1, 7,15,5,-1, 5,15,16,-1, 7,10,15,-1, 12,17,3,-1, 8,17,13,-1, 
+          3,17,18,-1, 12,13,17,-1, 11,17,6,-1, 18,17,11,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/armar/right_arm/shoulder_link_r_conv.wrl b/data/RobotAPI/robots/Armar3/convexModel/armar/right_arm/shoulder_link_r_conv.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..b3c250cccfbb7b4cf2d58a512204e51c62f95c4b
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/armar/right_arm/shoulder_link_r_conv.wrl
@@ -0,0 +1,50 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            -40 -75 28, -40 -75 -28, -41.2092 -35.8693 -0.0604578, 30 -75 -28, 
+            60.2028 -33.8464 51.3286, 28.6668 -74.8949 27.4417, -30 -38 51, -30 -7.10543e-015 -50, 
+            -30 -38 -50, -12.0604 29.1464 -50.0056, 53.8218 -8.20554 50.957, 30 -38 -50, 
+            26.1435 16.6228 -51.1362, -23.6661 19.1514 51.2152, 6.98505 30.6394 50.9781
+          ]
+        }
+        coordIndex
+        [
+          12,10,4,-1, 11,4,3,-1, 13,9,7,-1, 14,12,9,-1, 10,12,14,-1, 2,1,0,-1, 
+          4,5,3,-1, 5,0,1,-1, 1,3,5,-1, 4,6,5,-1, 5,6,0,-1, 2,7,1,-1, 
+          7,8,1,-1, 14,9,13,-1, 11,3,1,-1, 1,8,11,-1, 12,4,11,-1, 11,7,9,-1, 
+          8,7,11,-1, 9,12,11,-1, 13,7,2,-1, 13,2,0,-1, 13,0,6,-1, 13,10,14,-1, 
+          13,6,4,-1, 10,13,4,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/armar/right_arm/shoulder_r_conv.wrl b/data/RobotAPI/robots/Armar3/convexModel/armar/right_arm/shoulder_r_conv.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..e32da6746e1d394f3b37e9cadc7fc755eb4db090
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/armar/right_arm/shoulder_r_conv.wrl
@@ -0,0 +1,51 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            88 62 3, -87 62 59.294, 87.9537 61.9929 67.9317, -87 62 3, 
+            88 31.2997 125.511, -87 31.2997 125.511, 88.1559 -27.9565 131.518, 88 15.2919 141.925, 
+            88 -7.47399 144.68, 59 60.5 5.68434e-014, -58 60.5 1.42109e-014, -87 15.2919 141.925, 
+            -87.0092 -15.8752 144.142, 76.1733 -82.5002 72.9996, -86.9118 -82.3856 0.156916, 87.9233 -82.4557 0.403558, 
+            -86.1444 -82.468 72.9742
+          ]
+        }
+        coordIndex
+        [
+          5,2,1,-1, 9,0,15,-1, 10,14,3,-1, 13,15,6,-1, 1,2,0,-1, 1,0,3,-1, 
+          4,2,5,-1, 4,15,2,-1, 7,15,4,-1, 0,2,15,-1, 7,8,15,-1, 6,15,8,-1, 
+          0,10,3,-1, 9,10,0,-1, 4,11,7,-1, 4,5,11,-1, 7,11,8,-1, 11,12,8,-1, 
+          16,13,12,-1, 6,12,13,-1, 16,15,13,-1, 14,15,16,-1, 6,8,12,-1, 1,14,5,-1, 
+          1,3,14,-1, 11,14,12,-1, 11,5,14,-1, 12,14,16,-1, 15,14,9,-1, 10,9,14,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/armar/right_arm/underarm_r_conv.wrl b/data/RobotAPI/robots/Armar3/convexModel/armar/right_arm/underarm_r_conv.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..378274e4e1699c914cf7b2d2faf93ff5d71c6a9e
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/armar/right_arm/underarm_r_conv.wrl
@@ -0,0 +1,55 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            1.5 48.5 -20, 34.7337 34.7337 -166, 34.7337 34.7337 -20, 1.5 48.5 -166, 
+            -31.7337 34.7337 -166, -31.7337 34.7337 -20, 48.5 1.5 -20, 48.5 1.5 -166, 
+            -45.5 1.5 -20, -45.5 1.5 -166, -31.7337 -31.7337 -166, -31.7337 -31.7337 -20, 
+            1.5 -45.5 -20, 1.5 -45.5 -166, -22.5 -8.30662 -203.5, 22.5 -8.30662 -203.5, 
+            22.5 8.30662 -203.5, -22.5 8.30662 -203.5, -22.5 22.5 0, 22.5 22.5 0, 
+            22.5 -22.5 0, -22.5 -22.5 0, 34.7337 -31.7337 -20, 34.7337 -31.7337 -166
+          ]
+        }
+        coordIndex
+        [
+          16,1,7,-1, 1,16,3,-1, 16,17,3,-1, 7,15,16,-1, 4,17,9,-1, 17,4,3,-1, 
+          11,21,8,-1, 12,20,21,-1, 11,12,21,-1, 15,13,14,-1, 10,14,13,-1, 10,9,14,-1, 
+          17,14,9,-1, 0,19,2,-1, 6,2,19,-1, 6,19,20,-1, 15,7,23,-1, 15,23,13,-1, 
+          0,5,18,-1, 19,0,18,-1, 8,18,5,-1, 8,21,18,-1, 12,22,20,-1, 22,6,20,-1, 
+          1,0,2,-1, 0,1,3,-1, 4,0,3,-1, 4,5,0,-1, 6,1,2,-1, 1,6,7,-1, 
+          4,8,5,-1, 4,9,8,-1, 10,8,9,-1, 8,10,11,-1, 10,12,11,-1, 10,13,12,-1, 
+          15,14,16,-1, 16,14,17,-1, 19,18,20,-1, 20,18,21,-1, 12,13,22,-1, 23,22,13,-1, 
+          6,22,7,-1, 23,7,22,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/armar/right_arm/upperarm_r_conv.wrl b/data/RobotAPI/robots/Armar3/convexModel/armar/right_arm/upperarm_r_conv.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..f6d6a045574ddf7de0657324ea494d2fda0c9bc0
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/armar/right_arm/upperarm_r_conv.wrl
@@ -0,0 +1,52 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            -69.5811 4.1645 42.0062, -136.301 -0.122217 41.58, -287.315 39.4499 -5.49195, -70.4671 33.9073 22.678, 
+            -68.7048 40.2269 -6.6456, -69.976 -9.56657 -40.4846, -67.0037 22.4011 -33.5214, -231.148 -20.6333 -34.8982, 
+            -233.137 10.0146 -38.7801, -68.445 -38.5915 -12.8467, -226.195 -41.2657 -3.0627, -71.5466 -33.2925 23.9268, 
+            -268.046 37.8458 -22.2792, -283.642 -22.6839 -14.1032, -293.773 37.7302 29.4315, -295.114 -22.3276 29.1564, 
+            0.703255 -4.34722 -15.3938, 8.87691 14.4855 1.40159e-007, 9.12451 -11.4672 9.31807
+          ]
+        }
+        coordIndex
+        [
+          15,11,1,-1, 14,1,0,-1, 3,14,0,-1, 17,3,0,-1, 18,0,11,-1, 11,0,1,-1, 
+          15,1,14,-1, 10,9,11,-1, 18,11,9,-1, 6,12,4,-1, 13,12,8,-1, 13,8,7,-1, 
+          18,17,0,-1, 9,10,7,-1, 13,7,10,-1, 4,17,6,-1, 13,10,15,-1, 12,6,8,-1, 
+          16,18,9,-1, 6,17,16,-1, 12,2,4,-1, 14,4,2,-1, 3,4,14,-1, 4,3,17,-1, 
+          9,7,5,-1, 16,9,5,-1, 5,6,16,-1, 7,8,5,-1, 6,5,8,-1, 11,15,10,-1, 
+          2,12,13,-1, 15,14,2,-1, 2,13,15,-1, 18,16,17,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/armar/torso/torso_conv.wrl b/data/RobotAPI/robots/Armar3/convexModel/armar/torso/torso_conv.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..96e14bf231fa6d1d67205105a661f07abdc42b43
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/armar/torso/torso_conv.wrl
@@ -0,0 +1,54 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            -164.034 117.722 126.042, -131.908 176.891 131.017, 58.0618 176.983 131.043, 82.9937 142.354 130.966, 
+            -164.047 -117.298 126.052, -130.868 178.881 365.246, 75.0294 -180.711 358.224, -141.502 -115.748 564.57, 
+            -139.686 115.232 566.337, 19.5619 -1.83073e-006 28.9166, -0.697823 -0.000447581 21.411, -19.5895 -0.429302 632.047, 
+            -129.465 -180.726 358.938, 82.4193 -146.794 129.937, 75.026 180.654 358.77, -135.774 -176.897 131.261, 
+            51.5555 -176.989 131.012, -199.067 91.1645 233.034, 49.2065 -115.05 566.889, 49.2848 115.078 566.785, 
+            95.7263 114.994 446.348, 95.7279 -114.992 446.344
+          ]
+        }
+        coordIndex
+        [
+          0,4,17,-1, 10,1,2,-1, 3,14,20,-1, 17,1,0,-1, 0,1,10,-1, 0,10,4,-1, 
+          2,9,10,-1, 9,13,16,-1, 9,16,10,-1, 7,18,11,-1, 14,19,20,-1, 1,17,5,-1, 
+          4,10,15,-1, 2,3,9,-1, 13,3,21,-1, 7,4,12,-1, 15,12,4,-1, 18,7,12,-1, 
+          5,8,14,-1, 21,6,13,-1, 20,19,21,-1, 6,21,18,-1, 2,14,3,-1, 16,15,10,-1, 
+          7,17,4,-1, 5,17,8,-1, 17,7,8,-1, 8,19,14,-1, 12,6,18,-1, 16,6,12,-1, 
+          6,16,13,-1, 7,11,8,-1, 21,3,20,-1, 19,11,18,-1, 5,2,1,-1, 9,3,13,-1, 
+          5,14,2,-1, 12,15,16,-1, 8,11,19,-1, 18,21,19,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/elbow_l.iv b/data/RobotAPI/robots/Armar3/convexModel/elbow_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..2d68b771fbd78a6bec6c984494feb0314cba5676
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/elbow_l.iv
@@ -0,0 +1,29 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units {
+            units MILLIMETERS
+    }
+    Transform {
+        rotation 1 0 0 -1.57
+    }
+	Transform {
+		rotation 0 0 1 -1.57
+	} 
+	Transform {
+		rotation 0 1 0 3.14
+	} 
+        ## Kinematics 5.0 <-> armar model: 7.5
+	## Model of elbow is fixed to upperarm -> use offset, so transformations of kinematics have no effect
+#	Transform {
+#		translation 7.5 0 0 
+#		rotation 1 0 0 -0.07616814813524509
+#	} 
+	Transform {
+		translation 7.5 0 0
+		rotation 0 0 0 0 
+	} 
+    File { 
+    	name "armar/left_arm/elbow_link_l_conv.wrl"
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/elbow_r.iv b/data/RobotAPI/robots/Armar3/convexModel/elbow_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..2e6b0049e1e6ad3aab94517d30e24ba6e66011f6
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/elbow_r.iv
@@ -0,0 +1,20 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units {
+            units MILLIMETERS
+    }
+
+    Transform {
+        rotation 1 0 0 1.57
+    }
+    Transform {
+    	rotation 0 0 1 1.57
+    } 
+    Transform {
+    	translation 7.5 0 0
+    } 
+	File { 
+  		name "armar/right_arm/elbow_link_r_conv.wrl"
+	}
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/eye_l.iv b/data/RobotAPI/robots/Armar3/convexModel/eye_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..5df57b2eae4774b2ab640eae55cd307d579aabc0
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/eye_l.iv
@@ -0,0 +1,16 @@
+#Inventor V2.1 ascii
+
+Separator {
+
+	Transform {
+		rotation 0 1 0 1.57
+	}
+
+	Transform {
+		rotation 0 0 1 1.57
+	}
+
+	File { 
+	  name "armar/eyes/eye.iv"
+	}
+} 
diff --git a/data/RobotAPI/robots/Armar3/convexModel/eye_link_l.iv b/data/RobotAPI/robots/Armar3/convexModel/eye_link_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..8ec3c25ef28e6090eac76046700d629af1dce75e
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/eye_link_l.iv
@@ -0,0 +1,16 @@
+#Inventor V2.1 ascii
+
+Separator { 
+
+	Transform {
+		rotation 0 1 0 1.57
+	}
+
+	Transform {
+		rotation 1 0 0 1.57
+	}
+
+	File { 
+		name "armar/eyes/eyes_pitch_link_left.iv"
+	}
+} 
diff --git a/data/RobotAPI/robots/Armar3/convexModel/eye_link_r.iv b/data/RobotAPI/robots/Armar3/convexModel/eye_link_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..5aef77b4bd7fc28d302e638b4fa0d368fc2d805f
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/eye_link_r.iv
@@ -0,0 +1,16 @@
+#Inventor V2.1 ascii
+
+Separator {
+
+	Transform {
+		rotation 0 1 0 1.57
+	}
+
+	Transform {
+		rotation 1 0 0 1.57
+	}
+
+	File { 
+	  name "armar/eyes/eyes_pitch_link_right.iv"
+	}
+} 
diff --git a/data/RobotAPI/robots/Armar3/convexModel/eye_r.iv b/data/RobotAPI/robots/Armar3/convexModel/eye_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..5df57b2eae4774b2ab640eae55cd307d579aabc0
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/eye_r.iv
@@ -0,0 +1,16 @@
+#Inventor V2.1 ascii
+
+Separator {
+
+	Transform {
+		rotation 0 1 0 1.57
+	}
+
+	Transform {
+		rotation 0 0 1 1.57
+	}
+
+	File { 
+	  name "armar/eyes/eye.iv"
+	}
+} 
diff --git a/data/RobotAPI/robots/Armar3/convexModel/head.iv b/data/RobotAPI/robots/Armar3/convexModel/head.iv
new file mode 100644
index 0000000000000000000000000000000000000000..07390197af06a995310ba09d8937ad798f0248d9
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/head.iv
@@ -0,0 +1,15 @@
+#Inventor V2.1 ascii
+
+Separator { 
+    SoUnits
+    { 
+        units MILLIMETERS
+    }
+	Transform {
+		rotation 0 1 0 1.57
+	}
+
+	File { 
+		name "armar/head/head_conv.wrl"
+	}
+} 
diff --git a/data/RobotAPI/robots/Armar3/convexModel/head_base.iv b/data/RobotAPI/robots/Armar3/convexModel/head_base.iv
new file mode 100644
index 0000000000000000000000000000000000000000..1ede136dbed2cb493f0849fb8a79e7276985c438
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/head_base.iv
@@ -0,0 +1,19 @@
+#Inventor V2.1 ascii
+
+Separator {
+    SoUnits
+    { 
+        units MILLIMETERS
+    }
+    Transform {
+		translation -35 0 -605
+	}
+    RotationXYZ{
+      axis Z
+      angle 3.14
+    }
+    
+    File { 
+      name "armar/head/head_base_conv.wrl"
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/index_l1.iv b/data/RobotAPI/robots/Armar3/convexModel/index_l1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..352ffff1a31f3e4bd693c2c37e3cc5ed35a0ac8c
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/index_l1.iv
@@ -0,0 +1,21 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units
+    {
+        units MILLIMETERS
+    }
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	}
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+	}
+
+	Separator 
+	{
+		File {name armar/hands/metacarpals_conv.wrl }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/convexModel/index_l2.iv b/data/RobotAPI/robots/Armar3/convexModel/index_l2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..96e986f4e213d85877a7e39d9ed936e1f5e06baa
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/index_l2.iv
@@ -0,0 +1,21 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units
+    {
+        units MILLIMETERS
+    }
+
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	} 
+	Separator 
+	{
+		File {name armar/hands/proximal_index_middle_thumb_conv.wrl }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/convexModel/index_r1.iv b/data/RobotAPI/robots/Armar3/convexModel/index_r1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..352ffff1a31f3e4bd693c2c37e3cc5ed35a0ac8c
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/index_r1.iv
@@ -0,0 +1,21 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units
+    {
+        units MILLIMETERS
+    }
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	}
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+	}
+
+	Separator 
+	{
+		File {name armar/hands/metacarpals_conv.wrl }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/convexModel/index_r2.iv b/data/RobotAPI/robots/Armar3/convexModel/index_r2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..f995cb3671a86b478c209081870c6c44e3098868
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/index_r2.iv
@@ -0,0 +1,22 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units
+    {
+        units MILLIMETERS
+    }
+
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	} 
+
+	Separator 
+	{
+		File {name armar/hands/proximal_index_middle_thumb_conv.wrl }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/convexModel/jaw.iv b/data/RobotAPI/robots/Armar3/convexModel/jaw.iv
new file mode 100644
index 0000000000000000000000000000000000000000..a6cd0a5319271bf01eb7f327b1ac5ab7ff3751e0
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/jaw.iv
@@ -0,0 +1,20 @@
+#Inventor V2.1 ascii
+
+Separator { 
+
+    Units {
+            units MILLIMETERS
+    }
+	Transform {
+		translation 0 10 0 
+		rotation 0 0 1 1.57
+	}
+
+	Transform {
+		rotation 0 1 0 -1.57
+	}
+
+	File { 
+		name "armar/head/jaw.iv"
+	}
+} 
diff --git a/data/RobotAPI/robots/Armar3/convexModel/lid_l_bottom.iv b/data/RobotAPI/robots/Armar3/convexModel/lid_l_bottom.iv
new file mode 100644
index 0000000000000000000000000000000000000000..fee6dbbbc050aba14dccd2977e038c56c95f1e6a
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/lid_l_bottom.iv
@@ -0,0 +1,11 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Transform {
+		translation 0 0 0
+		rotation 0 1 0 -0.87
+	} 
+	File { 
+		name "armar/eyes/lid.iv"
+	}
+} 
diff --git a/data/RobotAPI/robots/Armar3/convexModel/lid_l_top.iv b/data/RobotAPI/robots/Armar3/convexModel/lid_l_top.iv
new file mode 100644
index 0000000000000000000000000000000000000000..b3cbbaed2c7dfbb0e4787964dd903c830fed993a
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/lid_l_top.iv
@@ -0,0 +1,11 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Transform {
+		translation 0 0 0
+		rotation 0 1 0 -2.44
+	} 
+	File { 
+		name "armar/eyes/lid.iv"
+	}
+} 
diff --git a/data/RobotAPI/robots/Armar3/convexModel/lid_r_bottom.iv b/data/RobotAPI/robots/Armar3/convexModel/lid_r_bottom.iv
new file mode 100644
index 0000000000000000000000000000000000000000..fee6dbbbc050aba14dccd2977e038c56c95f1e6a
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/lid_r_bottom.iv
@@ -0,0 +1,11 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Transform {
+		translation 0 0 0
+		rotation 0 1 0 -0.87
+	} 
+	File { 
+		name "armar/eyes/lid.iv"
+	}
+} 
diff --git a/data/RobotAPI/robots/Armar3/convexModel/lid_r_top.iv b/data/RobotAPI/robots/Armar3/convexModel/lid_r_top.iv
new file mode 100644
index 0000000000000000000000000000000000000000..9e55171a4ab2695f4a37127c60f9b6f5f80769e1
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/lid_r_top.iv
@@ -0,0 +1,12 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Transform {
+		translation 0 0 0
+		rotation 0 1 0 -2.44
+	} 
+
+	File { 
+		name "armar/eyes/lid.iv"
+	}
+} 
diff --git a/data/RobotAPI/robots/Armar3/convexModel/middle_l1.iv b/data/RobotAPI/robots/Armar3/convexModel/middle_l1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..352ffff1a31f3e4bd693c2c37e3cc5ed35a0ac8c
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/middle_l1.iv
@@ -0,0 +1,21 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units
+    {
+        units MILLIMETERS
+    }
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	}
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+	}
+
+	Separator 
+	{
+		File {name armar/hands/metacarpals_conv.wrl }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/convexModel/middle_l2.iv b/data/RobotAPI/robots/Armar3/convexModel/middle_l2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..f995cb3671a86b478c209081870c6c44e3098868
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/middle_l2.iv
@@ -0,0 +1,22 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units
+    {
+        units MILLIMETERS
+    }
+
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	} 
+
+	Separator 
+	{
+		File {name armar/hands/proximal_index_middle_thumb_conv.wrl }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/convexModel/middle_r1.iv b/data/RobotAPI/robots/Armar3/convexModel/middle_r1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..352ffff1a31f3e4bd693c2c37e3cc5ed35a0ac8c
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/middle_r1.iv
@@ -0,0 +1,21 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units
+    {
+        units MILLIMETERS
+    }
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	}
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+	}
+
+	Separator 
+	{
+		File {name armar/hands/metacarpals_conv.wrl }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/convexModel/middle_r2.iv b/data/RobotAPI/robots/Armar3/convexModel/middle_r2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..96e986f4e213d85877a7e39d9ed936e1f5e06baa
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/middle_r2.iv
@@ -0,0 +1,21 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units
+    {
+        units MILLIMETERS
+    }
+
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	} 
+	Separator 
+	{
+		File {name armar/hands/proximal_index_middle_thumb_conv.wrl }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/convexModel/neck_pitch_link.iv b/data/RobotAPI/robots/Armar3/convexModel/neck_pitch_link.iv
new file mode 100644
index 0000000000000000000000000000000000000000..33f287d365f57dac603b1d8a21f46e7283fb95d1
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/neck_pitch_link.iv
@@ -0,0 +1,18 @@
+#Inventor V2.1 ascii
+
+Separator { 
+    SoUnits
+    { 
+        units MILLIMETERS
+    }
+	Transform {
+		rotation 0 0 1 -1.57
+	}
+	Transform {
+		rotation 1 0 0 -1.57
+	}
+
+	File { 
+	  name "armar/neck/neck_pitch_link_conv.wrl"
+	}
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/neck_roll_link.iv b/data/RobotAPI/robots/Armar3/convexModel/neck_roll_link.iv
new file mode 100644
index 0000000000000000000000000000000000000000..70273a63fd70fdb3eaff16128c06c4ce5175e819
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/neck_roll_link.iv
@@ -0,0 +1,18 @@
+#Inventor V2.1 ascii
+
+Separator { 
+    SoUnits
+    { 
+        units MILLIMETERS
+    }
+	Transform {
+		rotation 0 0 1 -1.57
+	}
+	Transform {
+		rotation 0 1 0 -1.57
+	}
+
+	File { 
+		name "armar/neck/neck_yaw_link_conv.wrl"
+	}
+} 
diff --git a/data/RobotAPI/robots/Armar3/convexModel/neck_yaw_link.iv b/data/RobotAPI/robots/Armar3/convexModel/neck_yaw_link.iv
new file mode 100644
index 0000000000000000000000000000000000000000..14a17799444a4ef176896ba7a59c521ef4d03761
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/neck_yaw_link.iv
@@ -0,0 +1,18 @@
+#Inventor V2.1 ascii
+
+Separator { 
+    SoUnits
+    { 
+        units MILLIMETERS
+    }
+	Transform {
+		rotation 0 1 0 3.14
+	}
+	Transform {
+		rotation 0 0 1 1.57
+	}
+
+	File { 
+		name "armar/neck/neck_roll_link_conv.wrl"
+	}
+} 
diff --git a/data/RobotAPI/robots/Armar3/convexModel/palm1_l.iv b/data/RobotAPI/robots/Armar3/convexModel/palm1_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..36e9492f7f31734fe16317267fc4022e3f840bca
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/palm1_l.iv
@@ -0,0 +1,18 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units
+    {
+        units MILLIMETERS
+    }
+
+	Transform {
+		translation 0 0 0
+		rotation 0 0 -1 1.57
+	} 
+
+	Separator 
+	{
+		File {name armar/hands/palm1_l_conv.wrl }
+	}
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/palm1_r.iv b/data/RobotAPI/robots/Armar3/convexModel/palm1_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..20031ad9809be180a9a484f56718f808a7311d17
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/palm1_r.iv
@@ -0,0 +1,22 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units
+    {
+        units MILLIMETERS
+    }
+
+	Transform {
+		translation 0 0 0
+		rotation 0 0 -1 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 3.1415
+	} 
+
+	Separator 
+	{
+		File {name armar/hands/palm1_r_conv.wrl }
+	}
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/palm2_l.iv b/data/RobotAPI/robots/Armar3/convexModel/palm2_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..31551d6dbf0bc4f11030f848fa67b062547cdd88
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/palm2_l.iv
@@ -0,0 +1,21 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units
+    {
+        units MILLIMETERS
+    }
+
+	Transform {
+		translation 0 0 0
+		rotation 0 0 -1 1.57
+	} 
+	Transform {
+		rotation 0 1 0 1.57
+	} 
+
+	Separator 
+	{
+		File {name armar/hands/palm2_l_conv.wrl }
+	}
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/palm2_r.iv b/data/RobotAPI/robots/Armar3/convexModel/palm2_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..b4a79254881565bf7e0858881e45fb241997ce48
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/palm2_r.iv
@@ -0,0 +1,21 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units
+    {
+        units MILLIMETERS
+    }
+
+	Transform {
+		translation 0 0 0
+		rotation 0 0 -1 1.57
+	} 
+	Transform {
+		rotation 0 1 0 -1.57
+	} 
+
+	Separator 
+	{
+		File {name armar/hands/palm2_r_conv.wrl }
+	}
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/pinky_l1.iv b/data/RobotAPI/robots/Armar3/convexModel/pinky_l1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..352ffff1a31f3e4bd693c2c37e3cc5ed35a0ac8c
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/pinky_l1.iv
@@ -0,0 +1,21 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units
+    {
+        units MILLIMETERS
+    }
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	}
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+	}
+
+	Separator 
+	{
+		File {name armar/hands/metacarpals_conv.wrl }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/convexModel/pinky_l2.iv b/data/RobotAPI/robots/Armar3/convexModel/pinky_l2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..3a674b7a167508772926fbd34da99d4083c6b500
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/pinky_l2.iv
@@ -0,0 +1,21 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units
+    {
+        units MILLIMETERS
+    }
+
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	} 
+	Separator 
+	{
+		File {name armar/hands/proximal_pinky_conv.wrl }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/convexModel/pinky_r1.iv b/data/RobotAPI/robots/Armar3/convexModel/pinky_r1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..352ffff1a31f3e4bd693c2c37e3cc5ed35a0ac8c
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/pinky_r1.iv
@@ -0,0 +1,21 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units
+    {
+        units MILLIMETERS
+    }
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	}
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+	}
+
+	Separator 
+	{
+		File {name armar/hands/metacarpals_conv.wrl }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/convexModel/pinky_r2.iv b/data/RobotAPI/robots/Armar3/convexModel/pinky_r2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..3a674b7a167508772926fbd34da99d4083c6b500
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/pinky_r2.iv
@@ -0,0 +1,21 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units
+    {
+        units MILLIMETERS
+    }
+
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	} 
+	Separator 
+	{
+		File {name armar/hands/proximal_pinky_conv.wrl }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/convexModel/platform.iv b/data/RobotAPI/robots/Armar3/convexModel/platform.iv
new file mode 100644
index 0000000000000000000000000000000000000000..ba90592389b6fc3ee31c4d0549fe1b47439f3606
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/platform.iv
@@ -0,0 +1,19 @@
+#Inventor V2.1 ascii
+
+Separator { #Model
+    Units
+    {
+        units MILLIMETERS
+    }
+ RotationXYZ {
+   axis X
+   angle 1.57
+   }
+ RotationXYZ{
+ 	axis Z
+	angle -1.57
+ }
+ File { 
+  name "armar/platform/platform_conv.wrl"
+ }
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/platform_pitch_link.iv b/data/RobotAPI/robots/Armar3/convexModel/platform_pitch_link.iv
new file mode 100644
index 0000000000000000000000000000000000000000..82c5044d7964ae2de6d16fe00571860455bf6e7a
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/platform_pitch_link.iv
@@ -0,0 +1,14 @@
+#Inventor V2.1 ascii
+
+Separator { #Model
+    Units {
+        units MILLIMETERS
+    }
+    RotationXYZ{
+        axis Z
+        angle 1.57
+    }
+    File { 
+        name "armar/platform/hd_platform_pitch_link_conv.wrl"
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/platform_roll_link.iv b/data/RobotAPI/robots/Armar3/convexModel/platform_roll_link.iv
new file mode 100644
index 0000000000000000000000000000000000000000..e5ffeff568f5d320a2f8dba4259d25b21deb549a
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/platform_roll_link.iv
@@ -0,0 +1,23 @@
+#Inventor V2.1 ascii
+
+Separator { #Model
+    Units {
+        units MILLIMETERS
+    }
+    RotationXYZ{
+        axis Z
+        angle 1.57
+    }
+    Transform{
+        translation	0 0 127
+    }
+    Transform {
+        rotation 0 1 0 3.1415
+    }
+    Transform {
+        rotation 0 0 1 -1.57
+    }
+    File { 
+        name "armar/platform/hd_platform_roll_link_conv.wrl"
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/ring_l1.iv b/data/RobotAPI/robots/Armar3/convexModel/ring_l1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..352ffff1a31f3e4bd693c2c37e3cc5ed35a0ac8c
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/ring_l1.iv
@@ -0,0 +1,21 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units
+    {
+        units MILLIMETERS
+    }
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	}
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+	}
+
+	Separator 
+	{
+		File {name armar/hands/metacarpals_conv.wrl }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/convexModel/ring_l2.iv b/data/RobotAPI/robots/Armar3/convexModel/ring_l2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..c6fb4cd4a09e9b4d4f421c52279f440081852958
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/ring_l2.iv
@@ -0,0 +1,21 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units
+    {
+        units MILLIMETERS
+    }
+
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	} 
+	Separator 
+	{
+		File {name armar/hands/proximal_ring_conv.wrl }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/convexModel/ring_r1.iv b/data/RobotAPI/robots/Armar3/convexModel/ring_r1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..352ffff1a31f3e4bd693c2c37e3cc5ed35a0ac8c
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/ring_r1.iv
@@ -0,0 +1,21 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units
+    {
+        units MILLIMETERS
+    }
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	}
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+	}
+
+	Separator 
+	{
+		File {name armar/hands/metacarpals_conv.wrl }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/convexModel/ring_r2.iv b/data/RobotAPI/robots/Armar3/convexModel/ring_r2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..540d2b94eaf5c508207e92cbd102fa10f3d39e3c
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/ring_r2.iv
@@ -0,0 +1,23 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units
+    {
+        units MILLIMETERS
+    }
+
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	} 
+
+
+	Separator 
+	{
+		File {name armar/hands/proximal_ring_conv.wrl }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/convexModel/shoulder2_l_rot.iv b/data/RobotAPI/robots/Armar3/convexModel/shoulder2_l_rot.iv
new file mode 100644
index 0000000000000000000000000000000000000000..87e1f6394ecd1458d453a9e47a4b850c7b1e0ba1
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/shoulder2_l_rot.iv
@@ -0,0 +1,15 @@
+#Inventor V2.1 ascii
+Separator {
+    Units {
+        units MILLIMETERS
+    }
+    Transform {
+        rotation 0 0 1  1.57
+    }
+    Transform {
+        rotation 0 0 1 1.57  
+    }
+    File { 
+    	name "armar/left_arm/shoulder_link_l_conv.wrl"
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/shoulder2_r_rot.iv b/data/RobotAPI/robots/Armar3/convexModel/shoulder2_r_rot.iv
new file mode 100644
index 0000000000000000000000000000000000000000..2bc4f69ea02a8b1f9610c5ea9c00ee840782f623
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/shoulder2_r_rot.iv
@@ -0,0 +1,23 @@
+#Inventor V2.1 ascii
+Separator {
+    Units {
+            units MILLIMETERS
+    }
+
+  Transform {
+	translation 0 0 0
+	rotation 0 0 1  -1.57
+  }
+  Transform {
+	translation 0 0 0
+	rotation 0 1 0 3.14
+}
+  Transform {
+	translation 0 0 0
+	rotation 0 0 1  1.57
+  }
+    	File { 
+      		name "armar/right_arm/shoulder_link_r_conv.wrl"
+    	}
+
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/shoulder_l.iv b/data/RobotAPI/robots/Armar3/convexModel/shoulder_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..a4955ba26b21c6b17db8c8a2decc6109a5db44fe
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/shoulder_l.iv
@@ -0,0 +1,20 @@
+#Inventor V2.1 ascii
+Separator {
+
+    Units {
+        units MILLIMETERS
+    }
+    Transform {
+        rotation 0 0 1 -1.57
+    }
+    
+    Transform {
+        translation 0 0 -110
+    }
+    Transform {
+        rotation 0 1 0 -1.57
+    } 
+    File { 
+        name "armar/left_arm/shoulder_l_conv.wrl"
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/shoulder_r.iv b/data/RobotAPI/robots/Armar3/convexModel/shoulder_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..cb1a9f6e43151f3a1e11c687ef5670d30c5c6e44
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/shoulder_r.iv
@@ -0,0 +1,19 @@
+#Inventor V2.1 ascii
+Separator {
+    Units {
+            units MILLIMETERS
+    }
+  Transform {
+	rotation 0 0 1 1.57
+  }
+  Transform {
+	rotation 0 1 0 3.14
+  }
+  Transform {
+	translation 0 0 -110
+  }
+ 
+  File { 
+	name "armar/right_arm/shoulder_r_conv.wrl"
+  }
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/thumb_l1.iv b/data/RobotAPI/robots/Armar3/convexModel/thumb_l1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..b6da70857b1181041ae4474a0bc38b34a87059ff
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/thumb_l1.iv
@@ -0,0 +1,16 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units
+    {
+        units MILLIMETERS
+    }
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 -1.57
+	}	
+	Separator 
+	{
+		File {name armar/hands/metacarpals_conv.wrl }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/convexModel/thumb_l2.iv b/data/RobotAPI/robots/Armar3/convexModel/thumb_l2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..a48e14f56f63665c6f3fb48504ee046b9b6be07e
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/thumb_l2.iv
@@ -0,0 +1,17 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units
+    {
+        units MILLIMETERS
+    }
+
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 -1.57
+	} 
+	Separator 
+	{
+		File {name armar/hands/proximal_index_middle_thumb_conv.wrl }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/convexModel/thumb_r1.iv b/data/RobotAPI/robots/Armar3/convexModel/thumb_r1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..b6da70857b1181041ae4474a0bc38b34a87059ff
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/thumb_r1.iv
@@ -0,0 +1,16 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units
+    {
+        units MILLIMETERS
+    }
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 -1.57
+	}	
+	Separator 
+	{
+		File {name armar/hands/metacarpals_conv.wrl }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/convexModel/thumb_r2.iv b/data/RobotAPI/robots/Armar3/convexModel/thumb_r2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..d7cf09e9a425d74fd75f226b85b0832574ba0dcd
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/thumb_r2.iv
@@ -0,0 +1,19 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units
+    {
+        units MILLIMETERS
+    }
+
+ 
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 -1.57
+	} 
+
+	Separator 
+	{
+		File {name armar/hands/proximal_index_middle_thumb_conv.wrl }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/convexModel/torso.iv b/data/RobotAPI/robots/Armar3/convexModel/torso.iv
new file mode 100644
index 0000000000000000000000000000000000000000..61753ec9ad3dc87e8fa803895318ca8fd9bfe7d9
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/torso.iv
@@ -0,0 +1,16 @@
+#Inventor V2.1 ascii
+Separator { #Model
+
+    SoUnits
+    { 
+        units MILLIMETERS
+    }
+    RotationXYZ{
+      axis Z
+      angle 1.57
+    }
+    
+    File { 
+      name "armar/torso/torso_conv.wrl"
+    }
+} #Model
diff --git a/data/RobotAPI/robots/Armar3/convexModel/underarm_l.iv b/data/RobotAPI/robots/Armar3/convexModel/underarm_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..88d451c3402bb81ff1cbd79c8f06c38d22bece53
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/underarm_l.iv
@@ -0,0 +1,22 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units {
+            units MILLIMETERS
+    }
+	Transform {
+		translation 0 0 -46.5
+		rotation 0 0 0 0 
+	}
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 3.14
+	}
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 1.57
+	}
+   	File { 
+      		name "armar/left_arm/underarm_l_conv.wrl"
+    	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/convexModel/underarm_r.iv b/data/RobotAPI/robots/Armar3/convexModel/underarm_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..0ec5a19a13ae6f8a93a368e658a493c5f28a04fe
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/underarm_r.iv
@@ -0,0 +1,19 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units {
+            units MILLIMETERS
+    }
+
+	Transform {
+		translation 0 0 -46.5
+	}
+	
+    Transform {
+		rotation 0 0 1 1.57
+	}
+
+   	File { 
+      		name "armar/right_arm/underarm_r_conv.wrl"
+    	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/convexModel/upperarm_l.iv b/data/RobotAPI/robots/Armar3/convexModel/upperarm_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..99a39648879ea16c414e2faa13aec890f37bb23c
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/upperarm_l.iv
@@ -0,0 +1,16 @@
+#Inventor V2.1 ascii
+Separator {
+    Units {
+        units MILLIMETERS
+    }
+    Transform {
+        translation 0 0 0
+        rotation 0 1 0 -1.57
+    }
+    Transform {
+        translation -25.3 0 0 
+    }
+    File { 
+    	name "armar/left_arm/upperarm_l_conv.wrl"
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/upperarm_r.iv b/data/RobotAPI/robots/Armar3/convexModel/upperarm_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..7496cad8647343e4ba0d98818d3282c501e28222
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/upperarm_r.iv
@@ -0,0 +1,18 @@
+#Inventor V2.1 ascii
+Separator {
+    Units {
+        units MILLIMETERS
+    }
+    Transform {
+        rotation 0 1 0 -1.57
+    }
+    Transform {
+        rotation 1 0 0 3.14
+    }
+    Transform {
+        translation -25.3 0 0 
+    }
+    File { 
+    	name "armar/right_arm/upperarm_r_conv.wrl"
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/wrist1_l.iv b/data/RobotAPI/robots/Armar3/convexModel/wrist1_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..19fef404b9ce72927594f2ebf205139f3b38b2c3
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/wrist1_l.iv
@@ -0,0 +1,15 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units {
+            units MILLIMETERS
+    }
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+	} 
+	Separator 
+	{
+		File {name armar/hands/handlink_red_conv.wrl }
+	}
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/wrist1_r.iv b/data/RobotAPI/robots/Armar3/convexModel/wrist1_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..58e77a458d86048ce7f45cfefb37a90de57860ce
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/wrist1_r.iv
@@ -0,0 +1,21 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units {
+        units MILLIMETERS
+    }
+	Transform {
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		rotation 0 0 1 1.57
+	} 
+	Transform {
+		rotation 1 0 0 1.57
+	} 
+
+	Separator 
+	{
+		File {name armar/hands/handlink_red_conv.wrl }
+	}
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/wrist2_l.iv b/data/RobotAPI/robots/Armar3/convexModel/wrist2_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..2ceb2ec0ef603f74ddbd7c9b9dc7e20c3cb2863c
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/wrist2_l.iv
@@ -0,0 +1,23 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units {
+            units MILLIMETERS
+    }
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 1.57
+	}
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+	} 
+	Separator 
+	{
+		File {name armar/hands/handlink_green_conv.wrl }
+	}
+}
diff --git a/data/RobotAPI/robots/Armar3/convexModel/wrist2_r.iv b/data/RobotAPI/robots/Armar3/convexModel/wrist2_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..0ca3c2f74e8453c79e0b8984c5bc801efadd04f2
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/convexModel/wrist2_r.iv
@@ -0,0 +1,21 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units {
+        units MILLIMETERS
+    }
+	Transform {
+		rotation 0 1 0 1.57
+	} 
+	Transform {
+		rotation 0 0 1 1.57
+	} 
+	Transform {
+		rotation 0 1 0 1.57
+    } 
+
+	Separator 
+	{
+		File {name armar/hands/handlink_green_conv.wrl }
+	}
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/eyes/eye.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/eyes/eye.iv
new file mode 100644
index 0000000000000000000000000000000000000000..4005d2bcc9701655b0b2bd5af70710e6db2a45c0
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/eyes/eye.iv
@@ -0,0 +1,9581 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.0492702 0.212826 0.267677
+    }
+    Separator {
+        Normal {
+            vector      [ -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -3.38302e-16 1 2.37421e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          1 3.38302e-16 -4.92384e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          -1 -3.38302e-16 4.92384e-14,
+                          -1 -3.38302e-16 4.92384e-14,
+                          -1 -3.38302e-16 4.92384e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          -1 -3.38302e-16 4.92384e-14,
+                          -1 -3.38302e-16 4.92384e-14,
+                          -1 -3.38302e-16 4.92384e-14,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -3.38302e-16 1 2.37421e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -3.38302e-16 1 2.37421e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -1.54611e-16 1 2.37421e-14,
+                          -1.54611e-16 1 2.37421e-14,
+                          -0.707107 0.707107 5.1605e-14,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -0.707107 0.707107 5.1605e-14,
+                          -0.707107 0.707107 5.1605e-14,
+                          -1 -9.33808e-17 4.92384e-14,
+                          -1.54611e-16 1 2.37421e-14,
+                          -0.707107 0.707107 5.1605e-14,
+                          -0.707107 0.707107 5.1605e-14,
+                          -1 -9.33808e-17 4.92384e-14,
+                          -1 -9.33808e-17 4.92384e-14,
+                          -0.707107 -0.707107 1.80286e-14,
+                          -0.707107 0.707107 5.1605e-14,
+                          -1 -9.33808e-17 4.92384e-14,
+                          -1 -9.33808e-17 4.92384e-14,
+                          -0.707107 -0.707107 1.80286e-14,
+                          -0.707107 -0.707107 1.80286e-14,
+                          3.21505e-17 -1 -2.37421e-14,
+                          -1 -9.33808e-17 4.92384e-14,
+                          -0.707107 -0.707107 1.80286e-14,
+                          -0.707107 -0.707107 1.80286e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          -0.707107 -0.707107 1.80286e-14,
+                          3.21505e-17 -1 -2.37421e-14,
+                          3.21505e-17 -1 -2.37421e-14,
+                          -1 -3.38302e-16 4.92384e-14,
+                          -1 -3.38302e-16 4.92384e-14,
+                          -1 -3.38302e-16 4.92384e-14,
+                          -1 -3.38302e-16 4.92384e-14,
+                          -1 -3.38302e-16 4.92384e-14,
+                          -1 -3.38302e-16 4.92384e-14,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          3.38302e-16 -1 -2.37421e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          1 3.38302e-16 -4.92384e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          3.38302e-16 -1 -2.37421e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          3.38302e-16 -1 -2.37421e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          2.77072e-16 -1 -2.37421e-14,
+                          2.77072e-16 -1 -2.37421e-14,
+                          0.707107 -0.707107 -5.1605e-14,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          0.707107 -0.707107 -5.1605e-14,
+                          0.707107 -0.707107 -5.1605e-14,
+                          1 2.15841e-16 -4.92384e-14,
+                          2.77072e-16 -1 -2.37421e-14,
+                          0.707107 -0.707107 -5.1605e-14,
+                          0.707107 -0.707107 -5.1605e-14,
+                          1 2.15841e-16 -4.92384e-14,
+                          1 2.15841e-16 -4.92384e-14,
+                          0.707107 0.707107 -1.80286e-14,
+                          0.707107 -0.707107 -5.1605e-14,
+                          1 2.15841e-16 -4.92384e-14,
+                          1 2.15841e-16 -4.92384e-14,
+                          0.707107 0.707107 -1.80286e-14,
+                          0.707107 0.707107 -1.80286e-14,
+                          -1.54611e-16 1 2.37421e-14,
+                          1 2.15841e-16 -4.92384e-14,
+                          0.707107 0.707107 -1.80286e-14,
+                          0.707107 0.707107 -1.80286e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          0.707107 0.707107 -1.80286e-14,
+                          -1.54611e-16 1 2.37421e-14,
+                          -1.54611e-16 1 2.37421e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          1 3.38302e-16 -4.92384e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          0.900969 0.433884 -3.4061e-14,
+                          0.900969 -0.433884 -5.46636e-14,
+                          0.900969 -0.433884 -5.46636e-14,
+                          1 9.33808e-17 -4.92384e-14,
+                          0.900969 -0.433884 -5.46636e-14,
+                          1 9.33808e-17 -4.92384e-14,
+                          1 9.33808e-17 -4.92384e-14,
+                          0.900969 0.433884 -3.4061e-14,
+                          0.900969 0.433884 -3.4061e-14,
+                          0.62349 0.781832 -1.21373e-14,
+                          0.900969 0.433884 -3.4061e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          0.900969 0.433884 -3.4061e-14,
+                          0.62349 0.781832 -1.21373e-14,
+                          0.62349 0.781832 -1.21373e-14,
+                          0.222521 0.974928 1.21902e-14,
+                          0.900969 0.433884 -3.4061e-14,
+                          0.62349 0.781832 -1.21373e-14,
+                          0.62349 0.781832 -1.21373e-14,
+                          0.222521 0.974928 1.21902e-14,
+                          0.222521 0.974928 1.21902e-14,
+                          -0.222521 0.974928 3.41034e-14,
+                          0.62349 0.781832 -1.21373e-14,
+                          0.222521 0.974928 1.21902e-14,
+                          0.222521 0.974928 1.21902e-14,
+                          -0.222521 0.974928 3.41034e-14,
+                          -0.222521 0.974928 3.41034e-14,
+                          -0.62349 0.781832 4.92619e-14,
+                          0.222521 0.974928 1.21902e-14,
+                          -0.222521 0.974928 3.41034e-14,
+                          -0.222521 0.974928 3.41034e-14,
+                          -0.62349 0.781832 4.92619e-14,
+                          -0.62349 0.781832 4.92619e-14,
+                          -0.900969 0.433884 5.46636e-14,
+                          -0.222521 0.974928 3.41034e-14,
+                          -0.62349 0.781832 4.92619e-14,
+                          -0.62349 0.781832 4.92619e-14,
+                          -0.900969 0.433884 5.46636e-14,
+                          -0.900969 0.433884 5.46636e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -0.62349 0.781832 4.92619e-14,
+                          -0.900969 0.433884 5.46636e-14,
+                          -0.900969 0.433884 5.46636e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -0.900969 -0.433884 3.4061e-14,
+                          -0.900969 0.433884 5.46636e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -0.900969 -0.433884 3.4061e-14,
+                          -0.900969 -0.433884 3.4061e-14,
+                          -0.62349 -0.781832 1.21373e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -0.900969 -0.433884 3.4061e-14,
+                          -0.900969 -0.433884 3.4061e-14,
+                          -0.62349 -0.781832 1.21373e-14,
+                          -0.62349 -0.781832 1.21373e-14,
+                          -0.222521 -0.974928 -1.21902e-14,
+                          -0.900969 -0.433884 3.4061e-14,
+                          -0.62349 -0.781832 1.21373e-14,
+                          -0.62349 -0.781832 1.21373e-14,
+                          -0.222521 -0.974928 -1.21902e-14,
+                          -0.222521 -0.974928 -1.21902e-14,
+                          0.222521 -0.974928 -3.41034e-14,
+                          -0.62349 -0.781832 1.21373e-14,
+                          -0.222521 -0.974928 -1.21902e-14,
+                          -0.222521 -0.974928 -1.21902e-14,
+                          0.222521 -0.974928 -3.41034e-14,
+                          0.222521 -0.974928 -3.41034e-14,
+                          0.62349 -0.781832 -4.92619e-14,
+                          -0.222521 -0.974928 -1.21902e-14,
+                          0.222521 -0.974928 -3.41034e-14,
+                          0.222521 -0.974928 -3.41034e-14,
+                          0.62349 -0.781832 -4.92619e-14,
+                          0.62349 -0.781832 -4.92619e-14,
+                          0.900969 -0.433884 -5.46636e-14,
+                          0.222521 -0.974928 -3.41034e-14,
+                          0.62349 -0.781832 -4.92619e-14,
+                          0.62349 -0.781832 -4.92619e-14,
+                          0.62349 -0.781832 -4.92619e-14,
+                          0.900969 -0.433884 -5.46636e-14,
+                          0.900969 -0.433884 -5.46636e-14,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          1 3.38302e-16 -4.92384e-14,
+                          1 2.15841e-16 -4.92384e-14,
+                          0.866025 0.5 -3.07707e-14,
+                          0.866025 -0.5 -5.45127e-14,
+                          0.866025 -0.5 -5.45127e-14,
+                          1 9.33808e-17 -4.92384e-14,
+                          0.866025 -0.5 -5.45127e-14,
+                          1 9.33808e-17 -4.92384e-14,
+                          1 9.33808e-17 -4.92384e-14,
+                          0.866025 0.5 -3.07707e-14,
+                          0.866025 0.5 -3.07707e-14,
+                          0.5 0.866025 -4.05797e-15,
+                          0.866025 0.5 -3.07707e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          0.866025 0.5 -3.07707e-14,
+                          0.5 0.866025 -4.05797e-15,
+                          0.5 0.866025 -4.05797e-15,
+                          -2.77072e-16 1 2.37421e-14,
+                          0.5 0.866025 -4.05797e-15,
+                          0.866025 0.5 -3.07707e-14,
+                          0.5 0.866025 -4.05797e-15,
+                          -5.50271e-17 1 2.37421e-14,
+                          -2.77072e-16 1 2.37421e-14,
+                          -0.5 0.866025 4.51804e-14,
+                          -5.50271e-17 1 2.37421e-14,
+                          0.5 0.866025 -4.05797e-15,
+                          -2.77072e-16 1 2.37421e-14,
+                          -0.5 0.866025 4.51804e-14,
+                          -0.5 0.866025 4.51804e-14,
+                          -0.866025 0.5 5.45127e-14,
+                          -0.5 0.866025 4.51804e-14,
+                          -5.50271e-17 1 2.37421e-14,
+                          -0.5 0.866025 4.51804e-14,
+                          -0.866025 0.5 5.45127e-14,
+                          -0.866025 0.5 5.45127e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -0.866025 0.5 5.45127e-14,
+                          -0.5 0.866025 4.51804e-14,
+                          -0.866025 0.5 5.45127e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -0.866025 -0.5 3.07707e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -0.866025 0.5 5.45127e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -0.866025 -0.5 3.07707e-14,
+                          -0.866025 -0.5 3.07707e-14,
+                          -0.5 -0.866025 4.05797e-15,
+                          -0.866025 -0.5 3.07707e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -0.866025 -0.5 3.07707e-14,
+                          -0.5 -0.866025 4.05797e-15,
+                          -0.5 -0.866025 4.05797e-15,
+                          1.54611e-16 -1 -2.37421e-14,
+                          -0.5 -0.866025 4.05797e-15,
+                          -0.866025 -0.5 3.07707e-14,
+                          -0.5 -0.866025 4.05797e-15,
+                          1.54611e-16 -1 -2.37421e-14,
+                          1.54611e-16 -1 -2.37421e-14,
+                          0.5 -0.866025 -4.51804e-14,
+                          1.54611e-16 -1 -2.37421e-14,
+                          -0.5 -0.866025 4.05797e-15,
+                          1.54611e-16 -1 -2.37421e-14,
+                          0.5 -0.866025 -4.51804e-14,
+                          0.5 -0.866025 -4.51804e-14,
+                          0.866025 -0.5 -5.45127e-14,
+                          0.5 -0.866025 -4.51804e-14,
+                          1.54611e-16 -1 -2.37421e-14,
+                          0.5 -0.866025 -4.51804e-14,
+                          0.866025 -0.5 -5.45127e-14,
+                          0.5 -0.866025 -4.51804e-14,
+                          0.866025 -0.5 -5.45127e-14,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          1 3.38302e-16 -4.92384e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          0.866025 0.5 -3.07707e-14,
+                          0.866025 -0.5 -5.45127e-14,
+                          0.866025 -0.5 -5.45127e-14,
+                          1 9.33808e-17 -4.92384e-14,
+                          0.866025 -0.5 -5.45127e-14,
+                          1 9.33808e-17 -4.92384e-14,
+                          1 9.33808e-17 -4.92384e-14,
+                          0.866025 0.5 -3.07707e-14,
+                          0.866025 0.5 -3.07707e-14,
+                          0.5 0.866025 -4.05797e-15,
+                          0.866025 0.5 -3.07707e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          0.866025 0.5 -3.07707e-14,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          0.5 0.866025 -4.05797e-15,
+                          0.5 0.866025 -4.05797e-15,
+                          -2.77072e-16 1 2.37421e-14,
+                          0.866025 0.5 -3.07707e-14,
+                          0.5 0.866025 -4.05797e-15,
+                          0.5 0.866025 -4.05797e-15,
+                          -2.77072e-16 1 2.37421e-14,
+                          -2.77072e-16 1 2.37421e-14,
+                          -0.5 0.866025 4.51804e-14,
+                          0.5 0.866025 -4.05797e-15,
+                          -2.77072e-16 1 2.37421e-14,
+                          -2.77072e-16 1 2.37421e-14,
+                          -0.5 0.866025 4.51804e-14,
+                          -0.5 0.866025 4.51804e-14,
+                          -0.866025 0.5 5.45127e-14,
+                          -2.77072e-16 1 2.37421e-14,
+                          -0.5 0.866025 4.51804e-14,
+                          -0.5 0.866025 4.51804e-14,
+                          -0.866025 0.5 5.45127e-14,
+                          -0.866025 0.5 5.45127e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -0.5 0.866025 4.51804e-14,
+                          -0.866025 0.5 5.45127e-14,
+                          -0.866025 0.5 5.45127e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -0.866025 -0.5 3.07707e-14,
+                          -0.866025 0.5 5.45127e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -0.866025 -0.5 3.07707e-14,
+                          -0.866025 -0.5 3.07707e-14,
+                          -0.5 -0.866025 4.05797e-15,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -0.866025 -0.5 3.07707e-14,
+                          -0.866025 -0.5 3.07707e-14,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -0.5 -0.866025 4.05797e-15,
+                          -0.5 -0.866025 4.05797e-15,
+                          1.54611e-16 -1 -2.37421e-14,
+                          -0.866025 -0.5 3.07707e-14,
+                          -0.5 -0.866025 4.05797e-15,
+                          -0.5 -0.866025 4.05797e-15,
+                          1.54611e-16 -1 -2.37421e-14,
+                          1.54611e-16 -1 -2.37421e-14,
+                          0.5 -0.866025 -4.51804e-14,
+                          -0.5 -0.866025 4.05797e-15,
+                          1.54611e-16 -1 -2.37421e-14,
+                          1.54611e-16 -1 -2.37421e-14,
+                          0.5 -0.866025 -4.51804e-14,
+                          0.5 -0.866025 -4.51804e-14,
+                          0.866025 -0.5 -5.45127e-14,
+                          1.54611e-16 -1 -2.37421e-14,
+                          0.5 -0.866025 -4.51804e-14,
+                          0.5 -0.866025 -4.51804e-14,
+                          0.5 -0.866025 -4.51804e-14,
+                          0.866025 -0.5 -5.45127e-14,
+                          0.866025 -0.5 -5.45127e-14,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -8.3 -6.5 -3.35,
+                          -8.3 -0.2 -3.35,
+                          8.3 -0.2 -3.35,
+                          8.3 -0.2 3.35,
+                          8.3 -0.2 -3.35,
+                          -8.3 -0.2 -3.35,
+                          -8.3 -10.5 -3.35,
+                          -8.3 -6.5 -3.35,
+                          8.3 -0.2 -3.35,
+                          -8.3 -16.8 -3.35,
+                          -8.3 -10.5 -3.35,
+                          8.3 -0.2 -3.35,
+                          8.3 -6.5 -3.35,
+                          -8.3 -16.8 -3.35,
+                          8.3 -0.2 -3.35,
+                          8.3 -0.2 3.35,
+                          8.3 -6.5 -3.35,
+                          8.3 -0.2 -3.35,
+                          -8.3 -6.5 3.35,
+                          -8.3 -0.2 -3.35,
+                          -8.3 -6.5 -3.35,
+                          -8.3 -0.2 3.35,
+                          8.3 -0.2 3.35,
+                          -8.3 -0.2 -3.35,
+                          -8.3 -0.2 3.35,
+                          -8.3 -0.2 -3.35,
+                          -8.3 -6.5 3.35,
+                          -10.6 -10.5 -3.35,
+                          -10.6 -6.5 -3.35,
+                          -8.3 -6.5 -3.35,
+                          -10.6 -6.5 3.35,
+                          -8.3 -6.5 -3.35,
+                          -10.6 -6.5 -3.35,
+                          -8.3 -10.5 -3.35,
+                          -10.6 -10.5 -3.35,
+                          -8.3 -6.5 -3.35,
+                          -8.3 -6.5 3.35,
+                          -8.3 -6.5 -3.35,
+                          -10.6 -6.5 3.35,
+                          -12.0141 -9.91413 -3.35,
+                          -12.0141 -7.08587 -3.35,
+                          -10.6 -6.5 -3.35,
+                          -10.6 -6.5 3.35,
+                          -10.6 -6.5 -3.35,
+                          -12.0141 -7.08587 -3.35,
+                          -10.6 -10.5 -3.35,
+                          -12.0141 -9.91413 -3.35,
+                          -10.6 -6.5 -3.35,
+                          -12.0141 -9.91413 -3.35,
+                          -12.6 -8.5 -3.35,
+                          -12.0141 -7.08587 -3.35,
+                          -12.0141 -7.08587 3.35,
+                          -12.0141 -7.08587 -3.35,
+                          -12.6 -8.5 -3.35,
+                          -10.6 -6.5 3.35,
+                          -12.0141 -7.08587 -3.35,
+                          -12.0141 -7.08587 3.35,
+                          -12.6 -8.5 3.35,
+                          -12.6 -8.5 -3.35,
+                          -12.0141 -9.91413 -3.35,
+                          -12.0141 -7.08587 3.35,
+                          -12.6 -8.5 -3.35,
+                          -12.6 -8.5 3.35,
+                          -12.0141 -9.91413 3.35,
+                          -12.0141 -9.91413 -3.35,
+                          -10.6 -10.5 -3.35,
+                          -12.6 -8.5 3.35,
+                          -12.0141 -9.91413 -3.35,
+                          -12.0141 -9.91413 3.35,
+                          -8.3 -10.5 3.35,
+                          -10.6 -10.5 -3.35,
+                          -8.3 -10.5 -3.35,
+                          -10.6 -10.5 3.35,
+                          -10.6 -10.5 -3.35,
+                          -8.3 -10.5 3.35,
+                          -12.0141 -9.91413 3.35,
+                          -10.6 -10.5 -3.35,
+                          -10.6 -10.5 3.35,
+                          -8.3 -16.8 3.35,
+                          -8.3 -10.5 -3.35,
+                          -8.3 -16.8 -3.35,
+                          -8.3 -10.5 3.35,
+                          -8.3 -10.5 -3.35,
+                          -8.3 -16.8 3.35,
+                          8.3 -10.5 -3.35,
+                          8.3 -16.8 -3.35,
+                          -8.3 -16.8 -3.35,
+                          -8.3 -16.8 3.35,
+                          -8.3 -16.8 -3.35,
+                          8.3 -16.8 -3.35,
+                          8.3 -6.5 -3.35,
+                          8.3 -10.5 -3.35,
+                          -8.3 -16.8 -3.35,
+                          8.3 -10.5 3.35,
+                          8.3 -16.8 -3.35,
+                          8.3 -10.5 -3.35,
+                          8.3 -16.8 3.35,
+                          8.3 -16.8 -3.35,
+                          8.3 -10.5 3.35,
+                          -8.3 -16.8 3.35,
+                          8.3 -16.8 -3.35,
+                          8.3 -16.8 3.35,
+                          10.6 -6.5 -3.35,
+                          10.6 -10.5 -3.35,
+                          8.3 -10.5 -3.35,
+                          10.6 -10.5 3.35,
+                          8.3 -10.5 -3.35,
+                          10.6 -10.5 -3.35,
+                          8.3 -6.5 -3.35,
+                          10.6 -6.5 -3.35,
+                          8.3 -10.5 -3.35,
+                          8.3 -10.5 3.35,
+                          8.3 -10.5 -3.35,
+                          10.6 -10.5 3.35,
+                          12.0141 -7.08587 -3.35,
+                          12.0141 -9.91413 -3.35,
+                          10.6 -10.5 -3.35,
+                          10.6 -10.5 3.35,
+                          10.6 -10.5 -3.35,
+                          12.0141 -9.91413 -3.35,
+                          10.6 -6.5 -3.35,
+                          12.0141 -7.08587 -3.35,
+                          10.6 -10.5 -3.35,
+                          12.0141 -7.08587 -3.35,
+                          12.6 -8.5 -3.35,
+                          12.0141 -9.91413 -3.35,
+                          12.0141 -9.91413 3.35,
+                          12.0141 -9.91413 -3.35,
+                          12.6 -8.5 -3.35,
+                          10.6 -10.5 3.35,
+                          12.0141 -9.91413 -3.35,
+                          12.0141 -9.91413 3.35,
+                          12.6 -8.5 3.35,
+                          12.6 -8.5 -3.35,
+                          12.0141 -7.08587 -3.35,
+                          12.0141 -9.91413 3.35,
+                          12.6 -8.5 -3.35,
+                          12.6 -8.5 3.35,
+                          12.0141 -7.08587 3.35,
+                          12.0141 -7.08587 -3.35,
+                          10.6 -6.5 -3.35,
+                          12.6 -8.5 3.35,
+                          12.0141 -7.08587 -3.35,
+                          12.0141 -7.08587 3.35,
+                          8.3 -6.5 3.35,
+                          10.6 -6.5 -3.35,
+                          8.3 -6.5 -3.35,
+                          10.6 -6.5 3.35,
+                          10.6 -6.5 -3.35,
+                          8.3 -6.5 3.35,
+                          12.0141 -7.08587 3.35,
+                          10.6 -6.5 -3.35,
+                          10.6 -6.5 3.35,
+                          8.3 -6.5 3.35,
+                          8.3 -6.5 -3.35,
+                          8.3 -0.2 3.35,
+                          7.20788 -5.02924 3.35,
+                          8.3 -6.5 3.35,
+                          8.3 -0.2 3.35,
+                          1.78028 -0.70068 3.35,
+                          8.3 -0.2 3.35,
+                          -8.3 -0.2 3.35,
+                          4.98815 -2.2456 3.35,
+                          7.20788 -5.02924 3.35,
+                          8.3 -0.2 3.35,
+                          1.78028 -0.70068 3.35,
+                          4.98815 -2.2456 3.35,
+                          8.3 -0.2 3.35,
+                          10.6 -10.5 3.35,
+                          10.6 -6.5 3.35,
+                          8.3 -6.5 3.35,
+                          8.3 -10.5 3.35,
+                          10.6 -10.5 3.35,
+                          8.3 -6.5 3.35,
+                          8 -8.5 3.35,
+                          8.3 -10.5 3.35,
+                          8.3 -6.5 3.35,
+                          7.20788 -5.02924 3.35,
+                          8 -8.5 3.35,
+                          8.3 -6.5 3.35,
+                          12.0141 -9.91413 3.35,
+                          12.0141 -7.08587 3.35,
+                          10.6 -6.5 3.35,
+                          10.6 -10.5 3.35,
+                          12.0141 -9.91413 3.35,
+                          10.6 -6.5 3.35,
+                          12.0141 -9.91413 3.35,
+                          12.6 -8.5 3.35,
+                          12.0141 -7.08587 3.35,
+                          8 -8.5 3.35,
+                          8.3 -16.8 3.35,
+                          8.3 -10.5 3.35,
+                          -1.78028 -16.2993 3.35,
+                          -8.3 -16.8 3.35,
+                          8.3 -16.8 3.35,
+                          7.20788 -11.9708 3.35,
+                          8.3 -16.8 3.35,
+                          8 -8.5 3.35,
+                          1.78028 -16.2993 3.35,
+                          -1.78028 -16.2993 3.35,
+                          8.3 -16.8 3.35,
+                          4.98815 -14.7544 3.35,
+                          1.78028 -16.2993 3.35,
+                          8.3 -16.8 3.35,
+                          7.20788 -11.9708 3.35,
+                          4.98815 -14.7544 3.35,
+                          8.3 -16.8 3.35,
+                          -7.20788 -11.9708 3.35,
+                          -8.3 -10.5 3.35,
+                          -8.3 -16.8 3.35,
+                          -4.98815 -14.7544 3.35,
+                          -7.20788 -11.9708 3.35,
+                          -8.3 -16.8 3.35,
+                          -1.78028 -16.2993 3.35,
+                          -4.98815 -14.7544 3.35,
+                          -8.3 -16.8 3.35,
+                          -10.6 -6.5 3.35,
+                          -10.6 -10.5 3.35,
+                          -8.3 -10.5 3.35,
+                          -8.3 -6.5 3.35,
+                          -10.6 -6.5 3.35,
+                          -8.3 -10.5 3.35,
+                          -8 -8.5 3.35,
+                          -8.3 -6.5 3.35,
+                          -8.3 -10.5 3.35,
+                          -7.20788 -11.9708 3.35,
+                          -8 -8.5 3.35,
+                          -8.3 -10.5 3.35,
+                          -12.0141 -7.08587 3.35,
+                          -12.0141 -9.91413 3.35,
+                          -10.6 -10.5 3.35,
+                          -10.6 -6.5 3.35,
+                          -12.0141 -7.08587 3.35,
+                          -10.6 -10.5 3.35,
+                          -12.0141 -7.08587 3.35,
+                          -12.6 -8.5 3.35,
+                          -12.0141 -9.91413 3.35,
+                          -8 -8.5 3.35,
+                          -8.3 -0.2 3.35,
+                          -8.3 -6.5 3.35,
+                          -1.78028 -0.70068 3.35,
+                          1.78028 -0.70068 3.35,
+                          -8.3 -0.2 3.35,
+                          -4.98815 -2.2456 3.35,
+                          -1.78028 -0.70068 3.35,
+                          -8.3 -0.2 3.35,
+                          -7.20788 -5.02924 3.35,
+                          -4.98815 -2.2456 3.35,
+                          -8.3 -0.2 3.35,
+                          -8 -8.5 3.35,
+                          -7.20788 -5.02924 3.35,
+                          -8.3 -0.2 3.35,
+                          8 -8.5 12.35,
+                          8 -8.5 3.35,
+                          7.20788 -5.02924 3.35,
+                          7.20775 -11.9711 12.35,
+                          7.20788 -11.9708 3.35,
+                          8 -8.5 3.35,
+                          7.20775 -11.9711 12.35,
+                          8 -8.5 3.35,
+                          8 -8.5 12.35,
+                          7.20775 -5.02893 12.35,
+                          7.20788 -5.02924 3.35,
+                          4.98815 -2.2456 3.35,
+                          7.20775 -5.02893 12.35,
+                          8 -8.5 12.35,
+                          7.20788 -5.02924 3.35,
+                          4.98792 -2.24535 12.35,
+                          4.98815 -2.2456 3.35,
+                          1.78028 -0.70068 3.35,
+                          7.20775 -5.02893 12.35,
+                          4.98815 -2.2456 3.35,
+                          4.98792 -2.24535 12.35,
+                          1.78017 -0.700577 12.35,
+                          1.78028 -0.70068 3.35,
+                          -1.78028 -0.70068 3.35,
+                          4.98792 -2.24535 12.35,
+                          1.78028 -0.70068 3.35,
+                          1.78017 -0.700577 12.35,
+                          -1.78017 -0.700577 12.35,
+                          -1.78028 -0.70068 3.35,
+                          -4.98815 -2.2456 3.35,
+                          1.78017 -0.700577 12.35,
+                          -1.78028 -0.70068 3.35,
+                          -1.78017 -0.700577 12.35,
+                          -4.98792 -2.24535 12.35,
+                          -4.98815 -2.2456 3.35,
+                          -7.20788 -5.02924 3.35,
+                          -1.78017 -0.700577 12.35,
+                          -4.98815 -2.2456 3.35,
+                          -4.98792 -2.24535 12.35,
+                          -7.20775 -5.02893 12.35,
+                          -7.20788 -5.02924 3.35,
+                          -8 -8.5 3.35,
+                          -4.98792 -2.24535 12.35,
+                          -7.20788 -5.02924 3.35,
+                          -7.20775 -5.02893 12.35,
+                          -8 -8.5 12.35,
+                          -8 -8.5 3.35,
+                          -7.20788 -11.9708 3.35,
+                          -7.20775 -5.02893 12.35,
+                          -8 -8.5 3.35,
+                          -8 -8.5 12.35,
+                          -7.20775 -11.9711 12.35,
+                          -7.20788 -11.9708 3.35,
+                          -4.98815 -14.7544 3.35,
+                          -8 -8.5 12.35,
+                          -7.20788 -11.9708 3.35,
+                          -7.20775 -11.9711 12.35,
+                          -4.98792 -14.7547 12.35,
+                          -4.98815 -14.7544 3.35,
+                          -1.78028 -16.2993 3.35,
+                          -7.20775 -11.9711 12.35,
+                          -4.98815 -14.7544 3.35,
+                          -4.98792 -14.7547 12.35,
+                          -1.78017 -16.2994 12.35,
+                          -1.78028 -16.2993 3.35,
+                          1.78028 -16.2993 3.35,
+                          -4.98792 -14.7547 12.35,
+                          -1.78028 -16.2993 3.35,
+                          -1.78017 -16.2994 12.35,
+                          1.78017 -16.2994 12.35,
+                          1.78028 -16.2993 3.35,
+                          4.98815 -14.7544 3.35,
+                          -1.78017 -16.2994 12.35,
+                          1.78028 -16.2993 3.35,
+                          1.78017 -16.2994 12.35,
+                          4.98792 -14.7547 12.35,
+                          4.98815 -14.7544 3.35,
+                          7.20788 -11.9708 3.35,
+                          1.78017 -16.2994 12.35,
+                          4.98815 -14.7544 3.35,
+                          4.98792 -14.7547 12.35,
+                          4.98792 -14.7547 12.35,
+                          7.20788 -11.9708 3.35,
+                          7.20775 -11.9711 12.35,
+                          5.19624 -11.4997 12.35,
+                          7.20775 -11.9711 12.35,
+                          8 -8.5 12.35,
+                          6 -8.5 12.35,
+                          8 -8.5 12.35,
+                          7.20775 -5.02893 12.35,
+                          5.19624 -11.4997 12.35,
+                          8 -8.5 12.35,
+                          6 -8.5 12.35,
+                          2.99972 -13.6962 12.35,
+                          4.98792 -14.7547 12.35,
+                          7.20775 -11.9711 12.35,
+                          5.19624 -11.4997 12.35,
+                          2.99972 -13.6962 12.35,
+                          7.20775 -11.9711 12.35,
+                          -1.78017 -16.2994 12.35,
+                          1.78017 -16.2994 12.35,
+                          4.98792 -14.7547 12.35,
+                          -4.98792 -14.7547 12.35,
+                          -1.78017 -16.2994 12.35,
+                          4.98792 -14.7547 12.35,
+                          6.0122e-13 -14.5 12.35,
+                          -4.98792 -14.7547 12.35,
+                          4.98792 -14.7547 12.35,
+                          2.99972 -13.6962 12.35,
+                          6.0122e-13 -14.5 12.35,
+                          4.98792 -14.7547 12.35,
+                          -2.99972 -13.6962 12.35,
+                          -7.20775 -11.9711 12.35,
+                          -4.98792 -14.7547 12.35,
+                          6.0122e-13 -14.5 12.35,
+                          -2.99972 -13.6962 12.35,
+                          -4.98792 -14.7547 12.35,
+                          -6 -8.5 12.35,
+                          -8 -8.5 12.35,
+                          -7.20775 -11.9711 12.35,
+                          -5.19624 -11.4997 12.35,
+                          -6 -8.5 12.35,
+                          -7.20775 -11.9711 12.35,
+                          -2.99972 -13.6962 12.35,
+                          -5.19624 -11.4997 12.35,
+                          -7.20775 -11.9711 12.35,
+                          -5.19624 -5.50028 12.35,
+                          -7.20775 -5.02893 12.35,
+                          -8 -8.5 12.35,
+                          -6 -8.5 12.35,
+                          -5.19624 -5.50028 12.35,
+                          -8 -8.5 12.35,
+                          -2.99972 -3.30376 12.35,
+                          -4.98792 -2.24535 12.35,
+                          -7.20775 -5.02893 12.35,
+                          -5.19624 -5.50028 12.35,
+                          -2.99972 -3.30376 12.35,
+                          -7.20775 -5.02893 12.35,
+                          1.78017 -0.700577 12.35,
+                          -1.78017 -0.700577 12.35,
+                          -4.98792 -2.24535 12.35,
+                          4.98792 -2.24535 12.35,
+                          1.78017 -0.700577 12.35,
+                          -4.98792 -2.24535 12.35,
+                          5.9863e-13 -2.5 12.35,
+                          4.98792 -2.24535 12.35,
+                          -4.98792 -2.24535 12.35,
+                          -2.99972 -3.30376 12.35,
+                          5.9863e-13 -2.5 12.35,
+                          -4.98792 -2.24535 12.35,
+                          2.99972 -3.30376 12.35,
+                          7.20775 -5.02893 12.35,
+                          4.98792 -2.24535 12.35,
+                          5.9863e-13 -2.5 12.35,
+                          2.99972 -3.30376 12.35,
+                          4.98792 -2.24535 12.35,
+                          5.19624 -5.50028 12.35,
+                          6 -8.5 12.35,
+                          7.20775 -5.02893 12.35,
+                          2.99972 -3.30376 12.35,
+                          5.19624 -5.50028 12.35,
+                          7.20775 -5.02893 12.35,
+                          6 -8.5 14.15,
+                          6 -8.5 12.35,
+                          5.19624 -5.50028 12.35,
+                          5.19624 -11.4997 14.15,
+                          5.19624 -11.4997 12.35,
+                          6 -8.5 12.35,
+                          5.19624 -11.4997 14.15,
+                          6 -8.5 12.35,
+                          6 -8.5 14.15,
+                          5.19624 -5.50028 14.15,
+                          5.19624 -5.50028 12.35,
+                          2.99972 -3.30376 12.35,
+                          5.19624 -5.50028 14.15,
+                          6 -8.5 14.15,
+                          5.19624 -5.50028 12.35,
+                          2.99972 -3.30376 14.15,
+                          2.99972 -3.30376 12.35,
+                          5.9863e-13 -2.5 12.35,
+                          2.99972 -3.30376 14.15,
+                          5.19624 -5.50028 14.15,
+                          2.99972 -3.30376 12.35,
+                          6.88591e-13 -2.5 14.15,
+                          5.9863e-13 -2.5 12.35,
+                          -2.99972 -3.30376 12.35,
+                          6.88591e-13 -2.5 14.15,
+                          2.99972 -3.30376 14.15,
+                          5.9863e-13 -2.5 12.35,
+                          -2.99972 -3.30376 14.15,
+                          -2.99972 -3.30376 12.35,
+                          -5.19624 -5.50028 12.35,
+                          -2.99972 -3.30376 14.15,
+                          6.88591e-13 -2.5 14.15,
+                          -2.99972 -3.30376 12.35,
+                          -5.19624 -5.50028 14.15,
+                          -5.19624 -5.50028 12.35,
+                          -6 -8.5 12.35,
+                          -5.19624 -5.50028 14.15,
+                          -2.99972 -3.30376 14.15,
+                          -5.19624 -5.50028 12.35,
+                          -6 -8.5 14.15,
+                          -6 -8.5 12.35,
+                          -5.19624 -11.4997 12.35,
+                          -6 -8.5 14.15,
+                          -5.19624 -5.50028 14.15,
+                          -6 -8.5 12.35,
+                          -5.19624 -11.4997 14.15,
+                          -5.19624 -11.4997 12.35,
+                          -2.99972 -13.6962 12.35,
+                          -5.19624 -11.4997 14.15,
+                          -6 -8.5 14.15,
+                          -5.19624 -11.4997 12.35,
+                          -2.99972 -13.6962 14.15,
+                          -2.99972 -13.6962 12.35,
+                          6.0122e-13 -14.5 12.35,
+                          -2.99972 -13.6962 14.15,
+                          -5.19624 -11.4997 14.15,
+                          -2.99972 -13.6962 12.35,
+                          6.89849e-13 -14.5 14.15,
+                          6.0122e-13 -14.5 12.35,
+                          2.99972 -13.6962 12.35,
+                          6.89849e-13 -14.5 14.15,
+                          -2.99972 -13.6962 14.15,
+                          6.0122e-13 -14.5 12.35,
+                          2.99972 -13.6962 14.15,
+                          2.99972 -13.6962 12.35,
+                          5.19624 -11.4997 12.35,
+                          2.99972 -13.6962 14.15,
+                          6.89849e-13 -14.5 14.15,
+                          2.99972 -13.6962 12.35,
+                          5.19624 -11.4997 14.15,
+                          2.99972 -13.6962 14.15,
+                          5.19624 -11.4997 12.35,
+                          7.5 -8.5 14.15,
+                          6 -8.5 14.15,
+                          5.19624 -5.50028 14.15,
+                          6.4953 -12.2496 14.15,
+                          5.19624 -11.4997 14.15,
+                          6 -8.5 14.15,
+                          6.4953 -12.2496 14.15,
+                          6 -8.5 14.15,
+                          7.5 -8.5 14.15,
+                          6.4953 -4.75035 14.15,
+                          5.19624 -5.50028 14.15,
+                          2.99972 -3.30376 14.15,
+                          6.4953 -4.75035 14.15,
+                          7.5 -8.5 14.15,
+                          5.19624 -5.50028 14.15,
+                          3.74965 -2.0047 14.15,
+                          2.99972 -3.30376 14.15,
+                          6.88591e-13 -2.5 14.15,
+                          3.74965 -2.0047 14.15,
+                          6.4953 -4.75035 14.15,
+                          2.99972 -3.30376 14.15,
+                          -3.74965 -2.0047 14.15,
+                          6.88591e-13 -2.5 14.15,
+                          -2.99972 -3.30376 14.15,
+                          -3.74965 -2.0047 14.15,
+                          3.74965 -2.0047 14.15,
+                          6.88591e-13 -2.5 14.15,
+                          -6.4953 -4.75035 14.15,
+                          -2.99972 -3.30376 14.15,
+                          -5.19624 -5.50028 14.15,
+                          -6.4953 -4.75035 14.15,
+                          -3.74965 -2.0047 14.15,
+                          -2.99972 -3.30376 14.15,
+                          -6.4953 -4.75035 14.15,
+                          -5.19624 -5.50028 14.15,
+                          -6 -8.5 14.15,
+                          -7.5 -8.5 14.15,
+                          -6 -8.5 14.15,
+                          -5.19624 -11.4997 14.15,
+                          -7.5 -8.5 14.15,
+                          -6.4953 -4.75035 14.15,
+                          -6 -8.5 14.15,
+                          -6.4953 -12.2496 14.15,
+                          -5.19624 -11.4997 14.15,
+                          -2.99972 -13.6962 14.15,
+                          -6.4953 -12.2496 14.15,
+                          -7.5 -8.5 14.15,
+                          -5.19624 -11.4997 14.15,
+                          -3.74965 -14.9953 14.15,
+                          -2.99972 -13.6962 14.15,
+                          6.89849e-13 -14.5 14.15,
+                          -3.74965 -14.9953 14.15,
+                          -6.4953 -12.2496 14.15,
+                          -2.99972 -13.6962 14.15,
+                          3.74965 -14.9953 14.15,
+                          6.89849e-13 -14.5 14.15,
+                          2.99972 -13.6962 14.15,
+                          3.74965 -14.9953 14.15,
+                          -3.74965 -14.9953 14.15,
+                          6.89849e-13 -14.5 14.15,
+                          6.4953 -12.2496 14.15,
+                          2.99972 -13.6962 14.15,
+                          5.19624 -11.4997 14.15,
+                          6.4953 -12.2496 14.15,
+                          3.74965 -14.9953 14.15,
+                          2.99972 -13.6962 14.15,
+                          7.5 -8.5 17.45,
+                          7.5 -8.5 14.15,
+                          6.4953 -4.75035 14.15,
+                          6.4953 -12.2496 17.45,
+                          6.4953 -12.2496 14.15,
+                          7.5 -8.5 14.15,
+                          6.4953 -12.2496 17.45,
+                          7.5 -8.5 14.15,
+                          7.5 -8.5 17.45,
+                          6.4953 -4.75035 17.45,
+                          6.4953 -4.75035 14.15,
+                          3.74965 -2.0047 14.15,
+                          6.4953 -4.75035 17.45,
+                          7.5 -8.5 17.45,
+                          6.4953 -4.75035 14.15,
+                          -3.74965 -2.0047 14.15,
+                          6.86843e-13 -1 14.15,
+                          3.74965 -2.0047 14.15,
+                          3.74965 -2.0047 17.45,
+                          3.74965 -2.0047 14.15,
+                          6.86843e-13 -1 14.15,
+                          6.4953 -4.75035 17.45,
+                          3.74965 -2.0047 14.15,
+                          3.74965 -2.0047 17.45,
+                          8.4933e-13 -1 17.45,
+                          6.86843e-13 -1 14.15,
+                          -3.74965 -2.0047 14.15,
+                          3.74965 -2.0047 17.45,
+                          6.86843e-13 -1 14.15,
+                          8.4933e-13 -1 17.45,
+                          -3.74965 -2.0047 17.45,
+                          -3.74965 -2.0047 14.15,
+                          -6.4953 -4.75035 14.15,
+                          8.4933e-13 -1 17.45,
+                          -3.74965 -2.0047 14.15,
+                          -3.74965 -2.0047 17.45,
+                          -6.4953 -4.75035 17.45,
+                          -6.4953 -4.75035 14.15,
+                          -7.5 -8.5 14.15,
+                          -3.74965 -2.0047 17.45,
+                          -6.4953 -4.75035 14.15,
+                          -6.4953 -4.75035 17.45,
+                          -7.5 -8.5 17.45,
+                          -7.5 -8.5 14.15,
+                          -6.4953 -12.2496 14.15,
+                          -6.4953 -4.75035 17.45,
+                          -7.5 -8.5 14.15,
+                          -7.5 -8.5 17.45,
+                          -6.4953 -12.2496 17.45,
+                          -6.4953 -12.2496 14.15,
+                          -3.74965 -14.9953 14.15,
+                          -7.5 -8.5 17.45,
+                          -6.4953 -12.2496 14.15,
+                          -6.4953 -12.2496 17.45,
+                          3.74965 -14.9953 14.15,
+                          6.90081e-13 -16 14.15,
+                          -3.74965 -14.9953 14.15,
+                          -3.74965 -14.9953 17.45,
+                          -3.74965 -14.9953 14.15,
+                          6.90081e-13 -16 14.15,
+                          -6.4953 -12.2496 17.45,
+                          -3.74965 -14.9953 14.15,
+                          -3.74965 -14.9953 17.45,
+                          8.52567e-13 -16 17.45,
+                          6.90081e-13 -16 14.15,
+                          3.74965 -14.9953 14.15,
+                          -3.74965 -14.9953 17.45,
+                          6.90081e-13 -16 14.15,
+                          8.52567e-13 -16 17.45,
+                          3.74965 -14.9953 17.45,
+                          3.74965 -14.9953 14.15,
+                          6.4953 -12.2496 14.15,
+                          8.52567e-13 -16 17.45,
+                          3.74965 -14.9953 14.15,
+                          3.74965 -14.9953 17.45,
+                          3.74965 -14.9953 17.45,
+                          6.4953 -12.2496 14.15,
+                          6.4953 -12.2496 17.45,
+                          -6.4953 -12.2496 17.45,
+                          6.4953 -12.2496 17.45,
+                          7.5 -8.5 17.45,
+                          -7.5 -8.5 17.45,
+                          -6.4953 -12.2496 17.45,
+                          7.5 -8.5 17.45,
+                          6.4953 -4.75035 17.45,
+                          -7.5 -8.5 17.45,
+                          7.5 -8.5 17.45,
+                          -3.74965 -14.9953 17.45,
+                          3.74965 -14.9953 17.45,
+                          6.4953 -12.2496 17.45,
+                          -6.4953 -12.2496 17.45,
+                          -3.74965 -14.9953 17.45,
+                          6.4953 -12.2496 17.45,
+                          -3.74965 -14.9953 17.45,
+                          8.52567e-13 -16 17.45,
+                          3.74965 -14.9953 17.45,
+                          6.4953 -4.75035 17.45,
+                          -6.4953 -4.75035 17.45,
+                          -7.5 -8.5 17.45,
+                          3.74965 -2.0047 17.45,
+                          -3.74965 -2.0047 17.45,
+                          -6.4953 -4.75035 17.45,
+                          6.4953 -4.75035 17.45,
+                          3.74965 -2.0047 17.45,
+                          -6.4953 -4.75035 17.45,
+                          3.74965 -2.0047 17.45,
+                          8.4933e-13 -1 17.45,
+                          -3.74965 -2.0047 17.45 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -3.38302e-16 1 2.37421e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          1 3.38302e-16 -4.92384e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          -1 -3.38302e-16 4.92384e-14,
+                          -1 -3.38302e-16 4.92384e-14,
+                          -1 -3.38302e-16 4.92384e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          -1 -3.38302e-16 4.92384e-14,
+                          -1 -3.38302e-16 4.92384e-14,
+                          -1 -3.38302e-16 4.92384e-14,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -3.38302e-16 1 2.37421e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -3.38302e-16 1 2.37421e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -1.54611e-16 1 2.37421e-14,
+                          -1.54611e-16 1 2.37421e-14,
+                          -0.707107 0.707107 5.1605e-14,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -0.707107 0.707107 5.1605e-14,
+                          -0.707107 0.707107 5.1605e-14,
+                          -1 -9.33808e-17 4.92384e-14,
+                          -1.54611e-16 1 2.37421e-14,
+                          -0.707107 0.707107 5.1605e-14,
+                          -0.707107 0.707107 5.1605e-14,
+                          -1 -9.33808e-17 4.92384e-14,
+                          -1 -9.33808e-17 4.92384e-14,
+                          -0.707107 -0.707107 1.80286e-14,
+                          -0.707107 0.707107 5.1605e-14,
+                          -1 -9.33808e-17 4.92384e-14,
+                          -1 -9.33808e-17 4.92384e-14,
+                          -0.707107 -0.707107 1.80286e-14,
+                          -0.707107 -0.707107 1.80286e-14,
+                          3.21505e-17 -1 -2.37421e-14,
+                          -1 -9.33808e-17 4.92384e-14,
+                          -0.707107 -0.707107 1.80286e-14,
+                          -0.707107 -0.707107 1.80286e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          -0.707107 -0.707107 1.80286e-14,
+                          3.21505e-17 -1 -2.37421e-14,
+                          3.21505e-17 -1 -2.37421e-14,
+                          -1 -3.38302e-16 4.92384e-14,
+                          -1 -3.38302e-16 4.92384e-14,
+                          -1 -3.38302e-16 4.92384e-14,
+                          -1 -3.38302e-16 4.92384e-14,
+                          -1 -3.38302e-16 4.92384e-14,
+                          -1 -3.38302e-16 4.92384e-14,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          3.38302e-16 -1 -2.37421e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          1 3.38302e-16 -4.92384e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          3.38302e-16 -1 -2.37421e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          3.38302e-16 -1 -2.37421e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          3.38302e-16 -1 -2.37421e-14,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          2.77072e-16 -1 -2.37421e-14,
+                          2.77072e-16 -1 -2.37421e-14,
+                          0.707107 -0.707107 -5.1605e-14,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          0.707107 -0.707107 -5.1605e-14,
+                          0.707107 -0.707107 -5.1605e-14,
+                          1 2.15841e-16 -4.92384e-14,
+                          2.77072e-16 -1 -2.37421e-14,
+                          0.707107 -0.707107 -5.1605e-14,
+                          0.707107 -0.707107 -5.1605e-14,
+                          1 2.15841e-16 -4.92384e-14,
+                          1 2.15841e-16 -4.92384e-14,
+                          0.707107 0.707107 -1.80286e-14,
+                          0.707107 -0.707107 -5.1605e-14,
+                          1 2.15841e-16 -4.92384e-14,
+                          1 2.15841e-16 -4.92384e-14,
+                          0.707107 0.707107 -1.80286e-14,
+                          0.707107 0.707107 -1.80286e-14,
+                          -1.54611e-16 1 2.37421e-14,
+                          1 2.15841e-16 -4.92384e-14,
+                          0.707107 0.707107 -1.80286e-14,
+                          0.707107 0.707107 -1.80286e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          -3.38302e-16 1 2.37421e-14,
+                          0.707107 0.707107 -1.80286e-14,
+                          -1.54611e-16 1 2.37421e-14,
+                          -1.54611e-16 1 2.37421e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          1 3.38302e-16 -4.92384e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          0.900969 0.433884 -3.4061e-14,
+                          0.900969 -0.433884 -5.46636e-14,
+                          0.900969 -0.433884 -5.46636e-14,
+                          1 9.33808e-17 -4.92384e-14,
+                          0.900969 -0.433884 -5.46636e-14,
+                          1 9.33808e-17 -4.92384e-14,
+                          1 9.33808e-17 -4.92384e-14,
+                          0.900969 0.433884 -3.4061e-14,
+                          0.900969 0.433884 -3.4061e-14,
+                          0.62349 0.781832 -1.21373e-14,
+                          0.900969 0.433884 -3.4061e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          0.900969 0.433884 -3.4061e-14,
+                          0.62349 0.781832 -1.21373e-14,
+                          0.62349 0.781832 -1.21373e-14,
+                          0.222521 0.974928 1.21902e-14,
+                          0.900969 0.433884 -3.4061e-14,
+                          0.62349 0.781832 -1.21373e-14,
+                          0.62349 0.781832 -1.21373e-14,
+                          0.222521 0.974928 1.21902e-14,
+                          0.222521 0.974928 1.21902e-14,
+                          -0.222521 0.974928 3.41034e-14,
+                          0.62349 0.781832 -1.21373e-14,
+                          0.222521 0.974928 1.21902e-14,
+                          0.222521 0.974928 1.21902e-14,
+                          -0.222521 0.974928 3.41034e-14,
+                          -0.222521 0.974928 3.41034e-14,
+                          -0.62349 0.781832 4.92619e-14,
+                          0.222521 0.974928 1.21902e-14,
+                          -0.222521 0.974928 3.41034e-14,
+                          -0.222521 0.974928 3.41034e-14,
+                          -0.62349 0.781832 4.92619e-14,
+                          -0.62349 0.781832 4.92619e-14,
+                          -0.900969 0.433884 5.46636e-14,
+                          -0.222521 0.974928 3.41034e-14,
+                          -0.62349 0.781832 4.92619e-14,
+                          -0.62349 0.781832 4.92619e-14,
+                          -0.900969 0.433884 5.46636e-14,
+                          -0.900969 0.433884 5.46636e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -0.62349 0.781832 4.92619e-14,
+                          -0.900969 0.433884 5.46636e-14,
+                          -0.900969 0.433884 5.46636e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -0.900969 -0.433884 3.4061e-14,
+                          -0.900969 0.433884 5.46636e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -0.900969 -0.433884 3.4061e-14,
+                          -0.900969 -0.433884 3.4061e-14,
+                          -0.62349 -0.781832 1.21373e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -0.900969 -0.433884 3.4061e-14,
+                          -0.900969 -0.433884 3.4061e-14,
+                          -0.62349 -0.781832 1.21373e-14,
+                          -0.62349 -0.781832 1.21373e-14,
+                          -0.222521 -0.974928 -1.21902e-14,
+                          -0.900969 -0.433884 3.4061e-14,
+                          -0.62349 -0.781832 1.21373e-14,
+                          -0.62349 -0.781832 1.21373e-14,
+                          -0.222521 -0.974928 -1.21902e-14,
+                          -0.222521 -0.974928 -1.21902e-14,
+                          0.222521 -0.974928 -3.41034e-14,
+                          -0.62349 -0.781832 1.21373e-14,
+                          -0.222521 -0.974928 -1.21902e-14,
+                          -0.222521 -0.974928 -1.21902e-14,
+                          0.222521 -0.974928 -3.41034e-14,
+                          0.222521 -0.974928 -3.41034e-14,
+                          0.62349 -0.781832 -4.92619e-14,
+                          -0.222521 -0.974928 -1.21902e-14,
+                          0.222521 -0.974928 -3.41034e-14,
+                          0.222521 -0.974928 -3.41034e-14,
+                          0.62349 -0.781832 -4.92619e-14,
+                          0.62349 -0.781832 -4.92619e-14,
+                          0.900969 -0.433884 -5.46636e-14,
+                          0.222521 -0.974928 -3.41034e-14,
+                          0.62349 -0.781832 -4.92619e-14,
+                          0.62349 -0.781832 -4.92619e-14,
+                          0.62349 -0.781832 -4.92619e-14,
+                          0.900969 -0.433884 -5.46636e-14,
+                          0.900969 -0.433884 -5.46636e-14,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          1 3.38302e-16 -4.92384e-14,
+                          1 2.15841e-16 -4.92384e-14,
+                          0.866025 0.5 -3.07707e-14,
+                          0.866025 -0.5 -5.45127e-14,
+                          0.866025 -0.5 -5.45127e-14,
+                          1 9.33808e-17 -4.92384e-14,
+                          0.866025 -0.5 -5.45127e-14,
+                          1 9.33808e-17 -4.92384e-14,
+                          1 9.33808e-17 -4.92384e-14,
+                          0.866025 0.5 -3.07707e-14,
+                          0.866025 0.5 -3.07707e-14,
+                          0.5 0.866025 -4.05797e-15,
+                          0.866025 0.5 -3.07707e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          0.866025 0.5 -3.07707e-14,
+                          0.5 0.866025 -4.05797e-15,
+                          0.5 0.866025 -4.05797e-15,
+                          -2.77072e-16 1 2.37421e-14,
+                          0.5 0.866025 -4.05797e-15,
+                          0.866025 0.5 -3.07707e-14,
+                          0.5 0.866025 -4.05797e-15,
+                          -5.50271e-17 1 2.37421e-14,
+                          -2.77072e-16 1 2.37421e-14,
+                          -0.5 0.866025 4.51804e-14,
+                          -5.50271e-17 1 2.37421e-14,
+                          0.5 0.866025 -4.05797e-15,
+                          -2.77072e-16 1 2.37421e-14,
+                          -0.5 0.866025 4.51804e-14,
+                          -0.5 0.866025 4.51804e-14,
+                          -0.866025 0.5 5.45127e-14,
+                          -0.5 0.866025 4.51804e-14,
+                          -5.50271e-17 1 2.37421e-14,
+                          -0.5 0.866025 4.51804e-14,
+                          -0.866025 0.5 5.45127e-14,
+                          -0.866025 0.5 5.45127e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -0.866025 0.5 5.45127e-14,
+                          -0.5 0.866025 4.51804e-14,
+                          -0.866025 0.5 5.45127e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -0.866025 -0.5 3.07707e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -0.866025 0.5 5.45127e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -0.866025 -0.5 3.07707e-14,
+                          -0.866025 -0.5 3.07707e-14,
+                          -0.5 -0.866025 4.05797e-15,
+                          -0.866025 -0.5 3.07707e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -0.866025 -0.5 3.07707e-14,
+                          -0.5 -0.866025 4.05797e-15,
+                          -0.5 -0.866025 4.05797e-15,
+                          1.54611e-16 -1 -2.37421e-14,
+                          -0.5 -0.866025 4.05797e-15,
+                          -0.866025 -0.5 3.07707e-14,
+                          -0.5 -0.866025 4.05797e-15,
+                          1.54611e-16 -1 -2.37421e-14,
+                          1.54611e-16 -1 -2.37421e-14,
+                          0.5 -0.866025 -4.51804e-14,
+                          1.54611e-16 -1 -2.37421e-14,
+                          -0.5 -0.866025 4.05797e-15,
+                          1.54611e-16 -1 -2.37421e-14,
+                          0.5 -0.866025 -4.51804e-14,
+                          0.5 -0.866025 -4.51804e-14,
+                          0.866025 -0.5 -5.45127e-14,
+                          0.5 -0.866025 -4.51804e-14,
+                          1.54611e-16 -1 -2.37421e-14,
+                          0.5 -0.866025 -4.51804e-14,
+                          0.866025 -0.5 -5.45127e-14,
+                          0.5 -0.866025 -4.51804e-14,
+                          0.866025 -0.5 -5.45127e-14,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          1 3.38302e-16 -4.92384e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          0.866025 0.5 -3.07707e-14,
+                          0.866025 -0.5 -5.45127e-14,
+                          0.866025 -0.5 -5.45127e-14,
+                          1 9.33808e-17 -4.92384e-14,
+                          0.866025 -0.5 -5.45127e-14,
+                          1 9.33808e-17 -4.92384e-14,
+                          1 9.33808e-17 -4.92384e-14,
+                          0.866025 0.5 -3.07707e-14,
+                          0.866025 0.5 -3.07707e-14,
+                          0.5 0.866025 -4.05797e-15,
+                          0.866025 0.5 -3.07707e-14,
+                          1 3.38302e-16 -4.92384e-14,
+                          0.866025 0.5 -3.07707e-14,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          0.5 0.866025 -4.05797e-15,
+                          0.5 0.866025 -4.05797e-15,
+                          -2.77072e-16 1 2.37421e-14,
+                          0.866025 0.5 -3.07707e-14,
+                          0.5 0.866025 -4.05797e-15,
+                          0.5 0.866025 -4.05797e-15,
+                          -2.77072e-16 1 2.37421e-14,
+                          -2.77072e-16 1 2.37421e-14,
+                          -0.5 0.866025 4.51804e-14,
+                          0.5 0.866025 -4.05797e-15,
+                          -2.77072e-16 1 2.37421e-14,
+                          -2.77072e-16 1 2.37421e-14,
+                          -0.5 0.866025 4.51804e-14,
+                          -0.5 0.866025 4.51804e-14,
+                          -0.866025 0.5 5.45127e-14,
+                          -2.77072e-16 1 2.37421e-14,
+                          -0.5 0.866025 4.51804e-14,
+                          -0.5 0.866025 4.51804e-14,
+                          -0.866025 0.5 5.45127e-14,
+                          -0.866025 0.5 5.45127e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -0.5 0.866025 4.51804e-14,
+                          -0.866025 0.5 5.45127e-14,
+                          -0.866025 0.5 5.45127e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -0.866025 -0.5 3.07707e-14,
+                          -0.866025 0.5 5.45127e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -0.866025 -0.5 3.07707e-14,
+                          -0.866025 -0.5 3.07707e-14,
+                          -0.5 -0.866025 4.05797e-15,
+                          -1 -2.15841e-16 4.92384e-14,
+                          -0.866025 -0.5 3.07707e-14,
+                          -0.866025 -0.5 3.07707e-14,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -4.92384e-14 2.37421e-14 -1,
+                          -0.5 -0.866025 4.05797e-15,
+                          -0.5 -0.866025 4.05797e-15,
+                          1.54611e-16 -1 -2.37421e-14,
+                          -0.866025 -0.5 3.07707e-14,
+                          -0.5 -0.866025 4.05797e-15,
+                          -0.5 -0.866025 4.05797e-15,
+                          1.54611e-16 -1 -2.37421e-14,
+                          1.54611e-16 -1 -2.37421e-14,
+                          0.5 -0.866025 -4.51804e-14,
+                          -0.5 -0.866025 4.05797e-15,
+                          1.54611e-16 -1 -2.37421e-14,
+                          1.54611e-16 -1 -2.37421e-14,
+                          0.5 -0.866025 -4.51804e-14,
+                          0.5 -0.866025 -4.51804e-14,
+                          0.866025 -0.5 -5.45127e-14,
+                          1.54611e-16 -1 -2.37421e-14,
+                          0.5 -0.866025 -4.51804e-14,
+                          0.5 -0.866025 -4.51804e-14,
+                          0.5 -0.866025 -4.51804e-14,
+                          0.866025 -0.5 -5.45127e-14,
+                          0.866025 -0.5 -5.45127e-14,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1,
+                          4.92384e-14 -2.37421e-14 1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -8.3 10.1 -3.35,
+                          -8.3 16.4 -3.35,
+                          8.3 16.4 -3.35,
+                          8.3 16.4 3.35,
+                          8.3 16.4 -3.35,
+                          -8.3 16.4 -3.35,
+                          -8.3 6.1 -3.35,
+                          -8.3 10.1 -3.35,
+                          8.3 16.4 -3.35,
+                          -8.3 -0.2 -3.35,
+                          -8.3 6.1 -3.35,
+                          8.3 16.4 -3.35,
+                          8.3 10.1 -3.35,
+                          -8.3 -0.2 -3.35,
+                          8.3 16.4 -3.35,
+                          8.3 16.4 3.35,
+                          8.3 10.1 -3.35,
+                          8.3 16.4 -3.35,
+                          -8.3 10.1 3.35,
+                          -8.3 16.4 -3.35,
+                          -8.3 10.1 -3.35,
+                          -8.3 16.4 3.35,
+                          8.3 16.4 3.35,
+                          -8.3 16.4 -3.35,
+                          -8.3 16.4 3.35,
+                          -8.3 16.4 -3.35,
+                          -8.3 10.1 3.35,
+                          -10.6 6.1 -3.35,
+                          -10.6 10.1 -3.35,
+                          -8.3 10.1 -3.35,
+                          -10.6 10.1 3.35,
+                          -8.3 10.1 -3.35,
+                          -10.6 10.1 -3.35,
+                          -8.3 6.1 -3.35,
+                          -10.6 6.1 -3.35,
+                          -8.3 10.1 -3.35,
+                          -8.3 10.1 3.35,
+                          -8.3 10.1 -3.35,
+                          -10.6 10.1 3.35,
+                          -12.0141 6.68587 -3.35,
+                          -12.0141 9.51413 -3.35,
+                          -10.6 10.1 -3.35,
+                          -10.6 10.1 3.35,
+                          -10.6 10.1 -3.35,
+                          -12.0141 9.51413 -3.35,
+                          -10.6 6.1 -3.35,
+                          -12.0141 6.68587 -3.35,
+                          -10.6 10.1 -3.35,
+                          -12.0141 6.68587 -3.35,
+                          -12.6 8.1 -3.35,
+                          -12.0141 9.51413 -3.35,
+                          -12.0141 9.51413 3.35,
+                          -12.0141 9.51413 -3.35,
+                          -12.6 8.1 -3.35,
+                          -10.6 10.1 3.35,
+                          -12.0141 9.51413 -3.35,
+                          -12.0141 9.51413 3.35,
+                          -12.6 8.1 3.35,
+                          -12.6 8.1 -3.35,
+                          -12.0141 6.68587 -3.35,
+                          -12.0141 9.51413 3.35,
+                          -12.6 8.1 -3.35,
+                          -12.6 8.1 3.35,
+                          -12.0141 6.68587 3.35,
+                          -12.0141 6.68587 -3.35,
+                          -10.6 6.1 -3.35,
+                          -12.6 8.1 3.35,
+                          -12.0141 6.68587 -3.35,
+                          -12.0141 6.68587 3.35,
+                          -8.3 6.1 3.35,
+                          -10.6 6.1 -3.35,
+                          -8.3 6.1 -3.35,
+                          -10.6 6.1 3.35,
+                          -10.6 6.1 -3.35,
+                          -8.3 6.1 3.35,
+                          -12.0141 6.68587 3.35,
+                          -10.6 6.1 -3.35,
+                          -10.6 6.1 3.35,
+                          -8.3 -0.2 3.35,
+                          -8.3 6.1 -3.35,
+                          -8.3 -0.2 -3.35,
+                          -8.3 6.1 3.35,
+                          -8.3 6.1 -3.35,
+                          -8.3 -0.2 3.35,
+                          8.3 6.1 -3.35,
+                          8.3 -0.2 -3.35,
+                          -8.3 -0.2 -3.35,
+                          -8.3 -0.2 3.35,
+                          -8.3 -0.2 -3.35,
+                          8.3 -0.2 -3.35,
+                          8.3 10.1 -3.35,
+                          8.3 6.1 -3.35,
+                          -8.3 -0.2 -3.35,
+                          8.3 6.1 3.35,
+                          8.3 -0.2 -3.35,
+                          8.3 6.1 -3.35,
+                          8.3 -0.2 3.35,
+                          8.3 -0.2 -3.35,
+                          8.3 6.1 3.35,
+                          -8.3 -0.2 3.35,
+                          8.3 -0.2 -3.35,
+                          8.3 -0.2 3.35,
+                          10.6 10.1 -3.35,
+                          10.6 6.1 -3.35,
+                          8.3 6.1 -3.35,
+                          10.6 6.1 3.35,
+                          8.3 6.1 -3.35,
+                          10.6 6.1 -3.35,
+                          8.3 10.1 -3.35,
+                          10.6 10.1 -3.35,
+                          8.3 6.1 -3.35,
+                          8.3 6.1 3.35,
+                          8.3 6.1 -3.35,
+                          10.6 6.1 3.35,
+                          12.0141 9.51413 -3.35,
+                          12.0141 6.68587 -3.35,
+                          10.6 6.1 -3.35,
+                          10.6 6.1 3.35,
+                          10.6 6.1 -3.35,
+                          12.0141 6.68587 -3.35,
+                          10.6 10.1 -3.35,
+                          12.0141 9.51413 -3.35,
+                          10.6 6.1 -3.35,
+                          12.0141 9.51413 -3.35,
+                          12.6 8.1 -3.35,
+                          12.0141 6.68587 -3.35,
+                          12.0141 6.68587 3.35,
+                          12.0141 6.68587 -3.35,
+                          12.6 8.1 -3.35,
+                          10.6 6.1 3.35,
+                          12.0141 6.68587 -3.35,
+                          12.0141 6.68587 3.35,
+                          12.6 8.1 3.35,
+                          12.6 8.1 -3.35,
+                          12.0141 9.51413 -3.35,
+                          12.0141 6.68587 3.35,
+                          12.6 8.1 -3.35,
+                          12.6 8.1 3.35,
+                          12.0141 9.51413 3.35,
+                          12.0141 9.51413 -3.35,
+                          10.6 10.1 -3.35,
+                          12.6 8.1 3.35,
+                          12.0141 9.51413 -3.35,
+                          12.0141 9.51413 3.35,
+                          8.3 10.1 3.35,
+                          10.6 10.1 -3.35,
+                          8.3 10.1 -3.35,
+                          10.6 10.1 3.35,
+                          10.6 10.1 -3.35,
+                          8.3 10.1 3.35,
+                          12.0141 9.51413 3.35,
+                          10.6 10.1 -3.35,
+                          10.6 10.1 3.35,
+                          8.3 10.1 3.35,
+                          8.3 10.1 -3.35,
+                          8.3 16.4 3.35,
+                          7.20788 11.5708 3.35,
+                          8.3 10.1 3.35,
+                          8.3 16.4 3.35,
+                          1.78028 15.8993 3.35,
+                          8.3 16.4 3.35,
+                          -8.3 16.4 3.35,
+                          4.98815 14.3544 3.35,
+                          7.20788 11.5708 3.35,
+                          8.3 16.4 3.35,
+                          1.78028 15.8993 3.35,
+                          4.98815 14.3544 3.35,
+                          8.3 16.4 3.35,
+                          10.6 6.1 3.35,
+                          10.6 10.1 3.35,
+                          8.3 10.1 3.35,
+                          8.3 6.1 3.35,
+                          10.6 6.1 3.35,
+                          8.3 10.1 3.35,
+                          8 8.1 3.35,
+                          8.3 6.1 3.35,
+                          8.3 10.1 3.35,
+                          7.20788 11.5708 3.35,
+                          8 8.1 3.35,
+                          8.3 10.1 3.35,
+                          12.0141 6.68587 3.35,
+                          12.0141 9.51413 3.35,
+                          10.6 10.1 3.35,
+                          10.6 6.1 3.35,
+                          12.0141 6.68587 3.35,
+                          10.6 10.1 3.35,
+                          12.0141 6.68587 3.35,
+                          12.6 8.1 3.35,
+                          12.0141 9.51413 3.35,
+                          8 8.1 3.35,
+                          8.3 -0.2 3.35,
+                          8.3 6.1 3.35,
+                          -1.78028 0.30068 3.35,
+                          -8.3 -0.2 3.35,
+                          8.3 -0.2 3.35,
+                          7.20788 4.62924 3.35,
+                          8.3 -0.2 3.35,
+                          8 8.1 3.35,
+                          1.78028 0.30068 3.35,
+                          -1.78028 0.30068 3.35,
+                          8.3 -0.2 3.35,
+                          4.98815 1.8456 3.35,
+                          1.78028 0.30068 3.35,
+                          8.3 -0.2 3.35,
+                          7.20788 4.62924 3.35,
+                          4.98815 1.8456 3.35,
+                          8.3 -0.2 3.35,
+                          -7.20788 4.62924 3.35,
+                          -8.3 6.1 3.35,
+                          -8.3 -0.2 3.35,
+                          -4.98815 1.8456 3.35,
+                          -7.20788 4.62924 3.35,
+                          -8.3 -0.2 3.35,
+                          -1.78028 0.30068 3.35,
+                          -4.98815 1.8456 3.35,
+                          -8.3 -0.2 3.35,
+                          -10.6 10.1 3.35,
+                          -10.6 6.1 3.35,
+                          -8.3 6.1 3.35,
+                          -8.3 10.1 3.35,
+                          -10.6 10.1 3.35,
+                          -8.3 6.1 3.35,
+                          -8 8.1 3.35,
+                          -8.3 10.1 3.35,
+                          -8.3 6.1 3.35,
+                          -7.20788 4.62924 3.35,
+                          -8 8.1 3.35,
+                          -8.3 6.1 3.35,
+                          -12.0141 9.51413 3.35,
+                          -12.0141 6.68587 3.35,
+                          -10.6 6.1 3.35,
+                          -10.6 10.1 3.35,
+                          -12.0141 9.51413 3.35,
+                          -10.6 6.1 3.35,
+                          -12.0141 9.51413 3.35,
+                          -12.6 8.1 3.35,
+                          -12.0141 6.68587 3.35,
+                          -8 8.1 3.35,
+                          -8.3 16.4 3.35,
+                          -8.3 10.1 3.35,
+                          -1.78028 15.8993 3.35,
+                          1.78028 15.8993 3.35,
+                          -8.3 16.4 3.35,
+                          -4.98815 14.3544 3.35,
+                          -1.78028 15.8993 3.35,
+                          -8.3 16.4 3.35,
+                          -7.20788 11.5708 3.35,
+                          -4.98815 14.3544 3.35,
+                          -8.3 16.4 3.35,
+                          -8 8.1 3.35,
+                          -7.20788 11.5708 3.35,
+                          -8.3 16.4 3.35,
+                          8 8.1 12.35,
+                          8 8.1 3.35,
+                          7.20788 11.5708 3.35,
+                          7.20775 4.62893 12.35,
+                          7.20788 4.62924 3.35,
+                          8 8.1 3.35,
+                          7.20775 4.62893 12.35,
+                          8 8.1 3.35,
+                          8 8.1 12.35,
+                          7.20775 11.5711 12.35,
+                          7.20788 11.5708 3.35,
+                          4.98815 14.3544 3.35,
+                          7.20775 11.5711 12.35,
+                          8 8.1 12.35,
+                          7.20788 11.5708 3.35,
+                          4.98792 14.3547 12.35,
+                          4.98815 14.3544 3.35,
+                          1.78028 15.8993 3.35,
+                          7.20775 11.5711 12.35,
+                          4.98815 14.3544 3.35,
+                          4.98792 14.3547 12.35,
+                          1.78017 15.8994 12.35,
+                          1.78028 15.8993 3.35,
+                          -1.78028 15.8993 3.35,
+                          4.98792 14.3547 12.35,
+                          1.78028 15.8993 3.35,
+                          1.78017 15.8994 12.35,
+                          -1.78017 15.8994 12.35,
+                          -1.78028 15.8993 3.35,
+                          -4.98815 14.3544 3.35,
+                          1.78017 15.8994 12.35,
+                          -1.78028 15.8993 3.35,
+                          -1.78017 15.8994 12.35,
+                          -4.98792 14.3547 12.35,
+                          -4.98815 14.3544 3.35,
+                          -7.20788 11.5708 3.35,
+                          -1.78017 15.8994 12.35,
+                          -4.98815 14.3544 3.35,
+                          -4.98792 14.3547 12.35,
+                          -7.20775 11.5711 12.35,
+                          -7.20788 11.5708 3.35,
+                          -8 8.1 3.35,
+                          -4.98792 14.3547 12.35,
+                          -7.20788 11.5708 3.35,
+                          -7.20775 11.5711 12.35,
+                          -8 8.1 12.35,
+                          -8 8.1 3.35,
+                          -7.20788 4.62924 3.35,
+                          -7.20775 11.5711 12.35,
+                          -8 8.1 3.35,
+                          -8 8.1 12.35,
+                          -7.20775 4.62893 12.35,
+                          -7.20788 4.62924 3.35,
+                          -4.98815 1.8456 3.35,
+                          -8 8.1 12.35,
+                          -7.20788 4.62924 3.35,
+                          -7.20775 4.62893 12.35,
+                          -4.98792 1.84535 12.35,
+                          -4.98815 1.8456 3.35,
+                          -1.78028 0.30068 3.35,
+                          -7.20775 4.62893 12.35,
+                          -4.98815 1.8456 3.35,
+                          -4.98792 1.84535 12.35,
+                          -1.78017 0.300577 12.35,
+                          -1.78028 0.30068 3.35,
+                          1.78028 0.30068 3.35,
+                          -4.98792 1.84535 12.35,
+                          -1.78028 0.30068 3.35,
+                          -1.78017 0.300577 12.35,
+                          1.78017 0.300577 12.35,
+                          1.78028 0.30068 3.35,
+                          4.98815 1.8456 3.35,
+                          -1.78017 0.300577 12.35,
+                          1.78028 0.30068 3.35,
+                          1.78017 0.300577 12.35,
+                          4.98792 1.84535 12.35,
+                          4.98815 1.8456 3.35,
+                          7.20788 4.62924 3.35,
+                          1.78017 0.300577 12.35,
+                          4.98815 1.8456 3.35,
+                          4.98792 1.84535 12.35,
+                          4.98792 1.84535 12.35,
+                          7.20788 4.62924 3.35,
+                          7.20775 4.62893 12.35,
+                          5.19624 5.10028 12.35,
+                          7.20775 4.62893 12.35,
+                          8 8.1 12.35,
+                          6 8.1 12.35,
+                          8 8.1 12.35,
+                          7.20775 11.5711 12.35,
+                          5.19624 5.10028 12.35,
+                          8 8.1 12.35,
+                          6 8.1 12.35,
+                          2.99972 2.90376 12.35,
+                          4.98792 1.84535 12.35,
+                          7.20775 4.62893 12.35,
+                          5.19624 5.10028 12.35,
+                          2.99972 2.90376 12.35,
+                          7.20775 4.62893 12.35,
+                          -1.78017 0.300577 12.35,
+                          1.78017 0.300577 12.35,
+                          4.98792 1.84535 12.35,
+                          -4.98792 1.84535 12.35,
+                          -1.78017 0.300577 12.35,
+                          4.98792 1.84535 12.35,
+                          6.08325e-13 2.1 12.35,
+                          -4.98792 1.84535 12.35,
+                          4.98792 1.84535 12.35,
+                          2.99972 2.90376 12.35,
+                          6.08325e-13 2.1 12.35,
+                          4.98792 1.84535 12.35,
+                          -2.99972 2.90376 12.35,
+                          -7.20775 4.62893 12.35,
+                          -4.98792 1.84535 12.35,
+                          6.08325e-13 2.1 12.35,
+                          -2.99972 2.90376 12.35,
+                          -4.98792 1.84535 12.35,
+                          -6 8.1 12.35,
+                          -8 8.1 12.35,
+                          -7.20775 4.62893 12.35,
+                          -5.19624 5.10028 12.35,
+                          -6 8.1 12.35,
+                          -7.20775 4.62893 12.35,
+                          -2.99972 2.90376 12.35,
+                          -5.19624 5.10028 12.35,
+                          -7.20775 4.62893 12.35,
+                          -5.19624 11.0997 12.35,
+                          -7.20775 11.5711 12.35,
+                          -8 8.1 12.35,
+                          -6 8.1 12.35,
+                          -5.19624 11.0997 12.35,
+                          -8 8.1 12.35,
+                          -2.99972 13.2962 12.35,
+                          -4.98792 14.3547 12.35,
+                          -7.20775 11.5711 12.35,
+                          -5.19624 11.0997 12.35,
+                          -2.99972 13.2962 12.35,
+                          -7.20775 11.5711 12.35,
+                          1.78017 15.8994 12.35,
+                          -1.78017 15.8994 12.35,
+                          -4.98792 14.3547 12.35,
+                          4.98792 14.3547 12.35,
+                          1.78017 15.8994 12.35,
+                          -4.98792 14.3547 12.35,
+                          6.05735e-13 14.1 12.35,
+                          4.98792 14.3547 12.35,
+                          -4.98792 14.3547 12.35,
+                          -2.99972 13.2962 12.35,
+                          6.05735e-13 14.1 12.35,
+                          -4.98792 14.3547 12.35,
+                          2.99972 13.2962 12.35,
+                          7.20775 11.5711 12.35,
+                          4.98792 14.3547 12.35,
+                          6.05735e-13 14.1 12.35,
+                          2.99972 13.2962 12.35,
+                          4.98792 14.3547 12.35,
+                          5.19624 11.0997 12.35,
+                          6 8.1 12.35,
+                          7.20775 11.5711 12.35,
+                          2.99972 13.2962 12.35,
+                          5.19624 11.0997 12.35,
+                          7.20775 11.5711 12.35,
+                          6 8.1 14.15,
+                          6 8.1 12.35,
+                          5.19624 11.0997 12.35,
+                          5.19624 5.10028 14.15,
+                          5.19624 5.10028 12.35,
+                          6 8.1 12.35,
+                          5.19624 5.10028 14.15,
+                          6 8.1 12.35,
+                          6 8.1 14.15,
+                          5.19624 11.0997 14.15,
+                          5.19624 11.0997 12.35,
+                          2.99972 13.2962 12.35,
+                          5.19624 11.0997 14.15,
+                          6 8.1 14.15,
+                          5.19624 11.0997 12.35,
+                          2.99972 13.2962 14.15,
+                          2.99972 13.2962 12.35,
+                          6.05735e-13 14.1 12.35,
+                          2.99972 13.2962 14.15,
+                          5.19624 11.0997 14.15,
+                          2.99972 13.2962 12.35,
+                          6.95696e-13 14.1 14.15,
+                          6.05735e-13 14.1 12.35,
+                          -2.99972 13.2962 12.35,
+                          6.95696e-13 14.1 14.15,
+                          2.99972 13.2962 14.15,
+                          6.05735e-13 14.1 12.35,
+                          -2.99972 13.2962 14.15,
+                          -2.99972 13.2962 12.35,
+                          -5.19624 11.0997 12.35,
+                          -2.99972 13.2962 14.15,
+                          6.95696e-13 14.1 14.15,
+                          -2.99972 13.2962 12.35,
+                          -5.19624 11.0997 14.15,
+                          -5.19624 11.0997 12.35,
+                          -6 8.1 12.35,
+                          -5.19624 11.0997 14.15,
+                          -2.99972 13.2962 14.15,
+                          -5.19624 11.0997 12.35,
+                          -6 8.1 14.15,
+                          -6 8.1 12.35,
+                          -5.19624 5.10028 12.35,
+                          -6 8.1 14.15,
+                          -5.19624 11.0997 14.15,
+                          -6 8.1 12.35,
+                          -5.19624 5.10028 14.15,
+                          -5.19624 5.10028 12.35,
+                          -2.99972 2.90376 12.35,
+                          -5.19624 5.10028 14.15,
+                          -6 8.1 14.15,
+                          -5.19624 5.10028 12.35,
+                          -2.99972 2.90376 14.15,
+                          -2.99972 2.90376 12.35,
+                          6.08325e-13 2.1 12.35,
+                          -2.99972 2.90376 14.15,
+                          -5.19624 5.10028 14.15,
+                          -2.99972 2.90376 12.35,
+                          6.96954e-13 2.1 14.15,
+                          6.08325e-13 2.1 12.35,
+                          2.99972 2.90376 12.35,
+                          6.96954e-13 2.1 14.15,
+                          -2.99972 2.90376 14.15,
+                          6.08325e-13 2.1 12.35,
+                          2.99972 2.90376 14.15,
+                          2.99972 2.90376 12.35,
+                          5.19624 5.10028 12.35,
+                          2.99972 2.90376 14.15,
+                          6.96954e-13 2.1 14.15,
+                          2.99972 2.90376 12.35,
+                          5.19624 5.10028 14.15,
+                          2.99972 2.90376 14.15,
+                          5.19624 5.10028 12.35,
+                          7.5 8.1 14.15,
+                          6 8.1 14.15,
+                          5.19624 11.0997 14.15,
+                          6.4953 4.35035 14.15,
+                          5.19624 5.10028 14.15,
+                          6 8.1 14.15,
+                          6.4953 4.35035 14.15,
+                          6 8.1 14.15,
+                          7.5 8.1 14.15,
+                          6.4953 11.8496 14.15,
+                          5.19624 11.0997 14.15,
+                          2.99972 13.2962 14.15,
+                          6.4953 11.8496 14.15,
+                          7.5 8.1 14.15,
+                          5.19624 11.0997 14.15,
+                          3.74965 14.5953 14.15,
+                          2.99972 13.2962 14.15,
+                          6.95696e-13 14.1 14.15,
+                          3.74965 14.5953 14.15,
+                          6.4953 11.8496 14.15,
+                          2.99972 13.2962 14.15,
+                          -3.74965 14.5953 14.15,
+                          6.95696e-13 14.1 14.15,
+                          -2.99972 13.2962 14.15,
+                          -3.74965 14.5953 14.15,
+                          3.74965 14.5953 14.15,
+                          6.95696e-13 14.1 14.15,
+                          -6.4953 11.8496 14.15,
+                          -2.99972 13.2962 14.15,
+                          -5.19624 11.0997 14.15,
+                          -6.4953 11.8496 14.15,
+                          -3.74965 14.5953 14.15,
+                          -2.99972 13.2962 14.15,
+                          -6.4953 11.8496 14.15,
+                          -5.19624 11.0997 14.15,
+                          -6 8.1 14.15,
+                          -7.5 8.1 14.15,
+                          -6 8.1 14.15,
+                          -5.19624 5.10028 14.15,
+                          -7.5 8.1 14.15,
+                          -6.4953 11.8496 14.15,
+                          -6 8.1 14.15,
+                          -6.4953 4.35035 14.15,
+                          -5.19624 5.10028 14.15,
+                          -2.99972 2.90376 14.15,
+                          -6.4953 4.35035 14.15,
+                          -7.5 8.1 14.15,
+                          -5.19624 5.10028 14.15,
+                          -3.74965 1.6047 14.15,
+                          -2.99972 2.90376 14.15,
+                          6.96954e-13 2.1 14.15,
+                          -3.74965 1.6047 14.15,
+                          -6.4953 4.35035 14.15,
+                          -2.99972 2.90376 14.15,
+                          3.74965 1.6047 14.15,
+                          6.96954e-13 2.1 14.15,
+                          2.99972 2.90376 14.15,
+                          3.74965 1.6047 14.15,
+                          -3.74965 1.6047 14.15,
+                          6.96954e-13 2.1 14.15,
+                          6.4953 4.35035 14.15,
+                          2.99972 2.90376 14.15,
+                          5.19624 5.10028 14.15,
+                          6.4953 4.35035 14.15,
+                          3.74965 1.6047 14.15,
+                          2.99972 2.90376 14.15,
+                          7.5 8.1 17.45,
+                          7.5 8.1 14.15,
+                          6.4953 11.8496 14.15,
+                          6.4953 4.35035 17.45,
+                          6.4953 4.35035 14.15,
+                          7.5 8.1 14.15,
+                          6.4953 4.35035 17.45,
+                          7.5 8.1 14.15,
+                          7.5 8.1 17.45,
+                          6.4953 11.8496 17.45,
+                          6.4953 11.8496 14.15,
+                          3.74965 14.5953 14.15,
+                          6.4953 11.8496 17.45,
+                          7.5 8.1 17.45,
+                          6.4953 11.8496 14.15,
+                          -3.74965 14.5953 14.15,
+                          6.93949e-13 15.6 14.15,
+                          3.74965 14.5953 14.15,
+                          3.74965 14.5953 17.45,
+                          3.74965 14.5953 14.15,
+                          6.93949e-13 15.6 14.15,
+                          6.4953 11.8496 17.45,
+                          3.74965 14.5953 14.15,
+                          3.74965 14.5953 17.45,
+                          8.56435e-13 15.6 17.45,
+                          6.93949e-13 15.6 14.15,
+                          -3.74965 14.5953 14.15,
+                          3.74965 14.5953 17.45,
+                          6.93949e-13 15.6 14.15,
+                          8.56435e-13 15.6 17.45,
+                          -3.74965 14.5953 17.45,
+                          -3.74965 14.5953 14.15,
+                          -6.4953 11.8496 14.15,
+                          8.56435e-13 15.6 17.45,
+                          -3.74965 14.5953 14.15,
+                          -3.74965 14.5953 17.45,
+                          -6.4953 11.8496 17.45,
+                          -6.4953 11.8496 14.15,
+                          -7.5 8.1 14.15,
+                          -3.74965 14.5953 17.45,
+                          -6.4953 11.8496 14.15,
+                          -6.4953 11.8496 17.45,
+                          -7.5 8.1 17.45,
+                          -7.5 8.1 14.15,
+                          -6.4953 4.35035 14.15,
+                          -6.4953 11.8496 17.45,
+                          -7.5 8.1 14.15,
+                          -7.5 8.1 17.45,
+                          -6.4953 4.35035 17.45,
+                          -6.4953 4.35035 14.15,
+                          -3.74965 1.6047 14.15,
+                          -7.5 8.1 17.45,
+                          -6.4953 4.35035 14.15,
+                          -6.4953 4.35035 17.45,
+                          3.74965 1.6047 14.15,
+                          6.97186e-13 0.6 14.15,
+                          -3.74965 1.6047 14.15,
+                          -3.74965 1.6047 17.45,
+                          -3.74965 1.6047 14.15,
+                          6.97186e-13 0.6 14.15,
+                          -6.4953 4.35035 17.45,
+                          -3.74965 1.6047 14.15,
+                          -3.74965 1.6047 17.45,
+                          8.59673e-13 0.6 17.45,
+                          6.97186e-13 0.6 14.15,
+                          3.74965 1.6047 14.15,
+                          -3.74965 1.6047 17.45,
+                          6.97186e-13 0.6 14.15,
+                          8.59673e-13 0.6 17.45,
+                          3.74965 1.6047 17.45,
+                          3.74965 1.6047 14.15,
+                          6.4953 4.35035 14.15,
+                          8.59673e-13 0.6 17.45,
+                          3.74965 1.6047 14.15,
+                          3.74965 1.6047 17.45,
+                          3.74965 1.6047 17.45,
+                          6.4953 4.35035 14.15,
+                          6.4953 4.35035 17.45,
+                          -6.4953 4.35035 17.45,
+                          6.4953 4.35035 17.45,
+                          7.5 8.1 17.45,
+                          -7.5 8.1 17.45,
+                          -6.4953 4.35035 17.45,
+                          7.5 8.1 17.45,
+                          6.4953 11.8496 17.45,
+                          -7.5 8.1 17.45,
+                          7.5 8.1 17.45,
+                          -3.74965 1.6047 17.45,
+                          3.74965 1.6047 17.45,
+                          6.4953 4.35035 17.45,
+                          -6.4953 4.35035 17.45,
+                          -3.74965 1.6047 17.45,
+                          6.4953 4.35035 17.45,
+                          -3.74965 1.6047 17.45,
+                          8.59673e-13 0.6 17.45,
+                          3.74965 1.6047 17.45,
+                          6.4953 11.8496 17.45,
+                          -6.4953 11.8496 17.45,
+                          -7.5 8.1 17.45,
+                          3.74965 14.5953 17.45,
+                          -3.74965 14.5953 17.45,
+                          -6.4953 11.8496 17.45,
+                          6.4953 11.8496 17.45,
+                          3.74965 14.5953 17.45,
+                          -6.4953 11.8496 17.45,
+                          3.74965 14.5953 17.45,
+                          8.56435e-13 15.6 17.45,
+                          -3.74965 14.5953 17.45 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.985715 1 0.989286
+    }
+    Separator {
+        Normal {
+            vector      [ 0.279265 -0.960214 5.65673e-16,
+                          0.248522 -0.965926 0.0722792,
+                          6.99294e-16 -1 4.0808e-16,
+                          0.188112 -0.974754 0.120286,
+                          6.99294e-16 -1 4.0808e-16,
+                          0.248522 -0.965926 0.0722792,
+                          0.26975 -0.960214 -0.0722792,
+                          0.279265 -0.960214 6.21294e-16,
+                          8.69913e-17 -1 4.0808e-16,
+                          0.128298 -0.980711 0.147467,
+                          6.99294e-16 -1 4.0808e-16,
+                          0.188112 -0.974754 0.120286,
+                          0.0988266 -0.971507 0.215422,
+                          6.99294e-16 -1 4.0808e-16,
+                          0.128298 -0.980711 0.147467,
+                          0.0310822 -0.976337 0.214011,
+                          6.99294e-16 -1 4.0808e-16,
+                          0.0988266 -0.971507 0.215422,
+                          -0.0305244 -0.976348 0.214037,
+                          6.99294e-16 -1 4.0808e-16,
+                          0.0310822 -0.976337 0.214011,
+                          -0.0981478 -0.971581 0.215402,
+                          6.99294e-16 -1 4.0808e-16,
+                          -0.0305244 -0.976348 0.214037,
+                          -0.127563 -0.980819 0.147385,
+                          6.99294e-16 -1 4.0808e-16,
+                          -0.0981478 -0.971581 0.215402,
+                          -0.186741 -0.975042 0.120086,
+                          6.99294e-16 -1 4.0808e-16,
+                          -0.127563 -0.980819 0.147385,
+                          -0.248335 -0.965926 0.0729178,
+                          6.99294e-16 -1 4.0808e-16,
+                          -0.186741 -0.975042 0.120086,
+                          -0.279265 -0.960214 2.52214e-16,
+                          6.99294e-16 -1 4.0808e-16,
+                          -0.248335 -0.965926 0.0729178,
+                          -0.26975 -0.960214 -0.0722792,
+                          8.69913e-17 -1 4.0808e-16,
+                          -0.279265 -0.960214 2.52214e-16,
+                          0.241851 -0.960214 -0.139633,
+                          0.26975 -0.960214 -0.0722792,
+                          8.69913e-17 -1 4.0808e-16,
+                          0.19747 -0.960214 -0.19747,
+                          0.241851 -0.960214 -0.139633,
+                          8.69913e-17 -1 4.0808e-16,
+                          0.139633 -0.960214 -0.241851,
+                          0.19747 -0.960214 -0.19747,
+                          8.69913e-17 -1 4.0808e-16,
+                          0.0722792 -0.960214 -0.26975,
+                          0.139633 -0.960214 -0.241851,
+                          8.69913e-17 -1 4.0808e-16,
+                          4.38023e-16 -0.960214 -0.279265,
+                          0.0722792 -0.960214 -0.26975,
+                          8.69913e-17 -1 4.0808e-16,
+                          -0.0722792 -0.960214 -0.26975,
+                          4.38023e-16 -0.960214 -0.279265,
+                          8.69913e-17 -1 4.0808e-16,
+                          -0.139633 -0.960214 -0.241851,
+                          -0.0722792 -0.960214 -0.26975,
+                          8.69913e-17 -1 4.0808e-16,
+                          -0.19747 -0.960214 -0.19747,
+                          -0.139633 -0.960214 -0.241851,
+                          8.69913e-17 -1 4.0808e-16,
+                          -0.241851 -0.960214 -0.139633,
+                          -0.19747 -0.960214 -0.19747,
+                          8.69913e-17 -1 4.0808e-16,
+                          -0.26975 -0.960214 -0.0722792,
+                          -0.241851 -0.960214 -0.139633,
+                          8.69913e-17 -1 4.0808e-16,
+                          0.279265 -0.960214 5.65673e-16,
+                          0.480107 -0.866025 0.139633,
+                          0.248522 -0.965926 0.0722792,
+                          0.366727 -0.90029 0.234499,
+                          0.248522 -0.965926 0.0722792,
+                          0.480107 -0.866025 0.139633,
+                          0.366727 -0.90029 0.234499,
+                          0.188112 -0.974754 0.120286,
+                          0.248522 -0.965926 0.0722792,
+                          0.538717 -0.842487 6.79127e-16,
+                          0.678974 -0.707107 0.19747,
+                          0.480107 -0.866025 0.139633,
+                          0.526824 -0.780368 0.336871,
+                          0.480107 -0.866025 0.139633,
+                          0.678974 -0.707107 0.19747,
+                          0.279265 -0.960214 5.65673e-16,
+                          0.538717 -0.842487 6.79127e-16,
+                          0.480107 -0.866025 0.139633,
+                          0.526824 -0.780368 0.336871,
+                          0.366727 -0.90029 0.234499,
+                          0.480107 -0.866025 0.139633,
+                          0.754439 -0.65637 7.37453e-16,
+                          0.83157 -0.5 0.241851,
+                          0.678974 -0.707107 0.19747,
+                          0.660321 -0.621044 0.422234,
+                          0.678974 -0.707107 0.19747,
+                          0.83157 -0.5 0.241851,
+                          0.538717 -0.842487 6.79127e-16,
+                          0.754439 -0.65637 7.37453e-16,
+                          0.678974 -0.707107 0.19747,
+                          0.660321 -0.621044 0.422234,
+                          0.526824 -0.780368 0.336871,
+                          0.678974 -0.707107 0.19747,
+                          0.908919 -0.416973 7.35916e-16,
+                          0.927495 -0.258819 0.26975,
+                          0.83157 -0.5 0.241851,
+                          0.86403 -0.282527 0.416689,
+                          0.83157 -0.5 0.241851,
+                          0.927495 -0.258819 0.26975,
+                          0.754439 -0.65637 7.37453e-16,
+                          0.908919 -0.416973 7.35916e-16,
+                          0.83157 -0.5 0.241851,
+                          0.738399 -0.530243 0.416664,
+                          0.660321 -0.621044 0.422234,
+                          0.83157 -0.5 0.241851,
+                          0.86403 -0.282527 0.416689,
+                          0.738399 -0.530243 0.416664,
+                          0.83157 -0.5 0.241851,
+                          0.989617 -0.143728 6.74641e-16,
+                          0.960214 7.36385e-16 0.279265,
+                          0.927495 -0.258819 0.26975,
+                          0.909059 -1.15853e-05 0.416667,
+                          0.927495 -0.258819 0.26975,
+                          0.960214 7.36385e-16 0.279265,
+                          0.908919 -0.416973 7.35916e-16,
+                          0.989617 -0.143728 6.74641e-16,
+                          0.927495 -0.258819 0.26975,
+                          0.909059 -1.15853e-05 0.416667,
+                          0.86403 -0.282527 0.416689,
+                          0.927495 -0.258819 0.26975,
+                          0.989983 0.141184 5.58603e-16,
+                          0.927495 0.258819 0.26975,
+                          0.960214 7.36385e-16 0.279265,
+                          0.909059 -1.15853e-05 0.416667,
+                          0.960214 7.36385e-16 0.279265,
+                          0.927495 0.258819 0.26975,
+                          0.989617 -0.143728 6.74641e-16,
+                          0.989983 0.141184 5.58603e-16,
+                          0.960214 7.36385e-16 0.279265,
+                          0.909988 0.414635 3.97219e-16,
+                          0.83157 0.5 0.241851,
+                          0.927495 0.258819 0.26975,
+                          0.864038 0.282505 0.416689,
+                          0.927495 0.258819 0.26975,
+                          0.83157 0.5 0.241851,
+                          0.989983 0.141184 5.58603e-16,
+                          0.909988 0.414635 3.97219e-16,
+                          0.927495 0.258819 0.26975,
+                          0.864038 0.282505 0.416689,
+                          0.909059 -1.15853e-05 0.416667,
+                          0.927495 0.258819 0.26975,
+                          0.756123 0.654429 2.03591e-16,
+                          0.678974 0.707107 0.19747,
+                          0.83157 0.5 0.241851,
+                          0.738411 0.530226 0.416664,
+                          0.83157 0.5 0.241851,
+                          0.678974 0.707107 0.19747,
+                          0.909988 0.414635 3.97219e-16,
+                          0.756123 0.654429 2.03591e-16,
+                          0.83157 0.5 0.241851,
+                          0.738411 0.530226 0.416664,
+                          0.864038 0.282505 0.416689,
+                          0.83157 0.5 0.241851,
+                          0.540881 0.841099 -6.56304e-18,
+                          0.480107 0.866025 0.139633,
+                          0.678974 0.707107 0.19747,
+                          0.526824 0.780368 0.336871,
+                          0.678974 0.707107 0.19747,
+                          0.480107 0.866025 0.139633,
+                          0.756123 0.654429 2.03591e-16,
+                          0.540881 0.841099 -6.56304e-18,
+                          0.678974 0.707107 0.19747,
+                          0.660321 0.621044 0.422234,
+                          0.738411 0.530226 0.416664,
+                          0.678974 0.707107 0.19747,
+                          0.526824 0.780368 0.336871,
+                          0.660321 0.621044 0.422234,
+                          0.678974 0.707107 0.19747,
+                          0.281733 0.959493 -2.16185e-16,
+                          0.248522 0.965926 0.0722792,
+                          0.480107 0.866025 0.139633,
+                          0.366727 0.90029 0.234499,
+                          0.480107 0.866025 0.139633,
+                          0.248522 0.965926 0.0722792,
+                          0.540881 0.841099 -6.56304e-18,
+                          0.281733 0.959493 -2.16185e-16,
+                          0.480107 0.866025 0.139633,
+                          0.366727 0.90029 0.234499,
+                          0.526824 0.780368 0.336871,
+                          0.480107 0.866025 0.139633,
+                          0.281733 0.959493 -2.16185e-16,
+                          -5.69525e-16 1 -4.59378e-16,
+                          0.248522 0.965926 0.0722792,
+                          0.188112 0.974754 0.120286,
+                          0.248522 0.965926 0.0722792,
+                          -5.69525e-16 1 -4.59378e-16,
+                          0.188112 0.974754 0.120286,
+                          0.366727 0.90029 0.234499,
+                          0.248522 0.965926 0.0722792,
+                          0.272133 0.959493 -0.0729178,
+                          -5.76834e-16 1 -4.0808e-16,
+                          0.281733 0.959493 -1.60072e-16,
+                          0.128298 0.980711 0.147467,
+                          0.188112 0.974754 0.120286,
+                          -5.69525e-16 1 -4.59378e-16,
+                          -0.186741 0.975042 0.120086,
+                          -5.69525e-16 1 -4.59378e-16,
+                          -0.248335 0.965926 0.0729178,
+                          -0.281733 0.959493 -5.32413e-16,
+                          -0.248335 0.965926 0.0729178,
+                          -5.69525e-16 1 -4.59378e-16,
+                          -0.127563 0.980819 0.147386,
+                          -5.69525e-16 1 -4.59378e-16,
+                          -0.186741 0.975042 0.120086,
+                          -0.272133 0.959493 -0.0729178,
+                          -0.281733 0.959493 -5.32413e-16,
+                          -5.76834e-16 1 -4.0808e-16,
+                          -0.0981478 0.971581 0.215402,
+                          -5.69525e-16 1 -4.59378e-16,
+                          -0.127563 0.980819 0.147386,
+                          -0.0305244 0.976348 0.214037,
+                          -5.69525e-16 1 -4.59378e-16,
+                          -0.0981478 0.971581 0.215402,
+                          0.0310822 0.976337 0.214011,
+                          -5.69525e-16 1 -4.59378e-16,
+                          -0.0305244 0.976348 0.214037,
+                          0.0988266 0.971507 0.215422,
+                          -5.69525e-16 1 -4.59378e-16,
+                          0.0310822 0.976337 0.214011,
+                          0.128298 0.980711 0.147467,
+                          -5.69525e-16 1 -4.59378e-16,
+                          0.0988266 0.971507 0.215422,
+                          -0.243988 0.959493 -0.140866,
+                          -0.272133 0.959493 -0.0729178,
+                          -5.76834e-16 1 -4.0808e-16,
+                          -0.199215 0.959493 -0.199215,
+                          -0.243988 0.959493 -0.140866,
+                          -5.76834e-16 1 -4.0808e-16,
+                          -0.140866 0.959493 -0.243988,
+                          -0.199215 0.959493 -0.199215,
+                          -5.76834e-16 1 -4.0808e-16,
+                          -0.0729178 0.959493 -0.272133,
+                          -0.140866 0.959493 -0.243988,
+                          -5.76834e-16 1 -4.0808e-16,
+                          -3.16162e-16 0.959493 -0.281733,
+                          -0.0729178 0.959493 -0.272133,
+                          -5.76834e-16 1 -4.0808e-16,
+                          0.0729178 0.959493 -0.272133,
+                          -3.16162e-16 0.959493 -0.281733,
+                          -5.76834e-16 1 -4.0808e-16,
+                          0.140866 0.959493 -0.243988,
+                          0.0729178 0.959493 -0.272133,
+                          -5.76834e-16 1 -4.0808e-16,
+                          0.199215 0.959493 -0.199215,
+                          0.140866 0.959493 -0.243988,
+                          -5.76834e-16 1 -4.0808e-16,
+                          0.243988 0.959493 -0.140866,
+                          0.199215 0.959493 -0.199215,
+                          -5.76834e-16 1 -4.0808e-16,
+                          0.272133 0.959493 -0.0729178,
+                          0.243988 0.959493 -0.140866,
+                          -5.76834e-16 1 -4.0808e-16,
+                          0.522451 0.841099 -0.13999,
+                          0.281733 0.959493 -1.60072e-16,
+                          0.540881 0.841099 1.01163e-16,
+                          0.522451 0.841099 -0.13999,
+                          0.272133 0.959493 -0.0729178,
+                          0.281733 0.959493 -1.60072e-16,
+                          0.733789 0.654429 -0.182419,
+                          0.540881 0.841099 1.01163e-16,
+                          0.756123 0.654429 3.54187e-16,
+                          0.522451 0.841099 -0.13999,
+                          0.540881 0.841099 1.01163e-16,
+                          0.733789 0.654429 -0.182419,
+                          0.883832 0.414635 -0.216608,
+                          0.756123 0.654429 3.54187e-16,
+                          0.909988 0.414635 5.78459e-16,
+                          0.883832 0.414635 -0.216608,
+                          0.733789 0.654429 -0.182419,
+                          0.756123 0.654429 3.54187e-16,
+                          0.967137 0.141184 -0.211453,
+                          0.909988 0.414635 5.78459e-16,
+                          0.989983 0.141184 7.55775e-16,
+                          0.883832 0.414635 -0.216608,
+                          0.909988 0.414635 5.78459e-16,
+                          0.967137 0.141184 -0.211453,
+                          0.96695 -0.143728 -0.210596,
+                          0.989983 0.141184 7.55775e-16,
+                          0.989617 -0.143728 8.71741e-16,
+                          0.967137 0.141184 -0.211453,
+                          0.989983 0.141184 7.55775e-16,
+                          0.96695 -0.143728 -0.210596,
+                          0.882369 -0.416973 -0.218079,
+                          0.989617 -0.143728 8.71741e-16,
+                          0.908919 -0.416973 9.16944e-16,
+                          0.96695 -0.143728 -0.210596,
+                          0.989617 -0.143728 8.71741e-16,
+                          0.882369 -0.416973 -0.218079,
+                          0.731509 -0.65637 -0.184589,
+                          0.908919 -0.416973 9.16944e-16,
+                          0.754439 -0.65637 8.87713e-16,
+                          0.882369 -0.416973 -0.218079,
+                          0.908919 -0.416973 9.16944e-16,
+                          0.731509 -0.65637 -0.184589,
+                          0.520361 -0.842487 -0.13943,
+                          0.754439 -0.65637 8.87713e-16,
+                          0.538717 -0.842487 7.86422e-16,
+                          0.731509 -0.65637 -0.184589,
+                          0.754439 -0.65637 8.87713e-16,
+                          0.520361 -0.842487 -0.13943,
+                          0.26975 -0.960214 -0.0722792,
+                          0.538717 -0.842487 7.86422e-16,
+                          0.279265 -0.960214 6.21294e-16,
+                          0.520361 -0.842487 -0.13943,
+                          0.538717 -0.842487 7.86422e-16,
+                          0.26975 -0.960214 -0.0722792,
+                          0.251646 -0.923586 0.289245,
+                          0.188112 -0.974754 0.120286,
+                          0.366727 -0.90029 0.234499,
+                          0.251646 -0.923586 0.289245,
+                          0.128298 -0.980711 0.147467,
+                          0.188112 -0.974754 0.120286,
+                          0.365286 -0.830831 0.419864,
+                          0.366727 -0.90029 0.234499,
+                          0.526824 -0.780368 0.336871,
+                          0.365286 -0.830831 0.419864,
+                          0.251646 -0.923586 0.289245,
+                          0.366727 -0.90029 0.234499,
+                          0.587704 -0.693543 0.416656,
+                          0.526824 -0.780368 0.336871,
+                          0.660321 -0.621044 0.422234,
+                          0.448614 -0.790658 0.416659,
+                          0.365286 -0.830831 0.419864,
+                          0.526824 -0.780368 0.336871,
+                          0.587704 -0.693543 0.416656,
+                          0.448614 -0.790658 0.416659,
+                          0.526824 -0.780368 0.336871,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          0.587716 0.693533 0.416656,
+                          0.660321 0.621044 0.422234,
+                          0.526824 0.780368 0.336871,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          0.448625 0.790652 0.416659,
+                          0.526824 0.780368 0.336871,
+                          0.366727 0.90029 0.234499,
+                          0.448625 0.790652 0.416659,
+                          0.587716 0.693533 0.416656,
+                          0.526824 0.780368 0.336871,
+                          0.251646 0.923586 0.289244,
+                          0.366727 0.90029 0.234499,
+                          0.188112 0.974754 0.120286,
+                          0.365286 0.830831 0.419863,
+                          0.366727 0.90029 0.234499,
+                          0.251646 0.923586 0.289244,
+                          0.448625 0.790652 0.416659,
+                          0.366727 0.90029 0.234499,
+                          0.365286 0.830831 0.419863,
+                          0.251646 0.923586 0.289244,
+                          0.188112 0.974754 0.120286,
+                          0.128298 0.980711 0.147467,
+                          0.0988266 -0.971507 0.215422,
+                          0.128298 -0.980711 0.147467,
+                          0.251646 -0.923586 0.289245,
+                          0.3302 -0.846964 0.416678,
+                          0.251646 -0.923586 0.289245,
+                          0.365286 -0.830831 0.419864,
+                          0.192021 -0.887653 0.418569,
+                          0.0988266 -0.971507 0.215422,
+                          0.251646 -0.923586 0.289245,
+                          0.233894 -0.878453 0.416669,
+                          0.192021 -0.887653 0.418569,
+                          0.251646 -0.923586 0.289245,
+                          0.3302 -0.846964 0.416678,
+                          0.233894 -0.878453 0.416669,
+                          0.251646 -0.923586 0.289245,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          0.154382 -0.895857 0.416661,
+                          0.0988266 -0.971507 0.215422,
+                          0.192021 -0.887653 0.418569,
+                          0.0606933 -0.906466 0.417894,
+                          0.0310822 -0.976337 0.214011,
+                          0.0988266 -0.971507 0.215422,
+                          0.0775712 -0.905744 0.416666,
+                          0.0606933 -0.906466 0.417894,
+                          0.0988266 -0.971507 0.215422,
+                          0.154382 -0.895857 0.416661,
+                          0.0775712 -0.905744 0.416666,
+                          0.0988266 -0.971507 0.215422,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          3.08585e-16 -0.909059 0.416667,
+                          0.0310822 -0.976337 0.214011,
+                          0.0606933 -0.906466 0.417894,
+                          3.08585e-16 -0.909059 0.416667,
+                          -0.0305244 -0.976348 0.214037,
+                          0.0310822 -0.976337 0.214011,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          3.08585e-16 -0.909059 0.416667,
+                          -0.0596049 -0.906513 0.41795,
+                          -0.0305244 -0.976348 0.214037,
+                          -0.0981478 -0.971581 0.215402,
+                          -0.0305244 -0.976348 0.214037,
+                          -0.0596049 -0.906513 0.41795,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          -0.0775749 -0.905744 0.416666,
+                          -0.0981478 -0.971581 0.215402,
+                          -0.0596049 -0.906513 0.41795,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          -0.154388 -0.895856 0.416661,
+                          -0.190717 -0.887938 0.418561,
+                          -0.0981478 -0.971581 0.215402,
+                          -0.250232 -0.924011 0.289117,
+                          -0.0981478 -0.971581 0.215402,
+                          -0.190717 -0.887938 0.418561,
+                          -0.0775749 -0.905744 0.416666,
+                          -0.154388 -0.895856 0.416661,
+                          -0.0981478 -0.971581 0.215402,
+                          -0.250232 -0.924011 0.289117,
+                          -0.127563 -0.980819 0.147385,
+                          -0.0981478 -0.971581 0.215402,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          -0.233902 -0.878451 0.416669,
+                          -0.250232 -0.924011 0.289117,
+                          -0.190717 -0.887938 0.418561,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          -0.186741 -0.975042 0.120086,
+                          -0.127563 -0.980819 0.147385,
+                          -0.250232 -0.924011 0.289117,
+                          -0.330209 -0.84696 0.416678,
+                          -0.363302 -0.831755 0.419757,
+                          -0.250232 -0.924011 0.289117,
+                          -0.36416 -0.901414 0.234179,
+                          -0.250232 -0.924011 0.289117,
+                          -0.363302 -0.831755 0.419757,
+                          -0.233902 -0.878451 0.416669,
+                          -0.330209 -0.84696 0.416678,
+                          -0.250232 -0.924011 0.289117,
+                          -0.36416 -0.901414 0.234179,
+                          -0.186741 -0.975042 0.120086,
+                          -0.250232 -0.924011 0.289117,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          -0.448625 -0.790652 0.416659,
+                          -0.36416 -0.901414 0.234179,
+                          -0.363302 -0.831755 0.419757,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          -0.248335 -0.965926 0.0729178,
+                          -0.186741 -0.975042 0.120086,
+                          -0.36416 -0.901414 0.234179,
+                          -0.448625 -0.790652 0.416659,
+                          -0.523402 -0.782792 0.336581,
+                          -0.36416 -0.901414 0.234179,
+                          -0.479746 -0.866025 0.140866,
+                          -0.36416 -0.901414 0.234179,
+                          -0.523402 -0.782792 0.336581,
+                          -0.479746 -0.866025 0.140866,
+                          -0.248335 -0.965926 0.0729178,
+                          -0.36416 -0.901414 0.234179,
+                          -0.587716 -0.693533 0.416656,
+                          -0.656518 -0.625096 0.422184,
+                          -0.523402 -0.782792 0.336581,
+                          -0.678464 -0.707107 0.199215,
+                          -0.523402 -0.782792 0.336581,
+                          -0.656518 -0.625096 0.422184,
+                          -0.448625 -0.790652 0.416659,
+                          -0.587716 -0.693533 0.416656,
+                          -0.523402 -0.782792 0.336581,
+                          -0.678464 -0.707107 0.199215,
+                          -0.479746 -0.866025 0.140866,
+                          -0.523402 -0.782792 0.336581,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          -0.738411 -0.530226 0.416664,
+                          -0.678464 -0.707107 0.199215,
+                          -0.656518 -0.625096 0.422184,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          -0.279265 -0.960214 2.52214e-16,
+                          -0.248335 -0.965926 0.0729178,
+                          -0.479746 -0.866025 0.140866,
+                          -0.538717 -0.842487 7.44477e-17,
+                          -0.479746 -0.866025 0.140866,
+                          -0.678464 -0.707107 0.199215,
+                          -0.538717 -0.842487 7.44477e-17,
+                          -0.279265 -0.960214 2.52214e-16,
+                          -0.479746 -0.866025 0.140866,
+                          -0.738411 -0.530226 0.416664,
+                          -0.830945 -0.5 0.243988,
+                          -0.678464 -0.707107 0.199215,
+                          -0.754439 -0.65637 -1.09361e-16,
+                          -0.678464 -0.707107 0.199215,
+                          -0.830945 -0.5 0.243988,
+                          -0.754439 -0.65637 -1.09361e-16,
+                          -0.538717 -0.842487 7.44477e-17,
+                          -0.678464 -0.707107 0.199215,
+                          -0.864038 -0.282505 0.416689,
+                          -0.926799 -0.258819 0.272133,
+                          -0.830945 -0.5 0.243988,
+                          -0.908919 -0.416973 -2.84293e-16,
+                          -0.830945 -0.5 0.243988,
+                          -0.926799 -0.258819 0.272133,
+                          -0.738411 -0.530226 0.416664,
+                          -0.864038 -0.282505 0.416689,
+                          -0.830945 -0.5 0.243988,
+                          -0.908919 -0.416973 -2.84293e-16,
+                          -0.754439 -0.65637 -1.09361e-16,
+                          -0.830945 -0.5 0.243988,
+                          -0.909059 1.15853e-05 0.416667,
+                          -0.959493 -1.73272e-17 0.281733,
+                          -0.926799 -0.258819 0.272133,
+                          -0.989617 -0.143728 -4.36147e-16,
+                          -0.926799 -0.258819 0.272133,
+                          -0.959493 -1.73272e-17 0.281733,
+                          -0.864038 -0.282505 0.416689,
+                          -0.909059 1.15853e-05 0.416667,
+                          -0.926799 -0.258819 0.272133,
+                          -0.989617 -0.143728 -4.36147e-16,
+                          -0.908919 -0.416973 -2.84293e-16,
+                          -0.926799 -0.258819 0.272133,
+                          -0.909059 1.15853e-05 0.416667,
+                          -0.926799 0.258819 0.272133,
+                          -0.959493 -1.73272e-17 0.281733,
+                          -0.989983 0.141184 -5.52597e-16,
+                          -0.959493 -1.73272e-17 0.281733,
+                          -0.926799 0.258819 0.272133,
+                          -0.989983 0.141184 -5.52597e-16,
+                          -0.989617 -0.143728 -4.36147e-16,
+                          -0.959493 -1.73272e-17 0.281733,
+                          -0.86403 0.282527 0.416689,
+                          -0.830945 0.5 0.243988,
+                          -0.926799 0.258819 0.272133,
+                          -0.909988 0.414635 -6.2419e-16,
+                          -0.926799 0.258819 0.272133,
+                          -0.830945 0.5 0.243988,
+                          -0.909059 1.15853e-05 0.416667,
+                          -0.86403 0.282527 0.416689,
+                          -0.926799 0.258819 0.272133,
+                          -0.909988 0.414635 -6.2419e-16,
+                          -0.989983 0.141184 -5.52597e-16,
+                          -0.926799 0.258819 0.272133,
+                          -0.656519 0.625095 0.422184,
+                          -0.678464 0.707107 0.199215,
+                          -0.830945 0.5 0.243988,
+                          -0.756123 0.654429 -6.45114e-16,
+                          -0.830945 0.5 0.243988,
+                          -0.678464 0.707107 0.199215,
+                          -0.738399 0.530243 0.416664,
+                          -0.656519 0.625095 0.422184,
+                          -0.830945 0.5 0.243988,
+                          -0.86403 0.282527 0.416689,
+                          -0.738399 0.530243 0.416664,
+                          -0.830945 0.5 0.243988,
+                          -0.756123 0.654429 -6.45114e-16,
+                          -0.909988 0.414635 -6.2419e-16,
+                          -0.830945 0.5 0.243988,
+                          -0.523403 0.782792 0.336582,
+                          -0.479746 0.866025 0.140866,
+                          -0.678464 0.707107 0.199215,
+                          -0.540881 0.841099 -6.13671e-16,
+                          -0.678464 0.707107 0.199215,
+                          -0.479746 0.866025 0.140866,
+                          -0.656519 0.625095 0.422184,
+                          -0.523403 0.782792 0.336582,
+                          -0.678464 0.707107 0.199215,
+                          -0.540881 0.841099 -6.13671e-16,
+                          -0.756123 0.654429 -6.45114e-16,
+                          -0.678464 0.707107 0.199215,
+                          -0.36416 0.901414 0.234179,
+                          -0.248335 0.965926 0.0729178,
+                          -0.479746 0.866025 0.140866,
+                          -0.281733 0.959493 -5.32413e-16,
+                          -0.479746 0.866025 0.140866,
+                          -0.248335 0.965926 0.0729178,
+                          -0.523403 0.782792 0.336582,
+                          -0.36416 0.901414 0.234179,
+                          -0.479746 0.866025 0.140866,
+                          -0.281733 0.959493 -5.32413e-16,
+                          -0.540881 0.841099 -6.13671e-16,
+                          -0.479746 0.866025 0.140866,
+                          -0.36416 0.901414 0.234179,
+                          -0.186741 0.975042 0.120086,
+                          -0.248335 0.965926 0.0729178,
+                          -0.250232 0.92401 0.289117,
+                          -0.186741 0.975042 0.120086,
+                          -0.36416 0.901414 0.234179,
+                          -0.250232 0.92401 0.289117,
+                          -0.127563 0.980819 0.147386,
+                          -0.186741 0.975042 0.120086,
+                          -0.363302 0.831755 0.419757,
+                          -0.36416 0.901414 0.234179,
+                          -0.523403 0.782792 0.336582,
+                          -0.363302 0.831755 0.419757,
+                          -0.250232 0.92401 0.289117,
+                          -0.36416 0.901414 0.234179,
+                          -0.587704 0.693543 0.416656,
+                          -0.523403 0.782792 0.336582,
+                          -0.656519 0.625095 0.422184,
+                          -0.448614 0.790658 0.416659,
+                          -0.363302 0.831755 0.419757,
+                          -0.523403 0.782792 0.336582,
+                          -0.587704 0.693543 0.416656,
+                          -0.448614 0.790658 0.416659,
+                          -0.523403 0.782792 0.336582,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          -0.520361 -0.842487 -0.13943,
+                          -0.279265 -0.960214 2.52214e-16,
+                          -0.538717 -0.842487 7.44477e-17,
+                          -0.520361 -0.842487 -0.13943,
+                          -0.26975 -0.960214 -0.0722792,
+                          -0.279265 -0.960214 2.52214e-16,
+                          -0.731455 -0.65637 -0.184802,
+                          -0.538717 -0.842487 7.44477e-17,
+                          -0.754439 -0.65637 -1.09361e-16,
+                          -0.731455 -0.65637 -0.184802,
+                          -0.520361 -0.842487 -0.13943,
+                          -0.538717 -0.842487 7.44477e-17,
+                          -0.882389 -0.416973 -0.217998,
+                          -0.754439 -0.65637 -1.09361e-16,
+                          -0.908919 -0.416973 -2.84293e-16,
+                          -0.882389 -0.416973 -0.217998,
+                          -0.731455 -0.65637 -0.184802,
+                          -0.754439 -0.65637 -1.09361e-16,
+                          -0.966943 -0.143728 -0.210625,
+                          -0.908919 -0.416973 -2.84293e-16,
+                          -0.989617 -0.143728 -4.36147e-16,
+                          -0.966943 -0.143728 -0.210625,
+                          -0.882389 -0.416973 -0.217998,
+                          -0.908919 -0.416973 -2.84293e-16,
+                          -0.967137 0.141184 -0.211453,
+                          -0.989617 -0.143728 -4.36147e-16,
+                          -0.989983 0.141184 -5.52597e-16,
+                          -0.967137 0.141184 -0.211453,
+                          -0.966943 -0.143728 -0.210625,
+                          -0.989617 -0.143728 -4.36147e-16,
+                          -0.88383 0.414635 -0.216614,
+                          -0.989983 0.141184 -5.52597e-16,
+                          -0.909988 0.414635 -6.2419e-16,
+                          -0.88383 0.414635 -0.216614,
+                          -0.967137 0.141184 -0.211453,
+                          -0.989983 0.141184 -5.52597e-16,
+                          -0.733792 0.654429 -0.182406,
+                          -0.909988 0.414635 -6.2419e-16,
+                          -0.756123 0.654429 -6.45114e-16,
+                          -0.733792 0.654429 -0.182406,
+                          -0.88383 0.414635 -0.216614,
+                          -0.909988 0.414635 -6.2419e-16,
+                          -0.522451 0.841099 -0.13999,
+                          -0.756123 0.654429 -6.45114e-16,
+                          -0.540881 0.841099 -6.13671e-16,
+                          -0.522451 0.841099 -0.13999,
+                          -0.733792 0.654429 -0.182406,
+                          -0.756123 0.654429 -6.45114e-16,
+                          -0.272133 0.959493 -0.0729178,
+                          -0.540881 0.841099 -6.13671e-16,
+                          -0.281733 0.959493 -5.32413e-16,
+                          -0.522451 0.841099 -0.13999,
+                          -0.540881 0.841099 -6.13671e-16,
+                          -0.272133 0.959493 -0.0729178,
+                          -0.0981478 0.971581 0.215402,
+                          -0.127563 0.980819 0.147386,
+                          -0.250232 0.92401 0.289117,
+                          -0.3302 0.846964 0.416678,
+                          -0.250232 0.92401 0.289117,
+                          -0.363302 0.831755 0.419757,
+                          -0.190717 0.887938 0.418561,
+                          -0.0981478 0.971581 0.215402,
+                          -0.250232 0.92401 0.289117,
+                          -0.233894 0.878453 0.416669,
+                          -0.190717 0.887938 0.418561,
+                          -0.250232 0.92401 0.289117,
+                          -0.3302 0.846964 0.416678,
+                          -0.233894 0.878453 0.416669,
+                          -0.250232 0.92401 0.289117,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          -0.154382 0.895857 0.416661,
+                          -0.0981478 0.971581 0.215402,
+                          -0.190717 0.887938 0.418561,
+                          -0.0596048 0.906513 0.41795,
+                          -0.0305244 0.976348 0.214037,
+                          -0.0981478 0.971581 0.215402,
+                          -0.0775712 0.905744 0.416666,
+                          -0.0596048 0.906513 0.41795,
+                          -0.0981478 0.971581 0.215402,
+                          -0.154382 0.895857 0.416661,
+                          -0.0775712 0.905744 0.416666,
+                          -0.0981478 0.971581 0.215402,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          0.0310822 0.976337 0.214011,
+                          -0.0305244 0.976348 0.214037,
+                          -0.0596048 0.906513 0.41795,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          -3.13677e-16 0.909059 0.416667,
+                          0.0310822 0.976337 0.214011,
+                          -0.0596048 0.906513 0.41795,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          -3.13677e-16 0.909059 0.416667,
+                          0.0606933 0.906466 0.417894,
+                          0.0310822 0.976337 0.214011,
+                          0.0988266 0.971507 0.215422,
+                          0.0310822 0.976337 0.214011,
+                          0.0606933 0.906466 0.417894,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          0.0775749 0.905744 0.416666,
+                          0.0988266 0.971507 0.215422,
+                          0.0606933 0.906466 0.417894,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          0.154388 0.895856 0.416661,
+                          0.192021 0.887653 0.418569,
+                          0.0988266 0.971507 0.215422,
+                          0.251646 0.923586 0.289244,
+                          0.0988266 0.971507 0.215422,
+                          0.192021 0.887653 0.418569,
+                          0.0775749 0.905744 0.416666,
+                          0.154388 0.895856 0.416661,
+                          0.0988266 0.971507 0.215422,
+                          0.251646 0.923586 0.289244,
+                          0.128298 0.980711 0.147467,
+                          0.0988266 0.971507 0.215422,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          0.233902 0.878451 0.416669,
+                          0.251646 0.923586 0.289244,
+                          0.192021 0.887653 0.418569,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          0.330209 0.84696 0.416678,
+                          0.365286 0.830831 0.419863,
+                          0.251646 0.923586 0.289244,
+                          0.233902 0.878451 0.416669,
+                          0.330209 0.84696 0.416678,
+                          0.251646 0.923586 0.289244,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          5.59019e-17 -4.0808e-16 -1,
+                          -0.281733 -0.959493 2.16185e-16,
+                          -0.248522 -0.965926 -0.0722792,
+                          5.76834e-16 -1 4.0808e-16,
+                          -0.235481 -0.960144 -0.150575,
+                          5.76834e-16 -1 4.0808e-16,
+                          -0.248522 -0.965926 -0.0722792,
+                          -0.272133 -0.959493 0.0729178,
+                          -0.281733 -0.959493 1.60072e-16,
+                          2.09452e-16 -1 4.0808e-16,
+                          -0.182551 -0.960546 -0.209826,
+                          5.76834e-16 -1 4.0808e-16,
+                          -0.235481 -0.960144 -0.150575,
+                          -0.0946217 -0.973912 -0.206256,
+                          5.76834e-16 -1 4.0808e-16,
+                          -0.182551 -0.960546 -0.209826,
+                          -0.0297769 -0.978304 -0.205024,
+                          5.76834e-16 -1 4.0808e-16,
+                          -0.0946217 -0.973912 -0.206256,
+                          0.0292426 -0.978315 -0.205049,
+                          5.76834e-16 -1 4.0808e-16,
+                          -0.0297769 -0.978304 -0.205024,
+                          0.0939735 -0.973978 -0.206241,
+                          5.76834e-16 -1 4.0808e-16,
+                          0.0292426 -0.978315 -0.205049,
+                          0.181538 -0.960755 -0.209748,
+                          5.76834e-16 -1 4.0808e-16,
+                          0.0939735 -0.973978 -0.206241,
+                          0.233924 -0.960547 -0.150429,
+                          5.76834e-16 -1 4.0808e-16,
+                          0.181538 -0.960755 -0.209748,
+                          0.248335 -0.965926 -0.0729178,
+                          5.76834e-16 -1 4.0808e-16,
+                          0.233924 -0.960547 -0.150429,
+                          0.281733 -0.959493 5.32413e-16,
+                          5.76834e-16 -1 4.0808e-16,
+                          0.248335 -0.965926 -0.0729178,
+                          0.272133 -0.959493 0.0729178,
+                          2.09452e-16 -1 4.0808e-16,
+                          0.281733 -0.959493 5.32413e-16,
+                          -0.243988 -0.959493 0.140866,
+                          -0.272133 -0.959493 0.0729178,
+                          2.09452e-16 -1 4.0808e-16,
+                          -0.199215 -0.959493 0.199215,
+                          -0.243988 -0.959493 0.140866,
+                          2.09452e-16 -1 4.0808e-16,
+                          -0.140866 -0.959493 0.243988,
+                          -0.199215 -0.959493 0.199215,
+                          2.09452e-16 -1 4.0808e-16,
+                          -0.0729178 -0.959493 0.272133,
+                          -0.140866 -0.959493 0.243988,
+                          2.09452e-16 -1 4.0808e-16,
+                          3.16162e-16 -0.959493 0.281733,
+                          -0.0729178 -0.959493 0.272133,
+                          2.09452e-16 -1 4.0808e-16,
+                          0.0729178 -0.959493 0.272133,
+                          3.16162e-16 -0.959493 0.281733,
+                          2.09452e-16 -1 4.0808e-16,
+                          0.140866 -0.959493 0.243988,
+                          0.0729178 -0.959493 0.272133,
+                          2.09452e-16 -1 4.0808e-16,
+                          0.199215 -0.959493 0.199215,
+                          0.140866 -0.959493 0.243988,
+                          2.09452e-16 -1 4.0808e-16,
+                          0.243988 -0.959493 0.140866,
+                          0.199215 -0.959493 0.199215,
+                          2.09452e-16 -1 4.0808e-16,
+                          0.272133 -0.959493 0.0729178,
+                          0.243988 -0.959493 0.140866,
+                          2.09452e-16 -1 4.0808e-16,
+                          -0.281733 -0.959493 2.16185e-16,
+                          -0.480107 -0.866025 -0.139633,
+                          -0.248522 -0.965926 -0.0722792,
+                          -0.235481 -0.960144 -0.150575,
+                          -0.248522 -0.965926 -0.0722792,
+                          -0.480107 -0.866025 -0.139633,
+                          -0.540881 -0.841099 6.56304e-18,
+                          -0.678974 -0.707107 -0.19747,
+                          -0.480107 -0.866025 -0.139633,
+                          -0.452191 -0.843752 -0.289148,
+                          -0.480107 -0.866025 -0.139633,
+                          -0.678974 -0.707107 -0.19747,
+                          -0.281733 -0.959493 2.16185e-16,
+                          -0.540881 -0.841099 6.56304e-18,
+                          -0.480107 -0.866025 -0.139633,
+                          -0.452191 -0.843752 -0.289148,
+                          -0.235481 -0.960144 -0.150575,
+                          -0.480107 -0.866025 -0.139633,
+                          -0.756123 -0.654429 -2.03591e-16,
+                          -0.83157 -0.5 -0.241851,
+                          -0.678974 -0.707107 -0.19747,
+                          -0.632856 -0.660102 -0.404672,
+                          -0.678974 -0.707107 -0.19747,
+                          -0.83157 -0.5 -0.241851,
+                          -0.540881 -0.841099 6.56304e-18,
+                          -0.756123 -0.654429 -2.03591e-16,
+                          -0.678974 -0.707107 -0.19747,
+                          -0.632856 -0.660102 -0.404672,
+                          -0.452191 -0.843752 -0.289148,
+                          -0.678974 -0.707107 -0.19747,
+                          -0.909988 -0.414635 -3.97219e-16,
+                          -0.927495 -0.258819 -0.26975,
+                          -0.83157 -0.5 -0.241851,
+                          -0.827748 -0.393488 -0.4,
+                          -0.83157 -0.5 -0.241851,
+                          -0.927495 -0.258819 -0.26975,
+                          -0.756123 -0.654429 -2.03591e-16,
+                          -0.909988 -0.414635 -3.97219e-16,
+                          -0.83157 -0.5 -0.241851,
+                          -0.690327 -0.602867 -0.4,
+                          -0.632856 -0.660102 -0.404672,
+                          -0.83157 -0.5 -0.241851,
+                          -0.827748 -0.393488 -0.4,
+                          -0.690327 -0.602867 -0.4,
+                          -0.83157 -0.5 -0.241851,
+                          -0.989983 -0.141184 -5.58603e-16,
+                          -0.960214 -7.36385e-16 -0.279265,
+                          -0.927495 -0.258819 -0.26975,
+                          -0.906526 -0.134944 -0.4,
+                          -0.927495 -0.258819 -0.26975,
+                          -0.960214 -7.36385e-16 -0.279265,
+                          -0.909988 -0.414635 -3.97219e-16,
+                          -0.989983 -0.141184 -5.58603e-16,
+                          -0.927495 -0.258819 -0.26975,
+                          -0.906526 -0.134944 -0.4,
+                          -0.827748 -0.393488 -0.4,
+                          -0.927495 -0.258819 -0.26975,
+                          -0.989617 0.143728 -6.74641e-16,
+                          -0.927495 0.258819 -0.26975,
+                          -0.960214 -7.36385e-16 -0.279265,
+                          -0.906522 0.134971 -0.4,
+                          -0.960214 -7.36385e-16 -0.279265,
+                          -0.927495 0.258819 -0.26975,
+                          -0.989983 -0.141184 -5.58603e-16,
+                          -0.989617 0.143728 -6.74641e-16,
+                          -0.960214 -7.36385e-16 -0.279265,
+                          -0.906522 0.134971 -0.4,
+                          -0.906526 -0.134944 -0.4,
+                          -0.960214 -7.36385e-16 -0.279265,
+                          -0.908919 0.416973 -7.35916e-16,
+                          -0.83157 0.5 -0.241851,
+                          -0.927495 0.258819 -0.26975,
+                          -0.827737 0.393513 -0.4,
+                          -0.927495 0.258819 -0.26975,
+                          -0.83157 0.5 -0.241851,
+                          -0.989617 0.143728 -6.74641e-16,
+                          -0.908919 0.416973 -7.35916e-16,
+                          -0.927495 0.258819 -0.26975,
+                          -0.827737 0.393513 -0.4,
+                          -0.906522 0.134971 -0.4,
+                          -0.927495 0.258819 -0.26975,
+                          -0.754439 0.65637 -7.37453e-16,
+                          -0.678974 0.707107 -0.19747,
+                          -0.83157 0.5 -0.241851,
+                          -0.690312 0.602884 -0.4,
+                          -0.83157 0.5 -0.241851,
+                          -0.678974 0.707107 -0.19747,
+                          -0.908919 0.416973 -7.35916e-16,
+                          -0.754439 0.65637 -7.37453e-16,
+                          -0.83157 0.5 -0.241851,
+                          -0.690312 0.602884 -0.4,
+                          -0.827737 0.393513 -0.4,
+                          -0.83157 0.5 -0.241851,
+                          -0.538717 0.842487 -6.79127e-16,
+                          -0.480107 0.866025 -0.139633,
+                          -0.678974 0.707107 -0.19747,
+                          -0.452191 0.843752 -0.289147,
+                          -0.678974 0.707107 -0.19747,
+                          -0.480107 0.866025 -0.139633,
+                          -0.754439 0.65637 -7.37453e-16,
+                          -0.538717 0.842487 -6.79127e-16,
+                          -0.678974 0.707107 -0.19747,
+                          -0.632855 0.660103 -0.404671,
+                          -0.690312 0.602884 -0.4,
+                          -0.678974 0.707107 -0.19747,
+                          -0.452191 0.843752 -0.289147,
+                          -0.632855 0.660103 -0.404671,
+                          -0.678974 0.707107 -0.19747,
+                          -0.279265 0.960214 -5.65673e-16,
+                          -0.248522 0.965926 -0.0722792,
+                          -0.480107 0.866025 -0.139633,
+                          -0.235481 0.960144 -0.150575,
+                          -0.480107 0.866025 -0.139633,
+                          -0.248522 0.965926 -0.0722792,
+                          -0.538717 0.842487 -6.79127e-16,
+                          -0.279265 0.960214 -5.65673e-16,
+                          -0.480107 0.866025 -0.139633,
+                          -0.235481 0.960144 -0.150575,
+                          -0.452191 0.843752 -0.289147,
+                          -0.480107 0.866025 -0.139633,
+                          -0.279265 0.960214 -5.65673e-16,
+                          -6.87114e-16 1 -4.93577e-16,
+                          -0.248522 0.965926 -0.0722792,
+                          -0.235481 0.960144 -0.150575,
+                          -0.248522 0.965926 -0.0722792,
+                          -6.87114e-16 1 -4.93577e-16,
+                          -0.26975 0.960214 0.0722792,
+                          -6.99294e-16 1 -4.0808e-16,
+                          -0.279265 0.960214 -6.21294e-16,
+                          -0.182551 0.960546 -0.209826,
+                          -0.235481 0.960144 -0.150575,
+                          -6.87114e-16 1 -4.93577e-16,
+                          0.233925 0.960547 -0.150429,
+                          -6.87114e-16 1 -4.93577e-16,
+                          0.248335 0.965926 -0.0729178,
+                          0.279265 0.960214 -2.52214e-16,
+                          0.248335 0.965926 -0.0729178,
+                          -6.87114e-16 1 -4.93577e-16,
+                          0.181538 0.960755 -0.209748,
+                          -6.87114e-16 1 -4.93577e-16,
+                          0.233925 0.960547 -0.150429,
+                          0.26975 0.960214 0.0722792,
+                          0.279265 0.960214 -2.52214e-16,
+                          -6.99294e-16 1 -4.0808e-16,
+                          0.0939735 0.973978 -0.206241,
+                          -6.87114e-16 1 -4.93577e-16,
+                          0.181538 0.960755 -0.209748,
+                          0.0292426 0.978315 -0.205049,
+                          -6.87114e-16 1 -4.93577e-16,
+                          0.0939735 0.973978 -0.206241,
+                          -0.0297769 0.978304 -0.205024,
+                          -6.87114e-16 1 -4.93577e-16,
+                          0.0292426 0.978315 -0.205049,
+                          -0.0946217 0.973912 -0.206256,
+                          -6.87114e-16 1 -4.93577e-16,
+                          -0.0297769 0.978304 -0.205024,
+                          -0.182551 0.960546 -0.209826,
+                          -6.87114e-16 1 -4.93577e-16,
+                          -0.0946217 0.973912 -0.206256,
+                          0.241851 0.960214 0.139633,
+                          0.26975 0.960214 0.0722792,
+                          -6.99294e-16 1 -4.0808e-16,
+                          0.19747 0.960214 0.19747,
+                          0.241851 0.960214 0.139633,
+                          -6.99294e-16 1 -4.0808e-16,
+                          0.139633 0.960214 0.241851,
+                          0.19747 0.960214 0.19747,
+                          -6.99294e-16 1 -4.0808e-16,
+                          0.0722792 0.960214 0.26975,
+                          0.139633 0.960214 0.241851,
+                          -6.99294e-16 1 -4.0808e-16,
+                          -4.38023e-16 0.960214 0.279265,
+                          0.0722792 0.960214 0.26975,
+                          -6.99294e-16 1 -4.0808e-16,
+                          -0.0722792 0.960214 0.26975,
+                          -4.38023e-16 0.960214 0.279265,
+                          -6.99294e-16 1 -4.0808e-16,
+                          -0.139633 0.960214 0.241851,
+                          -0.0722792 0.960214 0.26975,
+                          -6.99294e-16 1 -4.0808e-16,
+                          -0.19747 0.960214 0.19747,
+                          -0.139633 0.960214 0.241851,
+                          -6.99294e-16 1 -4.0808e-16,
+                          -0.241851 0.960214 0.139633,
+                          -0.19747 0.960214 0.19747,
+                          -6.99294e-16 1 -4.0808e-16,
+                          -0.26975 0.960214 0.0722792,
+                          -0.241851 0.960214 0.139633,
+                          -6.99294e-16 1 -4.0808e-16,
+                          -0.520361 0.842487 0.13943,
+                          -0.279265 0.960214 -6.21294e-16,
+                          -0.538717 0.842487 -7.86422e-16,
+                          -0.520361 0.842487 0.13943,
+                          -0.26975 0.960214 0.0722792,
+                          -0.279265 0.960214 -6.21294e-16,
+                          -0.728732 0.65637 0.195263,
+                          -0.538717 0.842487 -7.86422e-16,
+                          -0.754439 0.65637 -8.87713e-16,
+                          -0.520361 0.842487 0.13943,
+                          -0.538717 0.842487 -7.86422e-16,
+                          -0.728732 0.65637 0.195263,
+                          -0.879924 0.416973 0.227745,
+                          -0.754439 0.65637 -8.87713e-16,
+                          -0.908919 0.416973 -9.16944e-16,
+                          -0.728732 0.65637 0.195263,
+                          -0.754439 0.65637 -8.87713e-16,
+                          -0.879924 0.416973 0.227745,
+                          -0.964932 0.143728 0.219654,
+                          -0.908919 0.416973 -9.16944e-16,
+                          -0.989617 0.143728 -8.71741e-16,
+                          -0.964932 0.143728 0.219654,
+                          -0.879924 0.416973 0.227745,
+                          -0.908919 0.416973 -9.16944e-16,
+                          -0.965308 -0.141184 0.219653,
+                          -0.989617 0.143728 -8.71741e-16,
+                          -0.989983 -0.141184 -7.55775e-16,
+                          -0.964932 0.143728 0.219654,
+                          -0.989617 0.143728 -8.71741e-16,
+                          -0.965308 -0.141184 0.219653,
+                          -0.881095 -0.414635 0.227485,
+                          -0.989983 -0.141184 -7.55775e-16,
+                          -0.909988 -0.414635 -5.78459e-16,
+                          -0.965308 -0.141184 0.219653,
+                          -0.989983 -0.141184 -7.55775e-16,
+                          -0.881095 -0.414635 0.227485,
+                          -0.730359 -0.654429 0.195699,
+                          -0.909988 -0.414635 -5.78459e-16,
+                          -0.756123 -0.654429 -3.54187e-16,
+                          -0.881095 -0.414635 0.227485,
+                          -0.909988 -0.414635 -5.78459e-16,
+                          -0.730359 -0.654429 0.195699,
+                          -0.522451 -0.841099 0.13999,
+                          -0.756123 -0.654429 -3.54187e-16,
+                          -0.540881 -0.841099 -1.01163e-16,
+                          -0.730359 -0.654429 0.195699,
+                          -0.756123 -0.654429 -3.54187e-16,
+                          -0.522451 -0.841099 0.13999,
+                          -0.272133 -0.959493 0.0729178,
+                          -0.540881 -0.841099 -1.01163e-16,
+                          -0.281733 -0.959493 1.60072e-16,
+                          -0.522451 -0.841099 0.13999,
+                          -0.540881 -0.841099 -1.01163e-16,
+                          -0.272133 -0.959493 0.0729178,
+                          -0.350697 -0.845297 -0.403095,
+                          -0.235481 -0.960144 -0.150575,
+                          -0.452191 -0.843752 -0.289148,
+                          -0.350697 -0.845297 -0.403095,
+                          -0.182551 -0.960546 -0.209826,
+                          -0.235481 -0.960144 -0.150575,
+                          -0.54757 -0.734961 -0.4,
+                          -0.452191 -0.843752 -0.289148,
+                          -0.632856 -0.660102 -0.404672,
+                          -0.419407 -0.814922 -0.4,
+                          -0.350697 -0.845297 -0.403095,
+                          -0.452191 -0.843752 -0.289148,
+                          -0.54757 -0.734961 -0.4,
+                          -0.419407 -0.814922 -0.4,
+                          -0.452191 -0.843752 -0.289148,
+                          -0.547556 0.734971 -0.4,
+                          -0.632855 0.660103 -0.404671,
+                          -0.452191 0.843752 -0.289147,
+                          -0.350697 0.845296 -0.403095,
+                          -0.452191 0.843752 -0.289147,
+                          -0.235481 0.960144 -0.150575,
+                          -0.419395 0.814928 -0.4,
+                          -0.452191 0.843752 -0.289147,
+                          -0.350697 0.845296 -0.403095,
+                          -0.419395 0.814928 -0.4,
+                          -0.547556 0.734971 -0.4,
+                          -0.452191 0.843752 -0.289147,
+                          -0.350697 0.845296 -0.403095,
+                          -0.235481 0.960144 -0.150575,
+                          -0.182551 0.960546 -0.209826,
+                          -0.310712 -0.86224 -0.4,
+                          -0.182551 -0.960546 -0.209826,
+                          -0.350697 -0.845297 -0.403095,
+                          -0.184306 -0.89701 -0.401751,
+                          -0.0946217 -0.973912 -0.206256,
+                          -0.182551 -0.960546 -0.209826,
+                          -0.222347 -0.889136 -0.4,
+                          -0.184306 -0.89701 -0.401751,
+                          -0.182551 -0.960546 -0.209826,
+                          -0.310712 -0.86224 -0.4,
+                          -0.222347 -0.889136 -0.4,
+                          -0.182551 -0.960546 -0.209826,
+                          -0.147573 -0.904556 -0.4,
+                          -0.0946217 -0.973912 -0.206256,
+                          -0.184306 -0.89701 -0.401751,
+                          -0.0582617 -0.914157 -0.401152,
+                          -0.0297769 -0.978304 -0.205024,
+                          -0.0946217 -0.973912 -0.206256,
+                          -0.0741014 -0.913515 -0.4,
+                          -0.0582617 -0.914157 -0.401152,
+                          -0.0946217 -0.973912 -0.206256,
+                          -0.147573 -0.904556 -0.4,
+                          -0.0741014 -0.913515 -0.4,
+                          -0.0946217 -0.973912 -0.206256,
+                          3.18356e-16 -0.916515 -0.4,
+                          -0.0297769 -0.978304 -0.205024,
+                          -0.0582617 -0.914157 -0.401152,
+                          3.18356e-16 -0.916515 -0.4,
+                          0.0292426 -0.978315 -0.205049,
+                          -0.0297769 -0.978304 -0.205024,
+                          3.18356e-16 -0.916515 -0.4,
+                          0.0572169 -0.914199 -0.401206,
+                          0.0292426 -0.978315 -0.205049,
+                          0.0939735 -0.973978 -0.206241,
+                          0.0292426 -0.978315 -0.205049,
+                          0.0572169 -0.914199 -0.401206,
+                          0.0740972 -0.913515 -0.4,
+                          0.0939735 -0.973978 -0.206241,
+                          0.0572169 -0.914199 -0.401206,
+                          0.147565 -0.904558 -0.4,
+                          0.183056 -0.897267 -0.401748,
+                          0.0939735 -0.973978 -0.206241,
+                          0.181538 -0.960755 -0.209748,
+                          0.0939735 -0.973978 -0.206241,
+                          0.183056 -0.897267 -0.401748,
+                          0.0740972 -0.913515 -0.4,
+                          0.147565 -0.904558 -0.4,
+                          0.0939735 -0.973978 -0.206241,
+                          0.222338 -0.889138 -0.4,
+                          0.181538 -0.960755 -0.209748,
+                          0.183056 -0.897267 -0.401748,
+                          0.310702 -0.862244 -0.4,
+                          0.348827 -0.8461 -0.403032,
+                          0.181538 -0.960755 -0.209748,
+                          0.233924 -0.960547 -0.150429,
+                          0.181538 -0.960755 -0.209748,
+                          0.348827 -0.8461 -0.403032,
+                          0.222338 -0.889138 -0.4,
+                          0.310702 -0.862244 -0.4,
+                          0.181538 -0.960755 -0.209748,
+                          0.449391 -0.845301 -0.288987,
+                          0.233924 -0.960547 -0.150429,
+                          0.348827 -0.8461 -0.403032,
+                          0.419395 -0.814928 -0.4,
+                          0.449391 -0.845301 -0.288987,
+                          0.348827 -0.8461 -0.403032,
+                          0.479746 -0.866025 -0.140866,
+                          0.233924 -0.960547 -0.150429,
+                          0.449391 -0.845301 -0.288987,
+                          0.479746 -0.866025 -0.140866,
+                          0.248335 -0.965926 -0.0729178,
+                          0.233924 -0.960547 -0.150429,
+                          0.547556 -0.734971 -0.4,
+                          0.629398 -0.663356 -0.404743,
+                          0.449391 -0.845301 -0.288987,
+                          0.678464 -0.707107 -0.199215,
+                          0.449391 -0.845301 -0.288987,
+                          0.629398 -0.663356 -0.404743,
+                          0.419395 -0.814928 -0.4,
+                          0.547556 -0.734971 -0.4,
+                          0.449391 -0.845301 -0.288987,
+                          0.678464 -0.707107 -0.199215,
+                          0.479746 -0.866025 -0.140866,
+                          0.449391 -0.845301 -0.288987,
+                          0.690312 -0.602884 -0.4,
+                          0.678464 -0.707107 -0.199215,
+                          0.629398 -0.663356 -0.404743,
+                          0.281733 -0.959493 5.32413e-16,
+                          0.248335 -0.965926 -0.0729178,
+                          0.479746 -0.866025 -0.140866,
+                          0.540881 -0.841099 6.13671e-16,
+                          0.479746 -0.866025 -0.140866,
+                          0.678464 -0.707107 -0.199215,
+                          0.540881 -0.841099 6.13671e-16,
+                          0.281733 -0.959493 5.32413e-16,
+                          0.479746 -0.866025 -0.140866,
+                          0.690312 -0.602884 -0.4,
+                          0.830945 -0.5 -0.243988,
+                          0.678464 -0.707107 -0.199215,
+                          0.756123 -0.654429 6.45114e-16,
+                          0.678464 -0.707107 -0.199215,
+                          0.830945 -0.5 -0.243988,
+                          0.756123 -0.654429 6.45114e-16,
+                          0.540881 -0.841099 6.13671e-16,
+                          0.678464 -0.707107 -0.199215,
+                          0.827737 -0.393513 -0.4,
+                          0.926799 -0.258819 -0.272133,
+                          0.830945 -0.5 -0.243988,
+                          0.909988 -0.414635 6.2419e-16,
+                          0.830945 -0.5 -0.243988,
+                          0.926799 -0.258819 -0.272133,
+                          0.690312 -0.602884 -0.4,
+                          0.827737 -0.393513 -0.4,
+                          0.830945 -0.5 -0.243988,
+                          0.909988 -0.414635 6.2419e-16,
+                          0.756123 -0.654429 6.45114e-16,
+                          0.830945 -0.5 -0.243988,
+                          0.906522 -0.134971 -0.4,
+                          0.959493 1.73272e-17 -0.281733,
+                          0.926799 -0.258819 -0.272133,
+                          0.989983 -0.141184 5.52597e-16,
+                          0.926799 -0.258819 -0.272133,
+                          0.959493 1.73272e-17 -0.281733,
+                          0.827737 -0.393513 -0.4,
+                          0.906522 -0.134971 -0.4,
+                          0.926799 -0.258819 -0.272133,
+                          0.989983 -0.141184 5.52597e-16,
+                          0.909988 -0.414635 6.2419e-16,
+                          0.926799 -0.258819 -0.272133,
+                          0.906526 0.134944 -0.4,
+                          0.926799 0.258819 -0.272133,
+                          0.959493 1.73272e-17 -0.281733,
+                          0.989617 0.143728 4.36147e-16,
+                          0.959493 1.73272e-17 -0.281733,
+                          0.926799 0.258819 -0.272133,
+                          0.906522 -0.134971 -0.4,
+                          0.906526 0.134944 -0.4,
+                          0.959493 1.73272e-17 -0.281733,
+                          0.989617 0.143728 4.36147e-16,
+                          0.989983 -0.141184 5.52597e-16,
+                          0.959493 1.73272e-17 -0.281733,
+                          0.827748 0.393488 -0.4,
+                          0.830945 0.5 -0.243988,
+                          0.926799 0.258819 -0.272133,
+                          0.908919 0.416973 2.84293e-16,
+                          0.926799 0.258819 -0.272133,
+                          0.830945 0.5 -0.243988,
+                          0.906526 0.134944 -0.4,
+                          0.827748 0.393488 -0.4,
+                          0.926799 0.258819 -0.272133,
+                          0.908919 0.416973 2.84293e-16,
+                          0.989617 0.143728 4.36147e-16,
+                          0.926799 0.258819 -0.272133,
+                          0.629398 0.663355 -0.404744,
+                          0.678464 0.707107 -0.199215,
+                          0.830945 0.5 -0.243988,
+                          0.754439 0.65637 1.09361e-16,
+                          0.830945 0.5 -0.243988,
+                          0.678464 0.707107 -0.199215,
+                          0.690327 0.602867 -0.4,
+                          0.629398 0.663355 -0.404744,
+                          0.830945 0.5 -0.243988,
+                          0.827748 0.393488 -0.4,
+                          0.690327 0.602867 -0.4,
+                          0.830945 0.5 -0.243988,
+                          0.754439 0.65637 1.09361e-16,
+                          0.908919 0.416973 2.84293e-16,
+                          0.830945 0.5 -0.243988,
+                          0.449391 0.845301 -0.288988,
+                          0.479746 0.866025 -0.140866,
+                          0.678464 0.707107 -0.199215,
+                          0.538717 0.842487 -7.44477e-17,
+                          0.678464 0.707107 -0.199215,
+                          0.479746 0.866025 -0.140866,
+                          0.629398 0.663355 -0.404744,
+                          0.449391 0.845301 -0.288988,
+                          0.678464 0.707107 -0.199215,
+                          0.538717 0.842487 -7.44477e-17,
+                          0.754439 0.65637 1.09361e-16,
+                          0.678464 0.707107 -0.199215,
+                          0.233925 0.960547 -0.150429,
+                          0.248335 0.965926 -0.0729178,
+                          0.479746 0.866025 -0.140866,
+                          0.279265 0.960214 -2.52214e-16,
+                          0.479746 0.866025 -0.140866,
+                          0.248335 0.965926 -0.0729178,
+                          0.449391 0.845301 -0.288988,
+                          0.233925 0.960547 -0.150429,
+                          0.479746 0.866025 -0.140866,
+                          0.279265 0.960214 -2.52214e-16,
+                          0.538717 0.842487 -7.44477e-17,
+                          0.479746 0.866025 -0.140866,
+                          0.348826 0.8461 -0.403032,
+                          0.233925 0.960547 -0.150429,
+                          0.449391 0.845301 -0.288988,
+                          0.348826 0.8461 -0.403032,
+                          0.181538 0.960755 -0.209748,
+                          0.233925 0.960547 -0.150429,
+                          0.54757 0.734961 -0.4,
+                          0.449391 0.845301 -0.288988,
+                          0.629398 0.663355 -0.404744,
+                          0.419407 0.814922 -0.4,
+                          0.348826 0.8461 -0.403032,
+                          0.449391 0.845301 -0.288988,
+                          0.54757 0.734961 -0.4,
+                          0.419407 0.814922 -0.4,
+                          0.449391 0.845301 -0.288988,
+                          0.522451 -0.841099 0.13999,
+                          0.281733 -0.959493 5.32413e-16,
+                          0.540881 -0.841099 6.13671e-16,
+                          0.522451 -0.841099 0.13999,
+                          0.272133 -0.959493 0.0729178,
+                          0.281733 -0.959493 5.32413e-16,
+                          0.730359 -0.654429 0.195699,
+                          0.540881 -0.841099 6.13671e-16,
+                          0.756123 -0.654429 6.45114e-16,
+                          0.730359 -0.654429 0.195699,
+                          0.522451 -0.841099 0.13999,
+                          0.540881 -0.841099 6.13671e-16,
+                          0.881095 -0.414635 0.227485,
+                          0.756123 -0.654429 6.45114e-16,
+                          0.909988 -0.414635 6.2419e-16,
+                          0.881095 -0.414635 0.227485,
+                          0.730359 -0.654429 0.195699,
+                          0.756123 -0.654429 6.45114e-16,
+                          0.965308 -0.141184 0.219653,
+                          0.909988 -0.414635 6.2419e-16,
+                          0.989983 -0.141184 5.52597e-16,
+                          0.965308 -0.141184 0.219653,
+                          0.881095 -0.414635 0.227485,
+                          0.909988 -0.414635 6.2419e-16,
+                          0.964932 0.143728 0.219654,
+                          0.989983 -0.141184 5.52597e-16,
+                          0.989617 0.143728 4.36147e-16,
+                          0.964932 0.143728 0.219654,
+                          0.965308 -0.141184 0.219653,
+                          0.989983 -0.141184 5.52597e-16,
+                          0.879924 0.416973 0.227745,
+                          0.989617 0.143728 4.36147e-16,
+                          0.908919 0.416973 2.84293e-16,
+                          0.879924 0.416973 0.227745,
+                          0.964932 0.143728 0.219654,
+                          0.989617 0.143728 4.36147e-16,
+                          0.728732 0.65637 0.195263,
+                          0.908919 0.416973 2.84293e-16,
+                          0.754439 0.65637 1.09361e-16,
+                          0.728732 0.65637 0.195263,
+                          0.879924 0.416973 0.227745,
+                          0.908919 0.416973 2.84293e-16,
+                          0.520361 0.842487 0.13943,
+                          0.754439 0.65637 1.09361e-16,
+                          0.538717 0.842487 -7.44477e-17,
+                          0.520361 0.842487 0.13943,
+                          0.728732 0.65637 0.195263,
+                          0.754439 0.65637 1.09361e-16,
+                          0.26975 0.960214 0.0722792,
+                          0.538717 0.842487 -7.44477e-17,
+                          0.279265 0.960214 -2.52214e-16,
+                          0.520361 0.842487 0.13943,
+                          0.538717 0.842487 -7.44477e-17,
+                          0.26975 0.960214 0.0722792,
+                          0.310712 0.86224 -0.4,
+                          0.181538 0.960755 -0.209748,
+                          0.348826 0.8461 -0.403032,
+                          0.183056 0.897267 -0.401748,
+                          0.0939735 0.973978 -0.206241,
+                          0.181538 0.960755 -0.209748,
+                          0.222347 0.889136 -0.4,
+                          0.183056 0.897267 -0.401748,
+                          0.181538 0.960755 -0.209748,
+                          0.310712 0.86224 -0.4,
+                          0.222347 0.889136 -0.4,
+                          0.181538 0.960755 -0.209748,
+                          0.147573 0.904556 -0.4,
+                          0.0939735 0.973978 -0.206241,
+                          0.183056 0.897267 -0.401748,
+                          0.0572169 0.914199 -0.401206,
+                          0.0292426 0.978315 -0.205049,
+                          0.0939735 0.973978 -0.206241,
+                          0.0741014 0.913515 -0.4,
+                          0.0572169 0.914199 -0.401206,
+                          0.0939735 0.973978 -0.206241,
+                          0.147573 0.904556 -0.4,
+                          0.0741014 0.913515 -0.4,
+                          0.0939735 0.973978 -0.206241,
+                          -0.0297769 0.978304 -0.205024,
+                          0.0292426 0.978315 -0.205049,
+                          0.0572169 0.914199 -0.401206,
+                          -3.13469e-16 0.916515 -0.4,
+                          -0.0297769 0.978304 -0.205024,
+                          0.0572169 0.914199 -0.401206,
+                          -3.13469e-16 0.916515 -0.4,
+                          -0.0582617 0.914157 -0.401152,
+                          -0.0297769 0.978304 -0.205024,
+                          -0.0946217 0.973912 -0.206256,
+                          -0.0297769 0.978304 -0.205024,
+                          -0.0582617 0.914157 -0.401152,
+                          -0.0740972 0.913515 -0.4,
+                          -0.0946217 0.973912 -0.206256,
+                          -0.0582617 0.914157 -0.401152,
+                          -0.147565 0.904558 -0.4,
+                          -0.184306 0.89701 -0.401751,
+                          -0.0946217 0.973912 -0.206256,
+                          -0.182551 0.960546 -0.209826,
+                          -0.0946217 0.973912 -0.206256,
+                          -0.184306 0.89701 -0.401751,
+                          -0.0740972 0.913515 -0.4,
+                          -0.147565 0.904558 -0.4,
+                          -0.0946217 0.973912 -0.206256,
+                          -0.222338 0.889138 -0.4,
+                          -0.182551 0.960546 -0.209826,
+                          -0.184306 0.89701 -0.401751,
+                          -0.310702 0.862244 -0.4,
+                          -0.350697 0.845296 -0.403095,
+                          -0.182551 0.960546 -0.209826,
+                          -0.222338 0.889138 -0.4,
+                          -0.310702 0.862244 -0.4,
+                          -0.182551 0.960546 -0.209826,
+                          -0.522451 0.841099 -0.13999,
+                          -0.272133 0.959493 -0.0729178,
+                          -0.243988 0.959493 -0.140866,
+                          -0.468417 0.841099 -0.270441,
+                          -0.243988 0.959493 -0.140866,
+                          -0.199215 0.959493 -0.199215,
+                          -0.522451 0.841099 -0.13999,
+                          -0.243988 0.959493 -0.140866,
+                          -0.468417 0.841099 -0.270441,
+                          -0.382461 0.841099 -0.382461,
+                          -0.199215 0.959493 -0.199215,
+                          -0.140866 0.959493 -0.243988,
+                          -0.468417 0.841099 -0.270441,
+                          -0.199215 0.959493 -0.199215,
+                          -0.382461 0.841099 -0.382461,
+                          -0.270441 0.841099 -0.468417,
+                          -0.140866 0.959493 -0.243988,
+                          -0.0729178 0.959493 -0.272133,
+                          -0.382461 0.841099 -0.382461,
+                          -0.140866 0.959493 -0.243988,
+                          -0.270441 0.841099 -0.468417,
+                          -0.13999 0.841099 -0.522451,
+                          -0.0729178 0.959493 -0.272133,
+                          -3.16162e-16 0.959493 -0.281733,
+                          -0.270441 0.841099 -0.468417,
+                          -0.0729178 0.959493 -0.272133,
+                          -0.13999 0.841099 -0.522451,
+                          -2.13454e-16 0.841099 -0.540881,
+                          -3.16162e-16 0.959493 -0.281733,
+                          0.0729178 0.959493 -0.272133,
+                          -0.13999 0.841099 -0.522451,
+                          -3.16162e-16 0.959493 -0.281733,
+                          -2.13454e-16 0.841099 -0.540881,
+                          0.13999 0.841099 -0.522451,
+                          0.0729178 0.959493 -0.272133,
+                          0.140866 0.959493 -0.243988,
+                          -2.13454e-16 0.841099 -0.540881,
+                          0.0729178 0.959493 -0.272133,
+                          0.13999 0.841099 -0.522451,
+                          0.270441 0.841099 -0.468417,
+                          0.140866 0.959493 -0.243988,
+                          0.199215 0.959493 -0.199215,
+                          0.13999 0.841099 -0.522451,
+                          0.140866 0.959493 -0.243988,
+                          0.270441 0.841099 -0.468417,
+                          0.382461 0.841099 -0.382461,
+                          0.199215 0.959493 -0.199215,
+                          0.243988 0.959493 -0.140866,
+                          0.270441 0.841099 -0.468417,
+                          0.199215 0.959493 -0.199215,
+                          0.382461 0.841099 -0.382461,
+                          0.468417 0.841099 -0.270441,
+                          0.243988 0.959493 -0.140866,
+                          0.272133 0.959493 -0.0729178,
+                          0.382461 0.841099 -0.382461,
+                          0.243988 0.959493 -0.140866,
+                          0.468417 0.841099 -0.270441,
+                          0.468417 0.841099 -0.270441,
+                          0.272133 0.959493 -0.0729178,
+                          0.522451 0.841099 -0.13999,
+                          0.520361 -0.842487 -0.13943,
+                          0.26975 -0.960214 -0.0722792,
+                          0.241851 -0.960214 -0.139633,
+                          0.466543 -0.842487 -0.269359,
+                          0.241851 -0.960214 -0.139633,
+                          0.19747 -0.960214 -0.19747,
+                          0.466543 -0.842487 -0.269359,
+                          0.520361 -0.842487 -0.13943,
+                          0.241851 -0.960214 -0.139633,
+                          0.380931 -0.842487 -0.380931,
+                          0.19747 -0.960214 -0.19747,
+                          0.139633 -0.960214 -0.241851,
+                          0.380931 -0.842487 -0.380931,
+                          0.466543 -0.842487 -0.269359,
+                          0.19747 -0.960214 -0.19747,
+                          0.269359 -0.842487 -0.466543,
+                          0.139633 -0.960214 -0.241851,
+                          0.0722792 -0.960214 -0.26975,
+                          0.269359 -0.842487 -0.466543,
+                          0.380931 -0.842487 -0.380931,
+                          0.139633 -0.960214 -0.241851,
+                          0.13943 -0.842487 -0.520361,
+                          0.0722792 -0.960214 -0.26975,
+                          4.38023e-16 -0.960214 -0.279265,
+                          0.13943 -0.842487 -0.520361,
+                          0.269359 -0.842487 -0.466543,
+                          0.0722792 -0.960214 -0.26975,
+                          4.47966e-16 -0.842487 -0.538717,
+                          4.38023e-16 -0.960214 -0.279265,
+                          -0.0722792 -0.960214 -0.26975,
+                          4.47966e-16 -0.842487 -0.538717,
+                          0.13943 -0.842487 -0.520361,
+                          4.38023e-16 -0.960214 -0.279265,
+                          -0.13943 -0.842487 -0.520361,
+                          -0.0722792 -0.960214 -0.26975,
+                          -0.139633 -0.960214 -0.241851,
+                          -0.13943 -0.842487 -0.520361,
+                          4.47966e-16 -0.842487 -0.538717,
+                          -0.0722792 -0.960214 -0.26975,
+                          -0.269359 -0.842487 -0.466543,
+                          -0.139633 -0.960214 -0.241851,
+                          -0.19747 -0.960214 -0.19747,
+                          -0.269359 -0.842487 -0.466543,
+                          -0.13943 -0.842487 -0.520361,
+                          -0.139633 -0.960214 -0.241851,
+                          -0.380931 -0.842487 -0.380931,
+                          -0.19747 -0.960214 -0.19747,
+                          -0.241851 -0.960214 -0.139633,
+                          -0.380931 -0.842487 -0.380931,
+                          -0.269359 -0.842487 -0.466543,
+                          -0.19747 -0.960214 -0.19747,
+                          -0.466543 -0.842487 -0.269359,
+                          -0.241851 -0.960214 -0.139633,
+                          -0.26975 -0.960214 -0.0722792,
+                          -0.466543 -0.842487 -0.269359,
+                          -0.380931 -0.842487 -0.380931,
+                          -0.241851 -0.960214 -0.139633,
+                          -0.520361 -0.842487 -0.13943,
+                          -0.466543 -0.842487 -0.269359,
+                          -0.26975 -0.960214 -0.0722792,
+                          0.664112 -0.65637 -0.357958,
+                          0.520361 -0.842487 -0.13943,
+                          0.466543 -0.842487 -0.269359,
+                          0.664112 -0.65637 -0.357958,
+                          0.731509 -0.65637 -0.184589,
+                          0.520361 -0.842487 -0.13943,
+                          0.556345 -0.65637 -0.509567,
+                          0.466543 -0.842487 -0.269359,
+                          0.380931 -0.842487 -0.380931,
+                          0.556345 -0.65637 -0.509567,
+                          0.664112 -0.65637 -0.357958,
+                          0.466543 -0.842487 -0.269359,
+                          0.414759 -0.65637 -0.630201,
+                          0.380931 -0.842487 -0.380931,
+                          0.269359 -0.842487 -0.466543,
+                          0.414759 -0.65637 -0.630201,
+                          0.556345 -0.65637 -0.509567,
+                          0.380931 -0.842487 -0.380931,
+                          0.247961 -0.65637 -0.712526,
+                          0.269359 -0.842487 -0.466543,
+                          0.13943 -0.842487 -0.520361,
+                          0.247961 -0.65637 -0.712526,
+                          0.414759 -0.65637 -0.630201,
+                          0.269359 -0.842487 -0.466543,
+                          0.0660903 -0.65637 -0.751538,
+                          0.13943 -0.842487 -0.520361,
+                          4.47966e-16 -0.842487 -0.538717,
+                          0.0660903 -0.65637 -0.751538,
+                          0.247961 -0.65637 -0.712526,
+                          0.13943 -0.842487 -0.520361,
+                          -0.0647781 -0.65637 -0.751653,
+                          4.47966e-16 -0.842487 -0.538717,
+                          -0.13943 -0.842487 -0.520361,
+                          0.00183532 -0.666659 -0.74536,
+                          0.0660903 -0.65637 -0.751538,
+                          4.47966e-16 -0.842487 -0.538717,
+                          -0.0647781 -0.65637 -0.751653,
+                          0.00183532 -0.666659 -0.74536,
+                          4.47966e-16 -0.842487 -0.538717,
+                          -0.246924 -0.65637 -0.712886,
+                          -0.13943 -0.842487 -0.520361,
+                          -0.269359 -0.842487 -0.466543,
+                          -0.246924 -0.65637 -0.712886,
+                          -0.0647781 -0.65637 -0.751653,
+                          -0.13943 -0.842487 -0.520361,
+                          -0.414025 -0.65637 -0.630683,
+                          -0.269359 -0.842487 -0.466543,
+                          -0.380931 -0.842487 -0.380931,
+                          -0.414025 -0.65637 -0.630683,
+                          -0.246924 -0.65637 -0.712886,
+                          -0.269359 -0.842487 -0.466543,
+                          -0.5559 -0.65637 -0.510052,
+                          -0.380931 -0.842487 -0.380931,
+                          -0.466543 -0.842487 -0.269359,
+                          -0.5559 -0.65637 -0.510052,
+                          -0.414025 -0.65637 -0.630683,
+                          -0.380931 -0.842487 -0.380931,
+                          -0.663903 -0.65637 -0.358344,
+                          -0.466543 -0.842487 -0.269359,
+                          -0.520361 -0.842487 -0.13943,
+                          -0.663903 -0.65637 -0.358344,
+                          -0.5559 -0.65637 -0.510052,
+                          -0.466543 -0.842487 -0.269359,
+                          -0.731455 -0.65637 -0.184802,
+                          -0.663903 -0.65637 -0.358344,
+                          -0.520361 -0.842487 -0.13943,
+                          0.804271 -0.416973 -0.423417,
+                          0.731509 -0.65637 -0.184589,
+                          0.664112 -0.65637 -0.357958,
+                          0.804271 -0.416973 -0.423417,
+                          0.882369 -0.416973 -0.218079,
+                          0.731509 -0.65637 -0.184589,
+                          0.679187 -0.416973 -0.604019,
+                          0.664112 -0.65637 -0.357958,
+                          0.556345 -0.65637 -0.509567,
+                          0.679187 -0.416973 -0.604019,
+                          0.804271 -0.416973 -0.423417,
+                          0.664112 -0.65637 -0.357958,
+                          0.514424 -0.416973 -0.749334,
+                          0.556345 -0.65637 -0.509567,
+                          0.414759 -0.65637 -0.630201,
+                          0.514424 -0.416973 -0.749334,
+                          0.679187 -0.416973 -0.604019,
+                          0.556345 -0.65637 -0.509567,
+                          0.39925 -0.533834 -0.7454,
+                          0.414759 -0.65637 -0.630201,
+                          0.247961 -0.65637 -0.712526,
+                          0.39925 -0.533834 -0.7454,
+                          0.514424 -0.416973 -0.749334,
+                          0.414759 -0.65637 -0.630201,
+                          0.206231 -0.633966 -0.745356,
+                          0.247961 -0.65637 -0.712526,
+                          0.0660903 -0.65637 -0.751538,
+                          0.206231 -0.633966 -0.745356,
+                          0.39925 -0.533834 -0.7454,
+                          0.247961 -0.65637 -0.712526,
+                          0.309017 -0.951057 5.42612e-16,
+                          0.101941 -0.99479 4.56923e-16,
+                          0.00275329 -0.999996 4.09455e-16,
+                          0.309017 -0.951057 5.42612e-16,
+                          0.309347 -0.950949 5.42734e-16,
+                          0.101941 -0.99479 4.56923e-16,
+                          -1.04596e-13 -1 4.0808e-16,
+                          0.00275329 -0.999996 4.09455e-16,
+                          -0.0999324 -0.994994 3.56072e-16,
+                          -1.04596e-13 -1 4.0808e-16,
+                          0.309017 -0.951057 5.42612e-16,
+                          0.00275329 -0.999996 4.09455e-16,
+                          -0.202724 -0.635096 -0.745356,
+                          -0.0647781 -0.65637 -0.751653,
+                          -0.246924 -0.65637 -0.712886,
+                          -1.04596e-13 -1 4.0808e-16,
+                          -0.0999324 -0.994994 3.56072e-16,
+                          -0.304086 -0.952645 2.36715e-16,
+                          -0.395935 -0.53629 -0.745405,
+                          -0.246924 -0.65637 -0.712886,
+                          -0.414025 -0.65637 -0.630683,
+                          -0.395935 -0.53629 -0.745405,
+                          -0.202724 -0.635096 -0.745356,
+                          -0.246924 -0.65637 -0.712886,
+                          -0.514698 -0.416973 -0.749146,
+                          -0.414025 -0.65637 -0.630683,
+                          -0.5559 -0.65637 -0.510052,
+                          -0.514698 -0.416973 -0.749146,
+                          -0.395935 -0.53629 -0.745405,
+                          -0.414025 -0.65637 -0.630683,
+                          -0.679352 -0.416973 -0.603833,
+                          -0.5559 -0.65637 -0.510052,
+                          -0.663903 -0.65637 -0.358344,
+                          -0.679352 -0.416973 -0.603833,
+                          -0.514698 -0.416973 -0.749146,
+                          -0.5559 -0.65637 -0.510052,
+                          -0.804348 -0.416973 -0.42327,
+                          -0.663903 -0.65637 -0.358344,
+                          -0.731455 -0.65637 -0.184802,
+                          -0.804348 -0.416973 -0.42327,
+                          -0.679352 -0.416973 -0.603833,
+                          -0.663903 -0.65637 -0.358344,
+                          -0.882389 -0.416973 -0.217998,
+                          -0.804348 -0.416973 -0.42327,
+                          -0.731455 -0.65637 -0.184802,
+                          -0.309017 -0.951057 2.33601e-16,
+                          -0.304086 -0.952645 2.36715e-16,
+                          -0.593983 -0.804478 3.13047e-17,
+                          -0.309017 -0.951057 2.33601e-16,
+                          -1.04596e-13 -1 4.0808e-16,
+                          -0.304086 -0.952645 2.36715e-16,
+                          -0.587785 -0.809017 3.6256e-17,
+                          -0.593983 -0.804478 3.13047e-17,
+                          -0.77718 -0.629279 -1.31787e-16,
+                          -0.587785 -0.809017 3.6256e-17,
+                          -0.309017 -0.951057 2.33601e-16,
+                          -0.593983 -0.804478 3.13047e-17,
+                          -0.543092 -0.386646 -0.745356,
+                          -0.514698 -0.416973 -0.749146,
+                          -0.679352 -0.416973 -0.603833,
+                          -0.809017 -0.587785 -1.64638e-16,
+                          -0.77718 -0.629279 -1.31787e-16,
+                          -0.814639 -0.579969 -1.70638e-16,
+                          -0.809017 -0.587785 -1.64638e-16,
+                          -0.587785 -0.809017 3.6256e-17,
+                          -0.77718 -0.629279 -1.31787e-16,
+                          -0.791738 -0.143728 -0.593712,
+                          -0.679352 -0.416973 -0.603833,
+                          -0.804348 -0.416973 -0.42327,
+                          -0.635618 -0.201068 -0.74536,
+                          -0.543092 -0.386646 -0.745356,
+                          -0.679352 -0.416973 -0.603833,
+                          -0.647235 -0.143728 -0.748618,
+                          -0.635618 -0.201068 -0.74536,
+                          -0.679352 -0.416973 -0.603833,
+                          -0.791738 -0.143728 -0.593712,
+                          -0.647235 -0.143728 -0.748618,
+                          -0.679352 -0.416973 -0.603833,
+                          -0.89996 -0.143728 -0.411599,
+                          -0.804348 -0.416973 -0.42327,
+                          -0.882389 -0.416973 -0.217998,
+                          -0.89996 -0.143728 -0.411599,
+                          -0.791738 -0.143728 -0.593712,
+                          -0.804348 -0.416973 -0.42327,
+                          -0.966943 -0.143728 -0.210625,
+                          -0.89996 -0.143728 -0.411599,
+                          -0.882389 -0.416973 -0.217998,
+                          -0.951057 -0.309017 -3.49416e-16,
+                          -0.814639 -0.579969 -1.70638e-16,
+                          -0.953434 -0.301601 -3.53631e-16,
+                          -0.951057 -0.309017 -3.49416e-16,
+                          -0.809017 -0.587785 -1.64638e-16,
+                          -0.814639 -0.579969 -1.70638e-16,
+                          -0.951057 -0.309017 -3.49416e-16,
+                          -0.953434 -0.301601 -3.53631e-16,
+                          -0.976275 -0.216536 -3.99765e-16,
+                          -0.666667 -3.21339e-16 -0.745356,
+                          -0.647235 -0.143728 -0.748618,
+                          -0.791738 -0.143728 -0.593712,
+                          -0.951057 -0.309017 -3.49416e-16,
+                          -0.976275 -0.216536 -3.99765e-16,
+                          -1 -2.70682e-16 -4.99991e-16,
+                          -0.899654 0.141184 -0.413146,
+                          -0.791738 -0.143728 -0.593712,
+                          -0.89996 -0.143728 -0.411599,
+                          -0.790648 0.141184 -0.595771,
+                          -0.666667 -3.21339e-16 -0.745356,
+                          -0.791738 -0.143728 -0.593712,
+                          -0.899654 0.141184 -0.413146,
+                          -0.790648 0.141184 -0.595771,
+                          -0.791738 -0.143728 -0.593712,
+                          -0.967137 0.141184 -0.211453,
+                          -0.89996 -0.143728 -0.411599,
+                          -0.966943 -0.143728 -0.210625,
+                          -0.967137 0.141184 -0.211453,
+                          -0.899654 0.141184 -0.413146,
+                          -0.89996 -0.143728 -0.411599,
+                          -0.790648 0.141184 -0.595771,
+                          -0.64515 0.141184 -0.750898,
+                          -0.666667 -3.21339e-16 -0.745356,
+                          -1 -2.70682e-16 -4.99991e-16,
+                          -1 -2.70682e-16 -4.99991e-16,
+                          -0.976928 0.213568 -5.75608e-16,
+                          -0.951057 -0.309017 -3.49416e-16,
+                          -1 -2.70682e-16 -4.99991e-16,
+                          -1 -2.70682e-16 -4.99991e-16,
+                          -0.683507 0.414635 -0.600746,
+                          -0.64515 0.141184 -0.750898,
+                          -0.790648 0.141184 -0.595771,
+                          -0.683507 0.414635 -0.600746,
+                          -0.622561 0.238391 -0.745377,
+                          -0.64515 0.141184 -0.750898,
+                          -0.951057 0.309017 -6.01623e-16,
+                          -0.976928 0.213568 -5.75608e-16,
+                          -0.933867 0.357621 -6.12863e-16,
+                          -0.951057 0.309017 -6.01623e-16,
+                          -1 -2.70682e-16 -4.99991e-16,
+                          -0.976928 0.213568 -5.75608e-16,
+                          -0.806861 0.414635 -0.420775,
+                          -0.790648 0.141184 -0.595771,
+                          -0.899654 0.141184 -0.413146,
+                          -0.806861 0.414635 -0.420775,
+                          -0.683507 0.414635 -0.600746,
+                          -0.790648 0.141184 -0.595771,
+                          -0.88383 0.414635 -0.216614,
+                          -0.899654 0.141184 -0.413146,
+                          -0.967137 0.141184 -0.211453,
+                          -0.88383 0.414635 -0.216614,
+                          -0.806861 0.414635 -0.420775,
+                          -0.899654 0.141184 -0.413146,
+                          -0.683507 0.414635 -0.600746,
+                          -0.520857 0.414635 -0.746181,
+                          -0.622561 0.238391 -0.745377,
+                          -0.809017 0.587785 -6.44364e-16,
+                          -0.933867 0.357621 -6.12863e-16,
+                          -0.782522 0.622623 -6.45334e-16,
+                          -0.809017 0.587785 -6.44364e-16,
+                          -0.951057 0.309017 -6.01623e-16,
+                          -0.933867 0.357621 -6.12863e-16,
+                          -0.562976 0.654429 -0.504758,
+                          -0.520857 0.414635 -0.746181,
+                          -0.683507 0.414635 -0.600746,
+                          -0.424582 0.654429 -0.625662,
+                          -0.516008 0.422178 -0.74532,
+                          -0.520857 0.414635 -0.746181,
+                          -0.809017 0.587785 -6.44364e-16,
+                          -0.782522 0.622623 -6.45334e-16,
+                          -0.773972 0.63322 -6.45383e-16,
+                          -0.562976 0.654429 -0.504758,
+                          -0.424582 0.654429 -0.625662,
+                          -0.520857 0.414635 -0.746181,
+                          -0.668117 0.654429 -0.354038,
+                          -0.683507 0.414635 -0.600746,
+                          -0.806861 0.414635 -0.420775,
+                          -0.668117 0.654429 -0.354038,
+                          -0.562976 0.654429 -0.504758,
+                          -0.683507 0.414635 -0.600746,
+                          -0.733792 0.654429 -0.182406,
+                          -0.806861 0.414635 -0.420775,
+                          -0.88383 0.414635 -0.216614,
+                          -0.733792 0.654429 -0.182406,
+                          -0.668117 0.654429 -0.354038,
+                          -0.806861 0.414635 -0.420775,
+                          -0.424582 0.654429 -0.625662,
+                          -0.370237 0.554372 -0.745383,
+                          -0.516008 0.422178 -0.74532,
+                          -0.587785 0.809017 -6.24031e-16,
+                          -0.773972 0.63322 -6.45383e-16,
+                          -0.555367 0.831605 -6.1704e-16,
+                          -0.587785 0.809017 -6.24031e-16,
+                          -0.809017 0.587785 -6.44364e-16,
+                          -0.773972 0.63322 -6.45383e-16,
+                          -0.261109 0.654429 -0.709609,
+                          -0.194452 0.637741 -0.745302,
+                          -0.370237 0.554372 -0.745383,
+                          -0.309017 0.951057 -5.42612e-16,
+                          -0.555367 0.831605 -6.1704e-16,
+                          -0.291682 0.956515 -5.36173e-16,
+                          -0.424582 0.654429 -0.625662,
+                          -0.261109 0.654429 -0.709609,
+                          -0.370237 0.554372 -0.745383,
+                          -0.309017 0.951057 -5.42612e-16,
+                          -0.587785 0.809017 -6.24031e-16,
+                          -0.555367 0.831605 -6.1704e-16,
+                          -0.261109 0.654429 -0.709609,
+                          -0.0822117 0.654429 -0.751641,
+                          -0.194452 0.637741 -0.745302,
+                          -0.309017 0.951057 -5.42612e-16,
+                          -0.291682 0.956515 -5.36173e-16,
+                          -0.126014 0.992029 -4.67832e-16,
+                          -0.13999 0.841099 -0.522451,
+                          -0.0822117 0.654429 -0.751641,
+                          -0.261109 0.654429 -0.709609,
+                          -2.13454e-16 0.841099 -0.540881,
+                          7.43372e-05 0.666667 -0.745356,
+                          -0.0822117 0.654429 -0.751641,
+                          -1.05581e-13 1 -4.0808e-16,
+                          -0.126014 0.992029 -4.67832e-16,
+                          0.000111506 1 -4.08024e-16,
+                          -0.13999 0.841099 -0.522451,
+                          -2.13454e-16 0.841099 -0.540881,
+                          -0.0822117 0.654429 -0.751641,
+                          -1.05581e-13 1 -4.0808e-16,
+                          -0.309017 0.951057 -5.42612e-16,
+                          -0.126014 0.992029 -4.67832e-16,
+                          -0.270441 0.841099 -0.468417,
+                          -0.261109 0.654429 -0.709609,
+                          -0.424582 0.654429 -0.625662,
+                          -0.270441 0.841099 -0.468417,
+                          -0.13999 0.841099 -0.522451,
+                          -0.261109 0.654429 -0.709609,
+                          -0.382461 0.841099 -0.382461,
+                          -0.424582 0.654429 -0.625662,
+                          -0.562976 0.654429 -0.504758,
+                          -0.382461 0.841099 -0.382461,
+                          -0.270441 0.841099 -0.468417,
+                          -0.424582 0.654429 -0.625662,
+                          -0.468417 0.841099 -0.270441,
+                          -0.562976 0.654429 -0.504758,
+                          -0.668117 0.654429 -0.354038,
+                          -0.468417 0.841099 -0.270441,
+                          -0.382461 0.841099 -0.382461,
+                          -0.562976 0.654429 -0.504758,
+                          -0.522451 0.841099 -0.13999,
+                          -0.668117 0.654429 -0.354038,
+                          -0.733792 0.654429 -0.182406,
+                          -0.522451 0.841099 -0.13999,
+                          -0.468417 0.841099 -0.270441,
+                          -0.668117 0.654429 -0.354038,
+                          0.13999 0.841099 -0.522451,
+                          0.0821343 0.654429 -0.751649,
+                          7.43372e-05 0.666667 -0.745356,
+                          -1.05581e-13 1 -4.0808e-16,
+                          0.000111506 1 -4.08024e-16,
+                          0.125908 0.992042 -3.41879e-16,
+                          -2.13454e-16 0.841099 -0.540881,
+                          0.13999 0.841099 -0.522451,
+                          7.43372e-05 0.666667 -0.745356,
+                          0.13999 0.841099 -0.522451,
+                          0.261048 0.654429 -0.709632,
+                          0.0821343 0.654429 -0.751649,
+                          0.194812 0.63763 -0.745303,
+                          0.0821343 0.654429 -0.751649,
+                          0.261048 0.654429 -0.709632,
+                          -1.05581e-13 1 -4.0808e-16,
+                          0.125908 0.992042 -3.41879e-16,
+                          0.292224 0.95635 -2.44157e-16,
+                          0.270441 0.841099 -0.468417,
+                          0.424539 0.654429 -0.625691,
+                          0.261048 0.654429 -0.709632,
+                          0.370468 0.554218 -0.745383,
+                          0.261048 0.654429 -0.709632,
+                          0.424539 0.654429 -0.625691,
+                          0.13999 0.841099 -0.522451,
+                          0.270441 0.841099 -0.468417,
+                          0.261048 0.654429 -0.709632,
+                          0.370468 0.554218 -0.745383,
+                          0.194812 0.63763 -0.745303,
+                          0.261048 0.654429 -0.709632,
+                          0.382461 0.841099 -0.382461,
+                          0.56295 0.654429 -0.504787,
+                          0.424539 0.654429 -0.625691,
+                          0.516113 0.422051 -0.745319,
+                          0.424539 0.654429 -0.625691,
+                          0.56295 0.654429 -0.504787,
+                          0.270441 0.841099 -0.468417,
+                          0.382461 0.841099 -0.382461,
+                          0.424539 0.654429 -0.625691,
+                          0.516113 0.422051 -0.745319,
+                          0.370468 0.554218 -0.745383,
+                          0.424539 0.654429 -0.625691,
+                          0.468417 0.841099 -0.270441,
+                          0.668104 0.654429 -0.354061,
+                          0.56295 0.654429 -0.504787,
+                          0.68352 0.414635 -0.600731,
+                          0.56295 0.654429 -0.504787,
+                          0.668104 0.654429 -0.354061,
+                          0.382461 0.841099 -0.382461,
+                          0.468417 0.841099 -0.270441,
+                          0.56295 0.654429 -0.504787,
+                          0.520879 0.414635 -0.746165,
+                          0.56295 0.654429 -0.504787,
+                          0.68352 0.414635 -0.600731,
+                          0.516113 0.422051 -0.745319,
+                          0.56295 0.654429 -0.504787,
+                          0.520879 0.414635 -0.746165,
+                          0.522451 0.841099 -0.13999,
+                          0.733789 0.654429 -0.182419,
+                          0.668104 0.654429 -0.354061,
+                          0.806868 0.414635 -0.420763,
+                          0.668104 0.654429 -0.354061,
+                          0.733789 0.654429 -0.182419,
+                          0.468417 0.841099 -0.270441,
+                          0.522451 0.841099 -0.13999,
+                          0.668104 0.654429 -0.354061,
+                          0.68352 0.414635 -0.600731,
+                          0.668104 0.654429 -0.354061,
+                          0.806868 0.414635 -0.420763,
+                          0.806868 0.414635 -0.420763,
+                          0.733789 0.654429 -0.182419,
+                          0.883832 0.414635 -0.216608,
+                          0.899985 -0.143728 -0.411544,
+                          0.882369 -0.416973 -0.218079,
+                          0.804271 -0.416973 -0.423417,
+                          0.899985 -0.143728 -0.411544,
+                          0.96695 -0.143728 -0.210596,
+                          0.882369 -0.416973 -0.218079,
+                          0.791792 -0.143728 -0.593639,
+                          0.804271 -0.416973 -0.423417,
+                          0.679187 -0.416973 -0.604019,
+                          0.791792 -0.143728 -0.593639,
+                          0.899985 -0.143728 -0.411544,
+                          0.804271 -0.416973 -0.423417,
+                          0.544929 -0.384053 -0.745356,
+                          0.679187 -0.416973 -0.604019,
+                          0.514424 -0.416973 -0.749334,
+                          0.647327 -0.143728 -0.748539,
+                          0.791792 -0.143728 -0.593639,
+                          0.679187 -0.416973 -0.604019,
+                          0.636046 -0.199711 -0.745359,
+                          0.647327 -0.143728 -0.748539,
+                          0.679187 -0.416973 -0.604019,
+                          0.544929 -0.384053 -0.745356,
+                          0.636046 -0.199711 -0.745359,
+                          0.679187 -0.416973 -0.604019,
+                          0.809017 -0.587785 6.44364e-16,
+                          0.777038 -0.629453 6.45379e-16,
+                          0.59895 -0.800786 6.26254e-16,
+                          0.809017 -0.587785 6.44364e-16,
+                          0.817394 -0.576079 6.43776e-16,
+                          0.777038 -0.629453 6.45379e-16,
+                          0.587785 -0.809017 6.24031e-16,
+                          0.59895 -0.800786 6.26254e-16,
+                          0.309347 -0.950949 5.42734e-16,
+                          0.587785 -0.809017 6.24031e-16,
+                          0.809017 -0.587785 6.44364e-16,
+                          0.59895 -0.800786 6.26254e-16,
+                          0.309017 -0.951057 5.42612e-16,
+                          0.587785 -0.809017 6.24031e-16,
+                          0.309347 -0.950949 5.42734e-16,
+                          0.967137 0.141184 -0.211453,
+                          0.96695 -0.143728 -0.210596,
+                          0.899985 -0.143728 -0.411544,
+                          0.899654 0.141184 -0.413146,
+                          0.899985 -0.143728 -0.411544,
+                          0.791792 -0.143728 -0.593639,
+                          0.899654 0.141184 -0.413146,
+                          0.967137 0.141184 -0.211453,
+                          0.899985 -0.143728 -0.411544,
+                          0.790648 0.141184 -0.595771,
+                          0.791792 -0.143728 -0.593639,
+                          0.647327 -0.143728 -0.748539,
+                          0.790648 0.141184 -0.595771,
+                          0.899654 0.141184 -0.413146,
+                          0.791792 -0.143728 -0.593639,
+                          1 1.48222e-16 4.99991e-16,
+                          0.976281 -0.216509 5.76485e-16,
+                          0.954075 -0.299567 5.99276e-16,
+                          0.666667 2.02852e-16 -0.745356,
+                          0.790648 0.141184 -0.595771,
+                          0.647327 -0.143728 -0.748539,
+                          1 1.48222e-16 4.99991e-16,
+                          1 1.48222e-16 4.99991e-16,
+                          0.976281 -0.216509 5.76485e-16,
+                          0.951057 -0.309017 6.01623e-16,
+                          0.954075 -0.299567 5.99276e-16,
+                          0.817394 -0.576079 6.43776e-16,
+                          0.951057 -0.309017 6.01623e-16,
+                          1 1.48222e-16 4.99991e-16,
+                          0.954075 -0.299567 5.99276e-16,
+                          0.809017 -0.587785 6.44364e-16,
+                          0.951057 -0.309017 6.01623e-16,
+                          0.817394 -0.576079 6.43776e-16,
+                          0.883832 0.414635 -0.216608,
+                          0.967137 0.141184 -0.211453,
+                          0.899654 0.141184 -0.413146,
+                          0.806868 0.414635 -0.420763,
+                          0.899654 0.141184 -0.413146,
+                          0.790648 0.141184 -0.595771,
+                          0.806868 0.414635 -0.420763,
+                          0.883832 0.414635 -0.216608,
+                          0.899654 0.141184 -0.413146,
+                          0.666667 2.02852e-16 -0.745356,
+                          0.64515 0.141184 -0.750899,
+                          0.790648 0.141184 -0.595771,
+                          0.68352 0.414635 -0.600731,
+                          0.790648 0.141184 -0.595771,
+                          0.64515 0.141184 -0.750899,
+                          0.68352 0.414635 -0.600731,
+                          0.806868 0.414635 -0.420763,
+                          0.790648 0.141184 -0.595771,
+                          0.951057 0.309017 3.49416e-16,
+                          0.976928 0.213568 4.01303e-16,
+                          1 2.70682e-16 4.99991e-16,
+                          0.622557 0.238405 -0.745377,
+                          0.68352 0.414635 -0.600731,
+                          0.64515 0.141184 -0.750899,
+                          0.951057 0.309017 3.49416e-16,
+                          0.933859 0.35764 3.20976e-16,
+                          0.976928 0.213568 4.01303e-16,
+                          0.951057 0.309017 3.49416e-16,
+                          1 2.70682e-16 4.99991e-16,
+                          1 1.55517e-16 4.99991e-16,
+                          0.622557 0.238405 -0.745377,
+                          0.520879 0.414635 -0.746165,
+                          0.68352 0.414635 -0.600731,
+                          0.809017 0.587785 1.64638e-16,
+                          0.782533 0.62261 1.37185e-16,
+                          0.933859 0.35764 3.20976e-16,
+                          0.587785 0.809017 -3.6256e-17,
+                          0.774128 0.633029 1.28731e-16,
+                          0.782533 0.62261 1.37185e-16,
+                          0.809017 0.587785 1.64638e-16,
+                          0.587785 0.809017 -3.6256e-17,
+                          0.782533 0.62261 1.37185e-16,
+                          0.951057 0.309017 3.49416e-16,
+                          0.809017 0.587785 1.64638e-16,
+                          0.933859 0.35764 3.20976e-16,
+                          0.309017 0.951057 -2.33601e-16,
+                          0.292224 0.95635 -2.44157e-16,
+                          0.555713 0.831374 -6.14151e-17,
+                          0.309017 0.951057 -2.33601e-16,
+                          -1.05581e-13 1 -4.0808e-16,
+                          0.292224 0.95635 -2.44157e-16,
+                          0.587785 0.809017 -3.6256e-17,
+                          0.555713 0.831374 -6.14151e-17,
+                          0.774128 0.633029 1.28731e-16,
+                          0.587785 0.809017 -3.6256e-17,
+                          0.309017 0.951057 -2.33601e-16,
+                          0.555713 0.831374 -6.14151e-17,
+                          0.520361 0.842487 0.13943,
+                          0.26975 0.960214 0.0722792,
+                          0.241851 0.960214 0.139633,
+                          0.466543 0.842487 0.269359,
+                          0.241851 0.960214 0.139633,
+                          0.19747 0.960214 0.19747,
+                          0.520361 0.842487 0.13943,
+                          0.241851 0.960214 0.139633,
+                          0.466543 0.842487 0.269359,
+                          0.380931 0.842487 0.380931,
+                          0.19747 0.960214 0.19747,
+                          0.139633 0.960214 0.241851,
+                          0.466543 0.842487 0.269359,
+                          0.19747 0.960214 0.19747,
+                          0.380931 0.842487 0.380931,
+                          0.269359 0.842487 0.466543,
+                          0.139633 0.960214 0.241851,
+                          0.0722792 0.960214 0.26975,
+                          0.380931 0.842487 0.380931,
+                          0.139633 0.960214 0.241851,
+                          0.269359 0.842487 0.466543,
+                          0.13943 0.842487 0.520361,
+                          0.0722792 0.960214 0.26975,
+                          -4.38023e-16 0.960214 0.279265,
+                          0.269359 0.842487 0.466543,
+                          0.0722792 0.960214 0.26975,
+                          0.13943 0.842487 0.520361,
+                          -4.47966e-16 0.842487 0.538717,
+                          -4.38023e-16 0.960214 0.279265,
+                          -0.0722792 0.960214 0.26975,
+                          0.13943 0.842487 0.520361,
+                          -4.38023e-16 0.960214 0.279265,
+                          -4.47966e-16 0.842487 0.538717,
+                          -0.13943 0.842487 0.520361,
+                          -0.0722792 0.960214 0.26975,
+                          -0.139633 0.960214 0.241851,
+                          -4.47966e-16 0.842487 0.538717,
+                          -0.0722792 0.960214 0.26975,
+                          -0.13943 0.842487 0.520361,
+                          -0.269359 0.842487 0.466543,
+                          -0.139633 0.960214 0.241851,
+                          -0.19747 0.960214 0.19747,
+                          -0.13943 0.842487 0.520361,
+                          -0.139633 0.960214 0.241851,
+                          -0.269359 0.842487 0.466543,
+                          -0.380931 0.842487 0.380931,
+                          -0.19747 0.960214 0.19747,
+                          -0.241851 0.960214 0.139633,
+                          -0.269359 0.842487 0.466543,
+                          -0.19747 0.960214 0.19747,
+                          -0.380931 0.842487 0.380931,
+                          -0.466543 0.842487 0.269359,
+                          -0.241851 0.960214 0.139633,
+                          -0.26975 0.960214 0.0722792,
+                          -0.380931 0.842487 0.380931,
+                          -0.241851 0.960214 0.139633,
+                          -0.466543 0.842487 0.269359,
+                          -0.466543 0.842487 0.269359,
+                          -0.26975 0.960214 0.0722792,
+                          -0.520361 0.842487 0.13943,
+                          -0.522451 -0.841099 0.13999,
+                          -0.272133 -0.959493 0.0729178,
+                          -0.243988 -0.959493 0.140866,
+                          -0.468417 -0.841099 0.270441,
+                          -0.243988 -0.959493 0.140866,
+                          -0.199215 -0.959493 0.199215,
+                          -0.468417 -0.841099 0.270441,
+                          -0.522451 -0.841099 0.13999,
+                          -0.243988 -0.959493 0.140866,
+                          -0.382461 -0.841099 0.382461,
+                          -0.199215 -0.959493 0.199215,
+                          -0.140866 -0.959493 0.243988,
+                          -0.382461 -0.841099 0.382461,
+                          -0.468417 -0.841099 0.270441,
+                          -0.199215 -0.959493 0.199215,
+                          -0.270441 -0.841099 0.468417,
+                          -0.140866 -0.959493 0.243988,
+                          -0.0729178 -0.959493 0.272133,
+                          -0.270441 -0.841099 0.468417,
+                          -0.382461 -0.841099 0.382461,
+                          -0.140866 -0.959493 0.243988,
+                          -0.13999 -0.841099 0.522451,
+                          -0.0729178 -0.959493 0.272133,
+                          3.16162e-16 -0.959493 0.281733,
+                          -0.13999 -0.841099 0.522451,
+                          -0.270441 -0.841099 0.468417,
+                          -0.0729178 -0.959493 0.272133,
+                          2.13454e-16 -0.841099 0.540881,
+                          3.16162e-16 -0.959493 0.281733,
+                          0.0729178 -0.959493 0.272133,
+                          2.13454e-16 -0.841099 0.540881,
+                          -0.13999 -0.841099 0.522451,
+                          3.16162e-16 -0.959493 0.281733,
+                          0.13999 -0.841099 0.522451,
+                          0.0729178 -0.959493 0.272133,
+                          0.140866 -0.959493 0.243988,
+                          0.13999 -0.841099 0.522451,
+                          2.13454e-16 -0.841099 0.540881,
+                          0.0729178 -0.959493 0.272133,
+                          0.270441 -0.841099 0.468417,
+                          0.140866 -0.959493 0.243988,
+                          0.199215 -0.959493 0.199215,
+                          0.270441 -0.841099 0.468417,
+                          0.13999 -0.841099 0.522451,
+                          0.140866 -0.959493 0.243988,
+                          0.382461 -0.841099 0.382461,
+                          0.199215 -0.959493 0.199215,
+                          0.243988 -0.959493 0.140866,
+                          0.382461 -0.841099 0.382461,
+                          0.270441 -0.841099 0.468417,
+                          0.199215 -0.959493 0.199215,
+                          0.468417 -0.841099 0.270441,
+                          0.243988 -0.959493 0.140866,
+                          0.272133 -0.959493 0.0729178,
+                          0.468417 -0.841099 0.270441,
+                          0.382461 -0.841099 0.382461,
+                          0.243988 -0.959493 0.140866,
+                          0.522451 -0.841099 0.13999,
+                          0.468417 -0.841099 0.270441,
+                          0.272133 -0.959493 0.0729178,
+                          -0.730359 -0.654429 0.195699,
+                          -0.522451 -0.841099 0.13999,
+                          -0.468417 -0.841099 0.270441,
+                          -0.654822 -0.654429 0.378062,
+                          -0.468417 -0.841099 0.270441,
+                          -0.382461 -0.841099 0.382461,
+                          -0.654822 -0.654429 0.378062,
+                          -0.730359 -0.654429 0.195699,
+                          -0.468417 -0.841099 0.270441,
+                          -0.53466 -0.654429 0.53466,
+                          -0.382461 -0.841099 0.382461,
+                          -0.270441 -0.841099 0.468417,
+                          -0.53466 -0.654429 0.53466,
+                          -0.654822 -0.654429 0.378062,
+                          -0.382461 -0.841099 0.382461,
+                          -0.378062 -0.654429 0.654822,
+                          -0.270441 -0.841099 0.468417,
+                          -0.13999 -0.841099 0.522451,
+                          -0.378062 -0.654429 0.654822,
+                          -0.53466 -0.654429 0.53466,
+                          -0.270441 -0.841099 0.468417,
+                          -0.195699 -0.654429 0.730359,
+                          -0.13999 -0.841099 0.522451,
+                          2.13454e-16 -0.841099 0.540881,
+                          -0.195699 -0.654429 0.730359,
+                          -0.378062 -0.654429 0.654822,
+                          -0.13999 -0.841099 0.522451,
+                          9.34199e-17 -0.654429 0.756123,
+                          2.13454e-16 -0.841099 0.540881,
+                          0.13999 -0.841099 0.522451,
+                          9.34199e-17 -0.654429 0.756123,
+                          -0.195699 -0.654429 0.730359,
+                          2.13454e-16 -0.841099 0.540881,
+                          0.195699 -0.654429 0.730359,
+                          0.13999 -0.841099 0.522451,
+                          0.270441 -0.841099 0.468417,
+                          0.195699 -0.654429 0.730359,
+                          9.34199e-17 -0.654429 0.756123,
+                          0.13999 -0.841099 0.522451,
+                          0.378062 -0.654429 0.654822,
+                          0.270441 -0.841099 0.468417,
+                          0.382461 -0.841099 0.382461,
+                          0.378062 -0.654429 0.654822,
+                          0.195699 -0.654429 0.730359,
+                          0.270441 -0.841099 0.468417,
+                          0.53466 -0.654429 0.53466,
+                          0.382461 -0.841099 0.382461,
+                          0.468417 -0.841099 0.270441,
+                          0.53466 -0.654429 0.53466,
+                          0.378062 -0.654429 0.654822,
+                          0.382461 -0.841099 0.382461,
+                          0.654822 -0.654429 0.378062,
+                          0.468417 -0.841099 0.270441,
+                          0.522451 -0.841099 0.13999,
+                          0.654822 -0.654429 0.378062,
+                          0.53466 -0.654429 0.53466,
+                          0.468417 -0.841099 0.270441,
+                          0.730359 -0.654429 0.195699,
+                          0.654822 -0.654429 0.378062,
+                          0.522451 -0.841099 0.13999,
+                          -0.796251 -0.414635 0.440524,
+                          -0.730359 -0.654429 0.195699,
+                          -0.654822 -0.654429 0.378062,
+                          -0.796251 -0.414635 0.440524,
+                          -0.881095 -0.414635 0.227485,
+                          -0.730359 -0.654429 0.195699,
+                          -0.660844 -0.414635 0.62559,
+                          -0.654822 -0.654429 0.378062,
+                          -0.53466 -0.654429 0.53466,
+                          -0.660844 -0.414635 0.62559,
+                          -0.796251 -0.414635 0.440524,
+                          -0.654822 -0.654429 0.378062,
+                          -0.483472 -0.414635 0.770929,
+                          -0.53466 -0.654429 0.53466,
+                          -0.378062 -0.654429 0.654822,
+                          -0.483472 -0.414635 0.770929,
+                          -0.660844 -0.414635 0.62559,
+                          -0.53466 -0.654429 0.53466,
+                          -0.362338 -0.527575 0.768359,
+                          -0.378062 -0.654429 0.654822,
+                          -0.195699 -0.654429 0.730359,
+                          -0.362338 -0.527575 0.768359,
+                          -0.483472 -0.414635 0.770929,
+                          -0.378062 -0.654429 0.654822,
+                          -0.193812 -0.609968 0.76836,
+                          -0.195699 -0.654429 0.730359,
+                          9.34199e-17 -0.654429 0.756123,
+                          -0.193812 -0.609968 0.76836,
+                          -0.362338 -0.527575 0.768359,
+                          -0.195699 -0.654429 0.730359,
+                          4.81291e-07 -0.64 0.768375,
+                          9.34199e-17 -0.654429 0.756123,
+                          0.195699 -0.654429 0.730359,
+                          4.81291e-07 -0.64 0.768375,
+                          -0.193812 -0.609968 0.76836,
+                          9.34199e-17 -0.654429 0.756123,
+                          0.362339 -0.527575 0.768359,
+                          0.195699 -0.654429 0.730359,
+                          0.378062 -0.654429 0.654822,
+                          0.193813 -0.609967 0.76836,
+                          4.81291e-07 -0.64 0.768375,
+                          0.195699 -0.654429 0.730359,
+                          0.362339 -0.527575 0.768359,
+                          0.193813 -0.609967 0.76836,
+                          0.195699 -0.654429 0.730359,
+                          0.483472 -0.414635 0.770929,
+                          0.378062 -0.654429 0.654822,
+                          0.53466 -0.654429 0.53466,
+                          0.483472 -0.414635 0.770929,
+                          0.362339 -0.527575 0.768359,
+                          0.378062 -0.654429 0.654822,
+                          0.660844 -0.414635 0.62559,
+                          0.53466 -0.654429 0.53466,
+                          0.654822 -0.654429 0.378062,
+                          0.660844 -0.414635 0.62559,
+                          0.483472 -0.414635 0.770929,
+                          0.53466 -0.654429 0.53466,
+                          0.796251 -0.414635 0.440524,
+                          0.654822 -0.654429 0.378062,
+                          0.730359 -0.654429 0.195699,
+                          0.796251 -0.414635 0.440524,
+                          0.660844 -0.414635 0.62559,
+                          0.654822 -0.654429 0.378062,
+                          0.881095 -0.414635 0.227485,
+                          0.796251 -0.414635 0.440524,
+                          0.730359 -0.654429 0.195699,
+                          -0.892512 -0.141184 0.428357,
+                          -0.881095 -0.414635 0.227485,
+                          -0.796251 -0.414635 0.440524,
+                          -0.892512 -0.141184 0.428357,
+                          -0.965308 -0.141184 0.219653,
+                          -0.881095 -0.414635 0.227485,
+                          -0.775224 -0.141184 0.615707,
+                          -0.796251 -0.414635 0.440524,
+                          -0.660844 -0.414635 0.62559,
+                          -0.775224 -0.141184 0.615707,
+                          -0.892512 -0.141184 0.428357,
+                          -0.796251 -0.414635 0.440524,
+                          -0.503417 -0.39515 0.768393,
+                          -0.660844 -0.414635 0.62559,
+                          -0.483472 -0.414635 0.770929,
+                          -0.619291 -0.141184 0.772364,
+                          -0.775224 -0.141184 0.615707,
+                          -0.660844 -0.414635 0.62559,
+                          -0.604511 -0.210188 0.768366,
+                          -0.619291 -0.141184 0.772364,
+                          -0.660844 -0.414635 0.62559,
+                          -0.503417 -0.39515 0.768393,
+                          -0.604511 -0.210188 0.768366,
+                          -0.660844 -0.414635 0.62559,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          -0.382686 0.923879 6.29127e-14,
+                          -1.05382e-13 1 4.78922e-14,
+                          -1.6043e-06 1 4.78923e-14,
+                          0.382683 0.92388 2.55806e-14,
+                          -1.6043e-06 1 4.78923e-14,
+                          -1.05382e-13 1 4.78922e-14,
+                          0.382683 0.92388 2.55806e-14,
+                          0.382683 0.92388 2.55806e-14,
+                          -1.6043e-06 1 4.78923e-14,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          0.503417 -0.395149 0.768393,
+                          0.483472 -0.414635 0.770929,
+                          0.660844 -0.414635 0.62559,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          0.775224 -0.141184 0.615707,
+                          0.660844 -0.414635 0.62559,
+                          0.796251 -0.414635 0.440524,
+                          0.604512 -0.210187 0.768366,
+                          0.503417 -0.395149 0.768393,
+                          0.660844 -0.414635 0.62559,
+                          0.619291 -0.141184 0.772364,
+                          0.604512 -0.210187 0.768366,
+                          0.660844 -0.414635 0.62559,
+                          0.775224 -0.141184 0.615707,
+                          0.619291 -0.141184 0.772364,
+                          0.660844 -0.414635 0.62559,
+                          0.892512 -0.141184 0.428357,
+                          0.796251 -0.414635 0.440524,
+                          0.881095 -0.414635 0.227485,
+                          0.892512 -0.141184 0.428357,
+                          0.775224 -0.141184 0.615707,
+                          0.796251 -0.414635 0.440524,
+                          0.965308 -0.141184 0.219653,
+                          0.892512 -0.141184 0.428357,
+                          0.881095 -0.414635 0.227485,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          0.640008 5.17752e-07 0.768368,
+                          0.619291 -0.141184 0.772364,
+                          0.775224 -0.141184 0.615707,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          0.892109 0.143728 0.428349,
+                          0.775224 -0.141184 0.615707,
+                          0.892512 -0.141184 0.428357,
+                          0.774781 0.143728 0.615676,
+                          0.640008 5.17752e-07 0.768368,
+                          0.775224 -0.141184 0.615707,
+                          0.892109 0.143728 0.428349,
+                          0.774781 0.143728 0.615676,
+                          0.775224 -0.141184 0.615707,
+                          0.964932 0.143728 0.219654,
+                          0.892512 -0.141184 0.428357,
+                          0.965308 -0.141184 0.219653,
+                          0.964932 0.143728 0.219654,
+                          0.892109 0.143728 0.428349,
+                          0.892512 -0.141184 0.428357,
+                          0.774781 0.143728 0.615676,
+                          0.618801 0.143728 0.772287,
+                          0.640008 5.17752e-07 0.768368,
+                          0.658944 0.416973 0.62604,
+                          0.618801 0.143728 0.772287,
+                          0.774781 0.143728 0.615676,
+                          0.658944 0.416973 0.62604,
+                          0.604511 0.210188 0.768366,
+                          0.618801 0.143728 0.772287,
+                          0.794788 0.416973 0.440959,
+                          0.774781 0.143728 0.615676,
+                          0.892109 0.143728 0.428349,
+                          0.794788 0.416973 0.440959,
+                          0.658944 0.416973 0.62604,
+                          0.774781 0.143728 0.615676,
+                          0.879924 0.416973 0.227745,
+                          0.892109 0.143728 0.428349,
+                          0.964932 0.143728 0.219654,
+                          0.879924 0.416973 0.227745,
+                          0.794788 0.416973 0.440959,
+                          0.892109 0.143728 0.428349,
+                          0.658944 0.416973 0.62604,
+                          0.503417 0.39515 0.768393,
+                          0.604511 0.210188 0.768366,
+                          0.658944 0.416973 0.62604,
+                          0.481059 0.416973 0.771178,
+                          0.503417 0.39515 0.768393,
+                          0.533469 0.65637 0.533469,
+                          0.481059 0.416973 0.771178,
+                          0.658944 0.416973 0.62604,
+                          0.377219 0.65637 0.653363,
+                          0.362338 0.527575 0.768359,
+                          0.481059 0.416973 0.771178,
+                          0.533469 0.65637 0.533469,
+                          0.377219 0.65637 0.653363,
+                          0.481059 0.416973 0.771178,
+                          0.653363 0.65637 0.377219,
+                          0.658944 0.416973 0.62604,
+                          0.794788 0.416973 0.440959,
+                          0.653363 0.65637 0.377219,
+                          0.533469 0.65637 0.533469,
+                          0.658944 0.416973 0.62604,
+                          0.728732 0.65637 0.195263,
+                          0.794788 0.416973 0.440959,
+                          0.879924 0.416973 0.227745,
+                          0.728732 0.65637 0.195263,
+                          0.653363 0.65637 0.377219,
+                          0.794788 0.416973 0.440959,
+                          0.195263 0.65637 0.728732,
+                          0.193812 0.609968 0.76836,
+                          0.362338 0.527575 0.768359,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          0.377219 0.65637 0.653363,
+                          0.195263 0.65637 0.728732,
+                          0.362338 0.527575 0.768359,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          -4.21546e-16 0.65637 0.754439,
+                          -4.81319e-07 0.64 0.768375,
+                          0.193812 0.609968 0.76836,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          0.195263 0.65637 0.728732,
+                          -4.21546e-16 0.65637 0.754439,
+                          0.193812 0.609968 0.76836,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          -0.195263 0.65637 0.728732,
+                          -0.193813 0.609967 0.76836,
+                          -4.81319e-07 0.64 0.768375,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          -4.21546e-16 0.65637 0.754439,
+                          -0.195263 0.65637 0.728732,
+                          -4.81319e-07 0.64 0.768375,
+                          0.382686 -0.923879 -6.29127e-14,
+                          -1.04795e-13 -1 -4.78922e-14,
+                          1.60439e-06 -1 -4.78923e-14,
+                          -0.382683 -0.92388 -2.55806e-14,
+                          1.60439e-06 -1 -4.78923e-14,
+                          -1.04795e-13 -1 -4.78922e-14,
+                          -0.382683 -0.92388 -2.55806e-14,
+                          -0.382683 -0.92388 -2.55806e-14,
+                          1.60439e-06 -1 -4.78923e-14,
+                          -0.195263 0.65637 0.728732,
+                          -0.362339 0.527575 0.768359,
+                          -0.193813 0.609967 0.76836,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          -0.377219 0.65637 0.653363,
+                          -0.481059 0.416973 0.771178,
+                          -0.362339 0.527575 0.768359,
+                          -0.195263 0.65637 0.728732,
+                          -0.377219 0.65637 0.653363,
+                          -0.362339 0.527575 0.768359,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          -0.533469 0.65637 0.533469,
+                          -0.658944 0.416973 0.62604,
+                          -0.481059 0.416973 0.771178,
+                          -0.503417 0.395149 0.768393,
+                          -0.481059 0.416973 0.771178,
+                          -0.658944 0.416973 0.62604,
+                          -0.377219 0.65637 0.653363,
+                          -0.533469 0.65637 0.533469,
+                          -0.481059 0.416973 0.771178,
+                          -0.653363 0.65637 0.377219,
+                          -0.794788 0.416973 0.440959,
+                          -0.658944 0.416973 0.62604,
+                          -0.774781 0.143728 0.615676,
+                          -0.658944 0.416973 0.62604,
+                          -0.794788 0.416973 0.440959,
+                          -0.533469 0.65637 0.533469,
+                          -0.653363 0.65637 0.377219,
+                          -0.658944 0.416973 0.62604,
+                          -0.618801 0.143728 0.772287,
+                          -0.658944 0.416973 0.62604,
+                          -0.774781 0.143728 0.615676,
+                          -0.604512 0.210187 0.768366,
+                          -0.658944 0.416973 0.62604,
+                          -0.618801 0.143728 0.772287,
+                          -0.604512 0.210187 0.768366,
+                          -0.503417 0.395149 0.768393,
+                          -0.658944 0.416973 0.62604,
+                          -0.728732 0.65637 0.195263,
+                          -0.879924 0.416973 0.227745,
+                          -0.794788 0.416973 0.440959,
+                          -0.892109 0.143728 0.428349,
+                          -0.794788 0.416973 0.440959,
+                          -0.879924 0.416973 0.227745,
+                          -0.653363 0.65637 0.377219,
+                          -0.728732 0.65637 0.195263,
+                          -0.794788 0.416973 0.440959,
+                          -0.774781 0.143728 0.615676,
+                          -0.794788 0.416973 0.440959,
+                          -0.892109 0.143728 0.428349,
+                          -0.892109 0.143728 0.428349,
+                          -0.879924 0.416973 0.227745,
+                          -0.964932 0.143728 0.219654,
+                          -0.520361 0.842487 0.13943,
+                          -0.728732 0.65637 0.195263,
+                          -0.653363 0.65637 0.377219,
+                          -0.466543 0.842487 0.269359,
+                          -0.653363 0.65637 0.377219,
+                          -0.533469 0.65637 0.533469,
+                          -0.466543 0.842487 0.269359,
+                          -0.520361 0.842487 0.13943,
+                          -0.653363 0.65637 0.377219,
+                          -0.380931 0.842487 0.380931,
+                          -0.533469 0.65637 0.533469,
+                          -0.377219 0.65637 0.653363,
+                          -0.380931 0.842487 0.380931,
+                          -0.466543 0.842487 0.269359,
+                          -0.533469 0.65637 0.533469,
+                          -0.269359 0.842487 0.466543,
+                          -0.377219 0.65637 0.653363,
+                          -0.195263 0.65637 0.728732,
+                          -0.269359 0.842487 0.466543,
+                          -0.380931 0.842487 0.380931,
+                          -0.377219 0.65637 0.653363,
+                          -0.13943 0.842487 0.520361,
+                          -0.195263 0.65637 0.728732,
+                          -4.21546e-16 0.65637 0.754439,
+                          -0.13943 0.842487 0.520361,
+                          -0.269359 0.842487 0.466543,
+                          -0.195263 0.65637 0.728732,
+                          -4.47966e-16 0.842487 0.538717,
+                          -4.21546e-16 0.65637 0.754439,
+                          0.195263 0.65637 0.728732,
+                          -4.47966e-16 0.842487 0.538717,
+                          -0.13943 0.842487 0.520361,
+                          -4.21546e-16 0.65637 0.754439,
+                          0.13943 0.842487 0.520361,
+                          0.195263 0.65637 0.728732,
+                          0.377219 0.65637 0.653363,
+                          0.13943 0.842487 0.520361,
+                          -4.47966e-16 0.842487 0.538717,
+                          0.195263 0.65637 0.728732,
+                          0.269359 0.842487 0.466543,
+                          0.377219 0.65637 0.653363,
+                          0.533469 0.65637 0.533469,
+                          0.269359 0.842487 0.466543,
+                          0.13943 0.842487 0.520361,
+                          0.377219 0.65637 0.653363,
+                          0.380931 0.842487 0.380931,
+                          0.533469 0.65637 0.533469,
+                          0.653363 0.65637 0.377219,
+                          0.380931 0.842487 0.380931,
+                          0.269359 0.842487 0.466543,
+                          0.533469 0.65637 0.533469,
+                          0.466543 0.842487 0.269359,
+                          0.653363 0.65637 0.377219,
+                          0.728732 0.65637 0.195263,
+                          0.466543 0.842487 0.269359,
+                          0.380931 0.842487 0.380931,
+                          0.653363 0.65637 0.377219,
+                          0.520361 0.842487 0.13943,
+                          0.466543 0.842487 0.269359,
+                          0.728732 0.65637 0.195263,
+                          -0.964932 0.143728 0.219654,
+                          -0.965308 -0.141184 0.219653,
+                          -0.892512 -0.141184 0.428357,
+                          -0.892109 0.143728 0.428349,
+                          -0.892512 -0.141184 0.428357,
+                          -0.775224 -0.141184 0.615707,
+                          -0.892109 0.143728 0.428349,
+                          -0.964932 0.143728 0.219654,
+                          -0.892512 -0.141184 0.428357,
+                          -0.774781 0.143728 0.615676,
+                          -0.775224 -0.141184 0.615707,
+                          -0.619291 -0.141184 0.772364,
+                          -0.774781 0.143728 0.615676,
+                          -0.892109 0.143728 0.428349,
+                          -0.775224 -0.141184 0.615707,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          -0.640008 -5.17783e-07 0.768368,
+                          -0.774781 0.143728 0.615676,
+                          -0.619291 -0.141184 0.772364,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          -0.640008 -5.17783e-07 0.768368,
+                          -0.618801 0.143728 0.772287,
+                          -0.774781 0.143728 0.615676,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -0.382683 0.92388 6.29127e-14,
+                          -1.05382e-13 1 4.78922e-14,
+                          -0.382686 0.923879 6.29127e-14,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          0.382683 -0.92388 -6.29127e-14,
+                          -1.04795e-13 -1 -4.78922e-14,
+                          0.382686 -0.923879 -6.29127e-14,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          -4.92208e-14 4.78922e-14 -1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          1 6.38064e-16 -4.87767e-14,
+                          1 6.38064e-16 -4.87767e-14,
+                          0.900969 0.433884 -2.31667e-14,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          0.92388 -0.382683 -6.33914e-14,
+                          0.92388 -0.382683 -6.33914e-14,
+                          1 3.93143e-16 -4.87767e-14,
+                          0.92388 -0.382683 -6.33914e-14,
+                          1 3.93143e-16 -4.87767e-14,
+                          1 5.11567e-16 -4.87767e-14,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          0.900969 0.433884 -2.31667e-14,
+                          0.900969 0.433884 -2.31667e-14,
+                          0.62349 0.781832 7.03183e-15,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          0.900969 0.433884 -2.31667e-14,
+                          1 6.38064e-16 -4.87767e-14,
+                          0.900969 0.433884 -2.31667e-14,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          0.62349 0.781832 7.03183e-15,
+                          0.62349 0.781832 7.03183e-15,
+                          0.222521 0.974928 3.58376e-14,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          0.900969 0.433884 -2.31667e-14,
+                          0.62349 0.781832 7.03183e-15,
+                          0.62349 0.781832 7.03183e-15,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          0.222521 0.974928 3.58376e-14,
+                          0.222521 0.974928 3.58376e-14,
+                          -0.222521 0.974928 5.75453e-14,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          0.62349 0.781832 7.03183e-15,
+                          0.222521 0.974928 3.58376e-14,
+                          0.222521 0.974928 3.58376e-14,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          -0.222521 0.974928 5.75453e-14,
+                          -0.222521 0.974928 5.75453e-14,
+                          -0.62349 0.781832 6.78554e-14,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          0.222521 0.974928 3.58376e-14,
+                          -0.222521 0.974928 5.75453e-14,
+                          -0.222521 0.974928 5.75453e-14,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          -0.62349 0.781832 6.78554e-14,
+                          -0.62349 0.781832 6.78554e-14,
+                          -0.900969 0.433884 6.4726e-14,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          -0.222521 0.974928 5.75453e-14,
+                          -0.62349 0.781832 6.78554e-14,
+                          -0.62349 0.781832 6.78554e-14,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          -0.900969 0.433884 6.4726e-14,
+                          -0.900969 0.433884 6.4726e-14,
+                          -1 -5.15604e-16 4.87767e-14,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          4.92208e-14 -4.78922e-14 1,
+                          -0.62349 0.781832 6.78554e-14,
+                          -0.900969 0.433884 6.4726e-14,
+                          -0.900969 0.433884 6.4726e-14,
+                          -1 -5.15604e-16 4.87767e-14,
+                          -1 -5.15604e-16 4.87767e-14,
+                          -0.92388 -0.382683 2.67363e-14,
+                          -0.900969 0.433884 6.4726e-14,
+                          -1 -5.15604e-16 4.87767e-14,
+                          -1 -5.15604e-16 4.87767e-14,
+                          -0.92388 -0.382683 2.67363e-14,
+                          -0.92388 -0.382683 2.67363e-14,
+                          -0.707107 -0.707107 6.25463e-16,
+                          -1 -5.15604e-16 4.87767e-14,
+                          -0.92388 -0.382683 2.67363e-14,
+                          -0.92388 -0.382683 2.67363e-14,
+                          -0.707107 -0.707107 6.25463e-16,
+                          -0.707107 -0.707107 6.25463e-16,
+                          -0.382683 -0.92388 -2.55806e-14,
+                          -0.92388 -0.382683 2.67363e-14,
+                          -0.707107 -0.707107 6.25463e-16,
+                          -0.707107 -0.707107 6.25463e-16,
+                          -0.707107 -0.707107 6.25463e-16,
+                          -0.382683 -0.92388 -2.55806e-14,
+                          -0.382683 -0.92388 -2.55806e-14,
+                          -0.382683 0.92388 6.29127e-14,
+                          -0.382686 0.923879 6.29127e-14,
+                          -0.707108 0.707106 6.83553e-14,
+                          -0.707107 0.707107 6.83553e-14,
+                          -0.707108 0.707106 6.83553e-14,
+                          -0.92388 0.382683 6.33914e-14,
+                          -0.382683 0.92388 6.29127e-14,
+                          -0.707108 0.707106 6.83553e-14,
+                          -0.707107 0.707107 6.83553e-14,
+                          -0.92388 0.382683 6.33914e-14,
+                          -0.92388 0.382683 6.33914e-14,
+                          -1 -5.15604e-16 4.87767e-14,
+                          -0.707107 0.707107 6.83553e-14,
+                          -0.92388 0.382683 6.33914e-14,
+                          -0.92388 0.382683 6.33914e-14,
+                          -1 -5.15604e-16 4.87767e-14,
+                          -1 -5.15604e-16 4.87767e-14,
+                          -0.900969 -0.433884 2.31667e-14,
+                          -0.92388 0.382683 6.33914e-14,
+                          -1 -5.15604e-16 4.87767e-14,
+                          -1 -5.15604e-16 4.87767e-14,
+                          -0.900969 -0.433884 2.31667e-14,
+                          -0.900969 -0.433884 2.31667e-14,
+                          -0.62349 -0.781832 -7.03183e-15,
+                          -1 -5.15604e-16 4.87767e-14,
+                          -0.900969 -0.433884 2.31667e-14,
+                          -0.900969 -0.433884 2.31667e-14,
+                          -0.62349 -0.781832 -7.03183e-15,
+                          -0.62349 -0.781832 -7.03183e-15,
+                          -0.222521 -0.974928 -3.58376e-14,
+                          -0.900969 -0.433884 2.31667e-14,
+                          -0.62349 -0.781832 -7.03183e-15,
+                          -0.62349 -0.781832 -7.03183e-15,
+                          -0.222521 -0.974928 -3.58376e-14,
+                          -0.222521 -0.974928 -3.58376e-14,
+                          0.222521 -0.974928 -5.75453e-14,
+                          -0.62349 -0.781832 -7.03183e-15,
+                          -0.222521 -0.974928 -3.58376e-14,
+                          -0.222521 -0.974928 -3.58376e-14,
+                          0.222521 -0.974928 -5.75453e-14,
+                          0.222521 -0.974928 -5.75453e-14,
+                          0.62349 -0.781832 -6.78554e-14,
+                          -0.222521 -0.974928 -3.58376e-14,
+                          0.222521 -0.974928 -5.75453e-14,
+                          0.222521 -0.974928 -5.75453e-14,
+                          0.62349 -0.781832 -6.78554e-14,
+                          0.62349 -0.781832 -6.78554e-14,
+                          0.900969 -0.433884 -6.4726e-14,
+                          0.222521 -0.974928 -5.75453e-14,
+                          0.62349 -0.781832 -6.78554e-14,
+                          0.62349 -0.781832 -6.78554e-14,
+                          0.900969 -0.433884 -6.4726e-14,
+                          0.900969 -0.433884 -6.4726e-14,
+                          1 3.93143e-16 -4.87767e-14,
+                          0.62349 -0.781832 -6.78554e-14,
+                          0.900969 -0.433884 -6.4726e-14,
+                          0.900969 -0.433884 -6.4726e-14,
+                          1 6.38064e-16 -4.87767e-14,
+                          1 6.38064e-16 -4.87767e-14,
+                          0.92388 0.382683 -2.67363e-14,
+                          0.900969 -0.433884 -6.4726e-14,
+                          1 3.93143e-16 -4.87767e-14,
+                          1 5.11567e-16 -4.87767e-14,
+                          0.92388 0.382683 -2.67363e-14,
+                          0.92388 0.382683 -2.67363e-14,
+                          0.707107 0.707107 -6.25463e-16,
+                          1 6.38064e-16 -4.87767e-14,
+                          0.92388 0.382683 -2.67363e-14,
+                          0.92388 0.382683 -2.67363e-14,
+                          0.707107 0.707107 -6.25463e-16,
+                          0.707107 0.707107 -6.25463e-16,
+                          0.382683 0.92388 2.55806e-14,
+                          0.92388 0.382683 -2.67363e-14,
+                          0.707107 0.707107 -6.25463e-16,
+                          0.707107 0.707107 -6.25463e-16,
+                          0.707107 0.707107 -6.25463e-16,
+                          0.382683 0.92388 2.55806e-14,
+                          0.382683 0.92388 2.55806e-14,
+                          0.382683 -0.92388 -6.29127e-14,
+                          0.382686 -0.923879 -6.29127e-14,
+                          0.707108 -0.707106 -6.83553e-14,
+                          0.707107 -0.707107 -6.83553e-14,
+                          0.707108 -0.707106 -6.83553e-14,
+                          0.92388 -0.382683 -6.33914e-14,
+                          0.382683 -0.92388 -6.29127e-14,
+                          0.707108 -0.707106 -6.83553e-14,
+                          0.707107 -0.707107 -6.83553e-14,
+                          0.707107 -0.707107 -6.83553e-14,
+                          0.92388 -0.382683 -6.33914e-14,
+                          0.92388 -0.382683 -6.33914e-14 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -6.70237 23.0451 3.98126e-15,
+                          -5.96452 23.1822 -1.7347,
+                          -2.695e-14 24 6.12195e-15,
+                          -4.5147 23.3941 -2.88687,
+                          -2.695e-14 24 6.12195e-15,
+                          -5.96452 23.1822 -1.7347,
+                          -6.47399 23.0451 1.7347,
+                          -6.70237 23.0451 3.98126e-15,
+                          -2.695e-14 24 6.12195e-15,
+                          -3.07915 23.5371 -3.53921,
+                          -2.695e-14 24 6.12195e-15,
+                          -4.5147 23.3941 -2.88687,
+                          -2.37184 23.3162 -5.17014,
+                          -2.695e-14 24 6.12195e-15,
+                          -3.07915 23.5371 -3.53921,
+                          -0.745972 23.4321 -5.13627,
+                          -2.695e-14 24 6.12195e-15,
+                          -2.37184 23.3162 -5.17014,
+                          0.732585 23.4324 -5.1369,
+                          -2.695e-14 24 6.12195e-15,
+                          -0.745972 23.4321 -5.13627,
+                          2.35555 23.3179 -5.16965,
+                          -2.695e-14 24 6.12195e-15,
+                          0.732585 23.4324 -5.1369,
+                          3.06151 23.5396 -3.53725,
+                          -2.695e-14 24 6.12195e-15,
+                          2.35555 23.3179 -5.16965,
+                          4.48178 23.401 -2.88207,
+                          -2.695e-14 24 6.12195e-15,
+                          3.06151 23.5396 -3.53725,
+                          5.96004 23.1822 -1.75003,
+                          -2.695e-14 24 6.12195e-15,
+                          4.48178 23.401 -2.88207,
+                          6.70237 23.0451 9.86274e-15,
+                          -2.695e-14 24 6.12195e-15,
+                          5.96004 23.1822 -1.75003,
+                          6.47399 23.0451 1.7347,
+                          -2.695e-14 24 6.12195e-15,
+                          6.70237 23.0451 9.86274e-15,
+                          -5.80442 23.0451 3.35118,
+                          -6.47399 23.0451 1.7347,
+                          -2.695e-14 24 6.12195e-15,
+                          -4.73929 23.0451 4.73929,
+                          -5.80442 23.0451 3.35118,
+                          -2.695e-14 24 6.12195e-15,
+                          -3.35118 23.0451 5.80442,
+                          -4.73929 23.0451 4.73929,
+                          -2.695e-14 24 6.12195e-15,
+                          -1.7347 23.0451 6.47399,
+                          -3.35118 23.0451 5.80442,
+                          -2.695e-14 24 6.12195e-15,
+                          -1.91487e-14 23.0451 6.70237,
+                          -1.7347 23.0451 6.47399,
+                          -2.695e-14 24 6.12195e-15,
+                          1.7347 23.0451 6.47399,
+                          -1.91487e-14 23.0451 6.70237,
+                          -2.695e-14 24 6.12195e-15,
+                          3.35118 23.0451 5.80442,
+                          1.7347 23.0451 6.47399,
+                          -2.695e-14 24 6.12195e-15,
+                          4.73929 23.0451 4.73929,
+                          3.35118 23.0451 5.80442,
+                          -2.695e-14 24 6.12195e-15,
+                          5.80442 23.0451 3.35118,
+                          4.73929 23.0451 4.73929,
+                          -2.695e-14 24 6.12195e-15,
+                          6.47399 23.0451 1.7347,
+                          5.80442 23.0451 3.35118,
+                          -2.695e-14 24 6.12195e-15,
+                          -6.70237 23.0451 3.98126e-15,
+                          -11.5226 20.7846 -3.35118,
+                          -5.96452 23.1822 -1.7347,
+                          -8.80144 21.607 -5.62797,
+                          -5.96452 23.1822 -1.7347,
+                          -11.5226 20.7846 -3.35118,
+                          -8.80144 21.607 -5.62797,
+                          -4.5147 23.3941 -2.88687,
+                          -5.96452 23.1822 -1.7347,
+                          -12.9292 20.2197 -2.95827e-15,
+                          -16.2954 16.9706 -4.73929,
+                          -11.5226 20.7846 -3.35118,
+                          -12.6438 18.7288 -8.0849,
+                          -11.5226 20.7846 -3.35118,
+                          -16.2954 16.9706 -4.73929,
+                          -6.70237 23.0451 3.98126e-15,
+                          -12.9292 20.2197 -2.95827e-15,
+                          -11.5226 20.7846 -3.35118,
+                          -12.6438 18.7288 -8.0849,
+                          -8.80144 21.607 -5.62797,
+                          -11.5226 20.7846 -3.35118,
+                          -18.1065 15.7529 -5.38925e-15,
+                          -19.9577 12 -5.80442,
+                          -16.2954 16.9706 -4.73929,
+                          -15.7752 15.0744 -10,
+                          -16.2954 16.9706 -4.73929,
+                          -19.9577 12 -5.80442,
+                          -12.9292 20.2197 -2.95827e-15,
+                          -18.1065 15.7529 -5.38925e-15,
+                          -16.2954 16.9706 -4.73929,
+                          -15.7752 15.0744 -10,
+                          -12.6438 18.7288 -8.0849,
+                          -16.2954 16.9706 -4.73929,
+                          -21.8141 10.0074 -6.09079e-15,
+                          -22.2599 6.21166 -6.47399,
+                          -19.9577 12 -5.80442,
+                          -20.737 6.77986 -10,
+                          -19.9577 12 -5.80442,
+                          -22.2599 6.21166 -6.47399,
+                          -18.1065 15.7529 -5.38925e-15,
+                          -21.8141 10.0074 -6.09079e-15,
+                          -19.9577 12 -5.80442,
+                          -17.7239 12.7262 -10,
+                          -15.7752 15.0744 -10,
+                          -19.9577 12 -5.80442,
+                          -20.737 6.77986 -10,
+                          -17.7239 12.7262 -10,
+                          -19.9577 12 -5.80442,
+                          -23.7508 3.44948 5.54155e-15,
+                          -23.0451 -1.41205e-14 -6.70237,
+                          -22.2599 6.21166 -6.47399,
+                          -21.8174 0.000278048 -10,
+                          -22.2599 6.21166 -6.47399,
+                          -23.0451 -1.41205e-14 -6.70237,
+                          -21.8141 10.0074 -6.09079e-15,
+                          -23.7508 3.44948 5.54155e-15,
+                          -22.2599 6.21166 -6.47399,
+                          -21.8174 0.000278048 -10,
+                          -20.737 6.77986 -10,
+                          -22.2599 6.21166 -6.47399,
+                          -23.7596 -3.38842 -2.22275e-15,
+                          -22.2599 -6.21166 -6.47399,
+                          -23.0451 -1.41205e-14 -6.70237,
+                          -21.8174 0.000278048 -10,
+                          -23.0451 -1.41205e-14 -6.70237,
+                          -22.2599 -6.21166 -6.47399,
+                          -23.7508 3.44948 5.54155e-15,
+                          -23.7596 -3.38842 -2.22275e-15,
+                          -23.0451 -1.41205e-14 -6.70237,
+                          -21.8397 -9.95125 2.03284e-15,
+                          -19.9577 -12 -5.80442,
+                          -22.2599 -6.21166 -6.47399,
+                          -20.7371 -6.77933 -10,
+                          -22.2599 -6.21166 -6.47399,
+                          -19.9577 -12 -5.80442,
+                          -23.7596 -3.38842 -2.22275e-15,
+                          -21.8397 -9.95125 2.03284e-15,
+                          -22.2599 -6.21166 -6.47399,
+                          -20.7371 -6.77933 -10,
+                          -21.8174 0.000278048 -10,
+                          -22.2599 -6.21166 -6.47399,
+                          -18.147 -15.7063 7.41538e-15,
+                          -16.2954 -16.9706 -4.73929,
+                          -19.9577 -12 -5.80442,
+                          -17.7242 -12.7258 -10,
+                          -19.9577 -12 -5.80442,
+                          -16.2954 -16.9706 -4.73929,
+                          -21.8397 -9.95125 2.03284e-15,
+                          -18.147 -15.7063 7.41538e-15,
+                          -19.9577 -12 -5.80442,
+                          -17.7242 -12.7258 -10,
+                          -20.7371 -6.77933 -10,
+                          -19.9577 -12 -5.80442,
+                          -12.9811 -20.1864 1.34879e-14,
+                          -11.5226 -20.7846 -3.35118,
+                          -16.2954 -16.9706 -4.73929,
+                          -12.6438 -18.7288 -8.0849,
+                          -16.2954 -16.9706 -4.73929,
+                          -11.5226 -20.7846 -3.35118,
+                          -18.147 -15.7063 7.41538e-15,
+                          -12.9811 -20.1864 1.34879e-14,
+                          -16.2954 -16.9706 -4.73929,
+                          -15.7751 -15.0744 -10,
+                          -17.7242 -12.7258 -10,
+                          -16.2954 -16.9706 -4.73929,
+                          -12.6438 -18.7288 -8.0849,
+                          -15.7751 -15.0744 -10,
+                          -16.2954 -16.9706 -4.73929,
+                          -6.76158 -23.0278 1.97576e-14,
+                          -5.96452 -23.1822 -1.7347,
+                          -11.5226 -20.7846 -3.35118,
+                          -8.80144 -21.607 -5.62797,
+                          -11.5226 -20.7846 -3.35118,
+                          -5.96452 -23.1822 -1.7347,
+                          -12.9811 -20.1864 1.34879e-14,
+                          -6.76158 -23.0278 1.97576e-14,
+                          -11.5226 -20.7846 -3.35118,
+                          -8.80144 -21.607 -5.62797,
+                          -12.6438 -18.7288 -8.0849,
+                          -11.5226 -20.7846 -3.35118,
+                          -6.76158 -23.0278 1.97576e-14,
+                          3.56257e-15 -24 2.65134e-14,
+                          -5.96452 -23.1822 -1.7347,
+                          -4.5147 -23.3941 -2.88687,
+                          -5.96452 -23.1822 -1.7347,
+                          3.56257e-15 -24 2.65134e-14,
+                          -4.5147 -23.3941 -2.88687,
+                          -8.80144 -21.607 -5.62797,
+                          -5.96452 -23.1822 -1.7347,
+                          -6.53119 -23.0278 1.75003,
+                          3.56257e-15 -24 2.65134e-14,
+                          -6.76158 -23.0278 1.97576e-14,
+                          -3.07915 -23.5371 -3.5392,
+                          -4.5147 -23.3941 -2.88687,
+                          3.56257e-15 -24 2.65134e-14,
+                          4.48178 -23.401 -2.88207,
+                          3.56257e-15 -24 2.65134e-14,
+                          5.96004 -23.1822 -1.75003,
+                          6.76158 -23.0278 2.86938e-14,
+                          5.96004 -23.1822 -1.75003,
+                          3.56257e-15 -24 2.65134e-14,
+                          3.06151 -23.5396 -3.53725,
+                          3.56257e-15 -24 2.65134e-14,
+                          4.48178 -23.401 -2.88207,
+                          6.53119 -23.0278 1.75003,
+                          6.76158 -23.0278 2.86938e-14,
+                          3.56257e-15 -24 2.65134e-14,
+                          2.35555 -23.3179 -5.16965,
+                          3.56257e-15 -24 2.65134e-14,
+                          3.06151 -23.5396 -3.53725,
+                          0.732585 -23.4324 -5.13689,
+                          3.56257e-15 -24 2.65134e-14,
+                          2.35555 -23.3179 -5.16965,
+                          -0.745972 -23.4321 -5.13627,
+                          3.56257e-15 -24 2.65134e-14,
+                          0.732585 -23.4324 -5.13689,
+                          -2.37184 -23.3162 -5.17014,
+                          3.56257e-15 -24 2.65134e-14,
+                          -0.745972 -23.4321 -5.13627,
+                          -3.07915 -23.5371 -3.5392,
+                          3.56257e-15 -24 2.65134e-14,
+                          -2.37184 -23.3162 -5.17014,
+                          5.8557 -23.0278 3.38079,
+                          6.53119 -23.0278 1.75003,
+                          3.56257e-15 -24 2.65134e-14,
+                          4.78116 -23.0278 4.78116,
+                          5.8557 -23.0278 3.38079,
+                          3.56257e-15 -24 2.65134e-14,
+                          3.38079 -23.0278 5.8557,
+                          4.78116 -23.0278 4.78116,
+                          3.56257e-15 -24 2.65134e-14,
+                          1.75003 -23.0278 6.53119,
+                          3.38079 -23.0278 5.8557,
+                          3.56257e-15 -24 2.65134e-14,
+                          -1.0483e-15 -23.0278 6.76158,
+                          1.75003 -23.0278 6.53119,
+                          3.56257e-15 -24 2.65134e-14,
+                          -1.75003 -23.0278 6.53119,
+                          -1.0483e-15 -23.0278 6.76158,
+                          3.56257e-15 -24 2.65134e-14,
+                          -3.38079 -23.0278 5.8557,
+                          -1.75003 -23.0278 6.53119,
+                          3.56257e-15 -24 2.65134e-14,
+                          -4.78116 -23.0278 4.78116,
+                          -3.38079 -23.0278 5.8557,
+                          3.56257e-15 -24 2.65134e-14,
+                          -5.8557 -23.0278 3.38079,
+                          -4.78116 -23.0278 4.78116,
+                          3.56257e-15 -24 2.65134e-14,
+                          -6.53119 -23.0278 1.75003,
+                          -5.8557 -23.0278 3.38079,
+                          3.56257e-15 -24 2.65134e-14,
+                          -12.5388 -20.1864 3.35977,
+                          -6.76158 -23.0278 1.97576e-14,
+                          -12.9811 -20.1864 1.34879e-14,
+                          -12.5388 -20.1864 3.35977,
+                          -6.53119 -23.0278 1.75003,
+                          -6.76158 -23.0278 1.97576e-14,
+                          -17.6109 -15.7063 4.37805,
+                          -12.9811 -20.1864 1.34879e-14,
+                          -18.147 -15.7063 7.41538e-15,
+                          -12.5388 -20.1864 3.35977,
+                          -12.9811 -20.1864 1.34879e-14,
+                          -17.6109 -15.7063 4.37805,
+                          -21.212 -9.95125 5.19858,
+                          -18.147 -15.7063 7.41538e-15,
+                          -21.8397 -9.95125 2.03284e-15,
+                          -21.212 -9.95125 5.19858,
+                          -17.6109 -15.7063 4.37805,
+                          -18.147 -15.7063 7.41538e-15,
+                          -23.2113 -3.38842 5.07487,
+                          -21.8397 -9.95125 2.03284e-15,
+                          -23.7596 -3.38842 -2.22275e-15,
+                          -21.212 -9.95125 5.19858,
+                          -21.8397 -9.95125 2.03284e-15,
+                          -23.2113 -3.38842 5.07487,
+                          -23.2068 3.44948 5.0543,
+                          -23.7596 -3.38842 -2.22275e-15,
+                          -23.7508 3.44948 5.54155e-15,
+                          -23.2113 -3.38842 5.07487,
+                          -23.7596 -3.38842 -2.22275e-15,
+                          -23.2068 3.44948 5.0543,
+                          -21.1769 10.0074 5.23389,
+                          -23.7508 3.44948 5.54155e-15,
+                          -21.8141 10.0074 -6.09079e-15,
+                          -23.2068 3.44948 5.0543,
+                          -23.7508 3.44948 5.54155e-15,
+                          -21.1769 10.0074 5.23389,
+                          -17.5562 15.7529 4.43014,
+                          -21.8141 10.0074 -6.09079e-15,
+                          -18.1065 15.7529 -5.38925e-15,
+                          -21.1769 10.0074 5.23389,
+                          -21.8141 10.0074 -6.09079e-15,
+                          -17.5562 15.7529 4.43014,
+                          -12.4887 20.2197 3.34633,
+                          -18.1065 15.7529 -5.38925e-15,
+                          -12.9292 20.2197 -2.95827e-15,
+                          -17.5562 15.7529 4.43014,
+                          -18.1065 15.7529 -5.38925e-15,
+                          -12.4887 20.2197 3.34633,
+                          -6.47399 23.0451 1.7347,
+                          -12.9292 20.2197 -2.95827e-15,
+                          -6.70237 23.0451 3.98126e-15,
+                          -12.4887 20.2197 3.34633,
+                          -12.9292 20.2197 -2.95827e-15,
+                          -6.47399 23.0451 1.7347,
+                          -6.03951 22.1661 -6.94187,
+                          -4.5147 23.3941 -2.88687,
+                          -8.80144 21.607 -5.62797,
+                          -6.03951 22.1661 -6.94187,
+                          -3.07915 23.5371 -3.53921,
+                          -4.5147 23.3941 -2.88687,
+                          -8.72801 19.9952 -10,
+                          -8.80144 21.607 -5.62797,
+                          -12.6438 18.7288 -8.0849,
+                          -8.72801 19.9952 -10,
+                          -6.03951 22.1661 -6.94187,
+                          -8.80144 21.607 -5.62797,
+                          -14.1061 16.6457 -10,
+                          -12.6438 18.7288 -8.0849,
+                          -15.7752 15.0744 -10,
+                          -10.7671 18.9762 -10,
+                          -8.72801 19.9952 -10,
+                          -12.6438 18.7288 -8.0849,
+                          -14.1061 16.6457 -10,
+                          -10.7671 18.9762 -10,
+                          -12.6438 18.7288 -8.0849,
+                          -17.2578 15.0721 -10,
+                          -15.7752 15.0744 -10,
+                          -17.7239 12.7262 -10,
+                          -15.7577 16.6324 -10,
+                          -14.1061 16.6457 -10,
+                          -15.7752 15.0744 -10,
+                          -15.7577 16.6324 -10,
+                          -15.7752 15.0744 -10,
+                          -17.2578 15.0721 -10,
+                          -20.6934 9.83782 -10,
+                          -17.7239 12.7262 -10,
+                          -20.737 6.77986 -10,
+                          -17.2578 15.0721 -10,
+                          -17.7239 12.7262 -10,
+                          -20.6934 9.83782 -10,
+                          -20.6934 9.83782 -10,
+                          -20.737 6.77986 -10,
+                          -21.8174 0.000278048 -10,
+                          -22.6632 -3.3736 -10,
+                          -21.8174 0.000278048 -10,
+                          -20.7371 -6.77933 -10,
+                          -22.6631 3.37428 -10,
+                          -21.8174 0.000278048 -10,
+                          -22.6632 -3.3736 -10,
+                          -20.6934 9.83782 -10,
+                          -21.8174 0.000278048 -10,
+                          -22.6631 3.37428 -10,
+                          -20.6937 -9.83719 -10,
+                          -20.7371 -6.77933 -10,
+                          -17.7242 -12.7258 -10,
+                          -22.6632 -3.3736 -10,
+                          -20.7371 -6.77933 -10,
+                          -20.6937 -9.83719 -10,
+                          -17.2582 -15.0717 -10,
+                          -17.7242 -12.7258 -10,
+                          -15.7751 -15.0744 -10,
+                          -20.6937 -9.83719 -10,
+                          -17.7242 -12.7258 -10,
+                          -17.2582 -15.0717 -10,
+                          -14.1064 -16.6455 -10,
+                          -15.7751 -15.0744 -10,
+                          -12.6438 -18.7288 -8.0849,
+                          -15.7577 -16.6324 -10,
+                          -15.7751 -15.0744 -10,
+                          -14.1064 -16.6455 -10,
+                          -17.2582 -15.0717 -10,
+                          -15.7751 -15.0744 -10,
+                          -15.7577 -16.6324 -10,
+                          -10.7674 -18.976 -10,
+                          -12.6438 -18.7288 -8.0849,
+                          -8.80144 -21.607 -5.62797,
+                          -10.7674 -18.976 -10,
+                          -14.1064 -16.6455 -10,
+                          -12.6438 -18.7288 -8.0849,
+                          -6.0395 -22.1661 -6.94187,
+                          -8.80144 -21.607 -5.62797,
+                          -4.5147 -23.3941 -2.88687,
+                          -8.72801 -19.9952 -10,
+                          -8.80144 -21.607 -5.62797,
+                          -6.0395 -22.1661 -6.94187,
+                          -10.7674 -18.976 -10,
+                          -8.80144 -21.607 -5.62797,
+                          -8.72801 -19.9952 -10,
+                          -6.0395 -22.1661 -6.94187,
+                          -4.5147 -23.3941 -2.88687,
+                          -3.07915 -23.5371 -3.5392,
+                          -2.37184 23.3162 -5.17014,
+                          -3.07915 23.5371 -3.53921,
+                          -6.03951 22.1661 -6.94187,
+                          -7.92497 20.3272 -10,
+                          -6.03951 22.1661 -6.94187,
+                          -8.72801 19.9952 -10,
+                          -4.59307 21.3284 -10,
+                          -2.37184 23.3162 -5.17014,
+                          -6.03951 22.1661 -6.94187,
+                          -5.61355 21.0829 -10,
+                          -4.59307 21.3284 -10,
+                          -6.03951 22.1661 -6.94187,
+                          -7.92497 20.3272 -10,
+                          -5.61355 21.0829 -10,
+                          -6.03951 22.1661 -6.94187,
+                          -8.7259 21.1869 -10,
+                          -8.72801 19.9952 -10,
+                          -10.7671 18.9762 -10,
+                          -7.76756 21.5561 -10,
+                          -7.92497 20.3272 -10,
+                          -8.72801 19.9952 -10,
+                          -7.76756 21.5561 -10,
+                          -8.72801 19.9952 -10,
+                          -8.7259 21.1869 -10,
+                          -13.6889 18.3743 -10,
+                          -10.7671 18.9762 -10,
+                          -14.1061 16.6457 -10,
+                          -10.4849 20.3732 -10,
+                          -8.7259 21.1869 -10,
+                          -10.7671 18.9762 -10,
+                          -10.4849 20.3732 -10,
+                          -10.7671 18.9762 -10,
+                          -13.6889 18.3743 -10,
+                          -13.6889 18.3743 -10,
+                          -14.1061 16.6457 -10,
+                          -15.7577 16.6324 -10,
+                          -3.70526 21.5005 -10,
+                          -2.37184 23.3162 -5.17014,
+                          -4.59307 21.3284 -10,
+                          -1.45843 21.7686 -10,
+                          -0.745972 23.4321 -5.13627,
+                          -2.37184 23.3162 -5.17014,
+                          -1.86187 21.7378 -10,
+                          -1.45843 21.7686 -10,
+                          -2.37184 23.3162 -5.17014,
+                          -3.70526 21.5005 -10,
+                          -1.86187 21.7378 -10,
+                          -2.37184 23.3162 -5.17014,
+                          -5.55845 22.2284 -10,
+                          -4.59307 21.3284 -10,
+                          -5.61355 21.0829 -10,
+                          -4.59866 22.4467 -10,
+                          -3.70526 21.5005 -10,
+                          -4.59307 21.3284 -10,
+                          -5.55845 22.2284 -10,
+                          -4.59866 22.4467 -10,
+                          -4.59307 21.3284 -10,
+                          -7.76756 21.5561 -10,
+                          -5.61355 21.0829 -10,
+                          -7.92497 20.3272 -10,
+                          -5.55845 22.2284 -10,
+                          -5.61355 21.0829 -10,
+                          -7.76756 21.5561 -10,
+                          -1.51238e-14 21.8174 -10,
+                          -0.745972 23.4321 -5.13627,
+                          -1.45843 21.7686 -10,
+                          -1.51238e-14 21.8174 -10,
+                          0.732585 23.4324 -5.1369,
+                          -0.745972 23.4321 -5.13627,
+                          -1.85243 22.8379 -10,
+                          -1.45843 21.7686 -10,
+                          -1.86187 21.7378 -10,
+                          -1.55544e-14 22.9129 -10,
+                          -1.51238e-14 21.8174 -10,
+                          -1.45843 21.7686 -10,
+                          -1.55544e-14 22.9129 -10,
+                          -1.45843 21.7686 -10,
+                          -1.45787 22.8664 -10,
+                          -1.85243 22.8379 -10,
+                          -1.45787 22.8664 -10,
+                          -1.45843 21.7686 -10,
+                          -3.68914 22.6139 -10,
+                          -1.86187 21.7378 -10,
+                          -3.70526 21.5005 -10,
+                          -1.85243 22.8379 -10,
+                          -1.86187 21.7378 -10,
+                          -3.68914 22.6139 -10,
+                          -3.68914 22.6139 -10,
+                          -3.70526 21.5005 -10,
+                          -4.59866 22.4467 -10,
+                          -1.51238e-14 21.8174 -10,
+                          1.43235 21.7703 -10,
+                          0.732585 23.4324 -5.1369,
+                          2.35555 23.3179 -5.16965,
+                          0.732585 23.4324 -5.1369,
+                          1.43235 21.7703 -10,
+                          1.43179 22.8681 -10,
+                          1.43235 21.7703 -10,
+                          -1.51238e-14 21.8174 -10,
+                          1.86195 21.7378 -10,
+                          2.35555 23.3179 -5.16965,
+                          1.43235 21.7703 -10,
+                          1.85253 22.8379 -10,
+                          1.86195 21.7378 -10,
+                          1.43235 21.7703 -10,
+                          1.85253 22.8379 -10,
+                          1.43235 21.7703 -10,
+                          1.43179 22.8681 -10,
+                          -1.55544e-14 22.9129 -10,
+                          1.43179 22.8681 -10,
+                          -1.51238e-14 21.8174 -10,
+                          3.70541 21.5005 -10,
+                          4.56214 21.3351 -10,
+                          2.35555 23.3179 -5.16965,
+                          6.00557 22.1763 -6.9388,
+                          2.35555 23.3179 -5.16965,
+                          4.56214 21.3351 -10,
+                          1.86195 21.7378 -10,
+                          3.70541 21.5005 -10,
+                          2.35555 23.3179 -5.16965,
+                          6.00557 22.1763 -6.9388,
+                          3.06151 23.5396 -3.53725,
+                          2.35555 23.3179 -5.16965,
+                          4.5675 22.4531 -10,
+                          4.56214 21.3351 -10,
+                          3.70541 21.5005 -10,
+                          5.61372 21.0828 -10,
+                          6.00557 22.1763 -6.9388,
+                          4.56214 21.3351 -10,
+                          5.55866 22.2284 -10,
+                          5.61372 21.0828 -10,
+                          4.56214 21.3351 -10,
+                          5.55866 22.2284 -10,
+                          4.56214 21.3351 -10,
+                          4.5675 22.4531 -10,
+                          3.68933 22.6139 -10,
+                          3.70541 21.5005 -10,
+                          1.86195 21.7378 -10,
+                          3.68933 22.6139 -10,
+                          4.5675 22.4531 -10,
+                          3.70541 21.5005 -10,
+                          3.68933 22.6139 -10,
+                          1.86195 21.7378 -10,
+                          1.85253 22.8379 -10,
+                          4.48178 23.401 -2.88207,
+                          3.06151 23.5396 -3.53725,
+                          6.00557 22.1763 -6.9388,
+                          7.92518 20.3271 -10,
+                          8.68181 20.0154 -10,
+                          6.00557 22.1763 -6.9388,
+                          8.73984 21.6339 -5.62028,
+                          6.00557 22.1763 -6.9388,
+                          8.68181 20.0154 -10,
+                          5.61372 21.0828 -10,
+                          7.92518 20.3271 -10,
+                          6.00557 22.1763 -6.9388,
+                          8.73984 21.6339 -5.62028,
+                          4.48178 23.401 -2.88207,
+                          6.00557 22.1763 -6.9388,
+                          8.68001 21.2057 -10,
+                          8.68181 20.0154 -10,
+                          7.92518 20.3271 -10,
+                          10.7674 18.976 -10,
+                          8.73984 21.6339 -5.62028,
+                          8.68181 20.0154 -10,
+                          10.4852 20.373 -10,
+                          10.7674 18.976 -10,
+                          8.68181 20.0154 -10,
+                          10.4852 20.373 -10,
+                          8.68181 20.0154 -10,
+                          8.68001 21.2057 -10,
+                          7.76781 21.556 -10,
+                          7.92518 20.3271 -10,
+                          5.61372 21.0828 -10,
+                          7.76781 21.556 -10,
+                          8.68001 21.2057 -10,
+                          7.92518 20.3271 -10,
+                          7.76781 21.556 -10,
+                          5.61372 21.0828 -10,
+                          5.55866 22.2284 -10,
+                          5.96004 23.1822 -1.75003,
+                          4.48178 23.401 -2.88207,
+                          8.73984 21.6339 -5.62028,
+                          10.7674 18.976 -10,
+                          12.5617 18.787 -8.07796,
+                          8.73984 21.6339 -5.62028,
+                          11.5139 20.7846 -3.38079,
+                          8.73984 21.6339 -5.62028,
+                          12.5617 18.787 -8.07796,
+                          11.5139 20.7846 -3.38079,
+                          5.96004 23.1822 -1.75003,
+                          8.73984 21.6339 -5.62028,
+                          14.1064 16.6455 -10,
+                          15.6844 15.1683 -10,
+                          12.5617 18.787 -8.07796,
+                          16.2831 16.9706 -4.78116,
+                          12.5617 18.787 -8.07796,
+                          15.6844 15.1683 -10,
+                          10.7674 18.976 -10,
+                          14.1064 16.6455 -10,
+                          12.5617 18.787 -8.07796,
+                          16.2831 16.9706 -4.78116,
+                          11.5139 20.7846 -3.38079,
+                          12.5617 18.787 -8.07796,
+                          15.6703 16.7149 -10,
+                          15.6844 15.1683 -10,
+                          14.1064 16.6455 -10,
+                          17.7242 12.7258 -10,
+                          16.2831 16.9706 -4.78116,
+                          15.6844 15.1683 -10,
+                          17.2582 15.0717 -10,
+                          17.7242 12.7258 -10,
+                          15.6844 15.1683 -10,
+                          17.2582 15.0717 -10,
+                          15.6844 15.1683 -10,
+                          15.6703 16.7149 -10,
+                          13.6892 18.374 -10,
+                          14.1064 16.6455 -10,
+                          10.7674 18.976 -10,
+                          13.6892 18.374 -10,
+                          15.6703 16.7149 -10,
+                          14.1064 16.6455 -10,
+                          13.6892 18.374 -10,
+                          10.7674 18.976 -10,
+                          10.4852 20.373 -10,
+                          6.70237 23.0451 9.86274e-15,
+                          5.96004 23.1822 -1.75003,
+                          11.5139 20.7846 -3.38079,
+                          12.9292 20.2197 1.41291e-14,
+                          11.5139 20.7846 -3.38079,
+                          16.2831 16.9706 -4.78116,
+                          12.9292 20.2197 1.41291e-14,
+                          6.70237 23.0451 9.86274e-15,
+                          11.5139 20.7846 -3.38079,
+                          17.7242 12.7258 -10,
+                          19.9427 12 -5.8557,
+                          16.2831 16.9706 -4.78116,
+                          18.1065 15.7529 1.85405e-14,
+                          16.2831 16.9706 -4.78116,
+                          19.9427 12 -5.8557,
+                          18.1065 15.7529 1.85405e-14,
+                          12.9292 20.2197 1.41291e-14,
+                          16.2831 16.9706 -4.78116,
+                          20.7371 6.77933 -10,
+                          22.2432 6.21166 -6.53119,
+                          19.9427 12 -5.8557,
+                          21.8141 10.0074 2.27389e-14,
+                          19.9427 12 -5.8557,
+                          22.2432 6.21166 -6.53119,
+                          17.7242 12.7258 -10,
+                          20.7371 6.77933 -10,
+                          19.9427 12 -5.8557,
+                          21.8141 10.0074 2.27389e-14,
+                          18.1065 15.7529 1.85405e-14,
+                          19.9427 12 -5.8557,
+                          21.8174 -0.000278048 -10,
+                          23.0278 3.96857e-15 -6.76158,
+                          22.2432 6.21166 -6.53119,
+                          23.7508 3.44948 2.63834e-14,
+                          22.2432 6.21166 -6.53119,
+                          23.0278 3.96857e-15 -6.76158,
+                          20.7371 6.77933 -10,
+                          21.8174 -0.000278048 -10,
+                          22.2432 6.21166 -6.53119,
+                          23.7508 3.44948 2.63834e-14,
+                          21.8141 10.0074 2.27389e-14,
+                          22.2432 6.21166 -6.53119,
+                          21.8174 -0.000278048 -10,
+                          22.2432 -6.21166 -6.53119,
+                          23.0278 3.96857e-15 -6.76158,
+                          23.7596 -3.38842 2.91782e-14,
+                          23.0278 3.96857e-15 -6.76158,
+                          22.2432 -6.21166 -6.53119,
+                          23.7596 -3.38842 2.91782e-14,
+                          23.7508 3.44948 2.63834e-14,
+                          23.0278 3.96857e-15 -6.76158,
+                          20.737 -6.77986 -10,
+                          19.9427 -12 -5.8557,
+                          22.2432 -6.21166 -6.53119,
+                          21.8397 -9.95125 3.08964e-14,
+                          22.2432 -6.21166 -6.53119,
+                          19.9427 -12 -5.8557,
+                          21.8174 -0.000278048 -10,
+                          20.737 -6.77986 -10,
+                          22.2432 -6.21166 -6.53119,
+                          21.8397 -9.95125 3.08964e-14,
+                          23.7596 -3.38842 2.91782e-14,
+                          22.2432 -6.21166 -6.53119,
+                          15.6844 -15.1683 -10,
+                          16.2831 -16.9706 -4.78116,
+                          19.9427 -12 -5.8557,
+                          18.147 -15.7063 3.13986e-14,
+                          19.9427 -12 -5.8557,
+                          16.2831 -16.9706 -4.78116,
+                          17.7239 -12.7262 -10,
+                          15.6844 -15.1683 -10,
+                          19.9427 -12 -5.8557,
+                          20.737 -6.77986 -10,
+                          17.7239 -12.7262 -10,
+                          19.9427 -12 -5.8557,
+                          18.147 -15.7063 3.13986e-14,
+                          21.8397 -9.95125 3.08964e-14,
+                          19.9427 -12 -5.8557,
+                          12.5617 -18.787 -8.07796,
+                          11.5139 -20.7846 -3.38079,
+                          16.2831 -16.9706 -4.78116,
+                          12.9811 -20.1864 3.0644e-14,
+                          16.2831 -16.9706 -4.78116,
+                          11.5139 -20.7846 -3.38079,
+                          15.6844 -15.1683 -10,
+                          12.5617 -18.787 -8.07796,
+                          16.2831 -16.9706 -4.78116,
+                          12.9811 -20.1864 3.0644e-14,
+                          18.147 -15.7063 3.13986e-14,
+                          16.2831 -16.9706 -4.78116,
+                          8.73985 -21.6339 -5.62029,
+                          5.96004 -23.1822 -1.75003,
+                          11.5139 -20.7846 -3.38079,
+                          6.76158 -23.0278 2.86938e-14,
+                          11.5139 -20.7846 -3.38079,
+                          5.96004 -23.1822 -1.75003,
+                          12.5617 -18.787 -8.07796,
+                          8.73985 -21.6339 -5.62029,
+                          11.5139 -20.7846 -3.38079,
+                          6.76158 -23.0278 2.86938e-14,
+                          12.9811 -20.1864 3.0644e-14,
+                          11.5139 -20.7846 -3.38079,
+                          8.73985 -21.6339 -5.62029,
+                          4.48178 -23.401 -2.88207,
+                          5.96004 -23.1822 -1.75003,
+                          6.00557 -22.1762 -6.93881,
+                          4.48178 -23.401 -2.88207,
+                          8.73985 -21.6339 -5.62029,
+                          6.00557 -22.1762 -6.93881,
+                          3.06151 -23.5396 -3.53725,
+                          4.48178 -23.401 -2.88207,
+                          8.68181 -20.0154 -10,
+                          8.73985 -21.6339 -5.62029,
+                          12.5617 -18.787 -8.07796,
+                          8.68181 -20.0154 -10,
+                          6.00557 -22.1762 -6.93881,
+                          8.73985 -21.6339 -5.62029,
+                          14.1061 -16.6457 -10,
+                          12.5617 -18.787 -8.07796,
+                          15.6844 -15.1683 -10,
+                          10.7671 -18.9762 -10,
+                          8.68181 -20.0154 -10,
+                          12.5617 -18.787 -8.07796,
+                          14.1061 -16.6457 -10,
+                          10.7671 -18.9762 -10,
+                          12.5617 -18.787 -8.07796,
+                          17.2578 -15.0721 -10,
+                          15.6844 -15.1683 -10,
+                          17.7239 -12.7262 -10,
+                          15.6703 -16.7149 -10,
+                          14.1061 -16.6457 -10,
+                          15.6844 -15.1683 -10,
+                          17.2578 -15.0721 -10,
+                          15.6703 -16.7149 -10,
+                          15.6844 -15.1683 -10,
+                          20.6934 -9.83782 -10,
+                          17.7239 -12.7262 -10,
+                          20.737 -6.77986 -10,
+                          17.2578 -15.0721 -10,
+                          17.7239 -12.7262 -10,
+                          20.6934 -9.83782 -10,
+                          20.6934 -9.83782 -10,
+                          20.737 -6.77986 -10,
+                          21.8174 -0.000278048 -10,
+                          22.6632 3.3736 -10,
+                          21.8174 -0.000278048 -10,
+                          20.7371 6.77933 -10,
+                          22.6631 -3.37428 -10,
+                          21.8174 -0.000278048 -10,
+                          22.6632 3.3736 -10,
+                          20.6934 -9.83782 -10,
+                          21.8174 -0.000278048 -10,
+                          22.6631 -3.37428 -10,
+                          20.6937 9.83719 -10,
+                          20.7371 6.77933 -10,
+                          17.7242 12.7258 -10,
+                          22.6632 3.3736 -10,
+                          20.7371 6.77933 -10,
+                          20.6937 9.83719 -10,
+                          20.6937 9.83719 -10,
+                          17.7242 12.7258 -10,
+                          17.2582 15.0717 -10,
+                          12.4887 20.2197 3.34633,
+                          6.70237 23.0451 9.86274e-15,
+                          12.9292 20.2197 1.41291e-14,
+                          12.4887 20.2197 3.34633,
+                          6.47399 23.0451 1.7347,
+                          6.70237 23.0451 9.86274e-15,
+                          17.5549 15.7529 4.43525,
+                          12.9292 20.2197 1.41291e-14,
+                          18.1065 15.7529 1.85405e-14,
+                          17.5549 15.7529 4.43525,
+                          12.4887 20.2197 3.34633,
+                          12.9292 20.2197 1.41291e-14,
+                          21.1773 10.0074 5.23195,
+                          18.1065 15.7529 1.85405e-14,
+                          21.8141 10.0074 2.27389e-14,
+                          21.1773 10.0074 5.23195,
+                          17.5549 15.7529 4.43525,
+                          18.1065 15.7529 1.85405e-14,
+                          23.2066 3.44948 5.05501,
+                          21.8141 10.0074 2.27389e-14,
+                          23.7508 3.44948 2.63834e-14,
+                          23.2066 3.44948 5.05501,
+                          21.1773 10.0074 5.23195,
+                          21.8141 10.0074 2.27389e-14,
+                          23.2113 -3.38842 5.07486,
+                          23.7508 3.44948 2.63834e-14,
+                          23.7596 -3.38842 2.91782e-14,
+                          23.2113 -3.38842 5.07486,
+                          23.2066 3.44948 5.05501,
+                          23.7508 3.44948 2.63834e-14,
+                          21.2119 -9.95125 5.19874,
+                          23.7596 -3.38842 2.91782e-14,
+                          21.8397 -9.95125 3.08964e-14,
+                          21.2119 -9.95125 5.19874,
+                          23.2113 -3.38842 5.07486,
+                          23.7596 -3.38842 2.91782e-14,
+                          17.611 -15.7063 4.37775,
+                          21.8397 -9.95125 3.08964e-14,
+                          18.147 -15.7063 3.13986e-14,
+                          17.611 -15.7063 4.37775,
+                          21.2119 -9.95125 5.19874,
+                          21.8397 -9.95125 3.08964e-14,
+                          12.5388 -20.1864 3.35977,
+                          18.147 -15.7063 3.13986e-14,
+                          12.9811 -20.1864 3.0644e-14,
+                          12.5388 -20.1864 3.35977,
+                          17.611 -15.7063 4.37775,
+                          18.147 -15.7063 3.13986e-14,
+                          6.53119 -23.0278 1.75003,
+                          12.9811 -20.1864 3.0644e-14,
+                          6.76158 -23.0278 2.86938e-14,
+                          12.5388 -20.1864 3.35977,
+                          12.9811 -20.1864 3.0644e-14,
+                          6.53119 -23.0278 1.75003,
+                          2.35555 -23.3179 -5.16965,
+                          3.06151 -23.5396 -3.53725,
+                          6.00557 -22.1762 -6.93881,
+                          7.92497 -20.3272 -10,
+                          6.00557 -22.1762 -6.93881,
+                          8.68181 -20.0154 -10,
+                          4.56213 -21.3351 -10,
+                          2.35555 -23.3179 -5.16965,
+                          6.00557 -22.1762 -6.93881,
+                          5.61355 -21.0829 -10,
+                          4.56213 -21.3351 -10,
+                          6.00557 -22.1762 -6.93881,
+                          7.92497 -20.3272 -10,
+                          5.61355 -21.0829 -10,
+                          6.00557 -22.1762 -6.93881,
+                          8.68001 -21.2057 -10,
+                          8.68181 -20.0154 -10,
+                          10.7671 -18.9762 -10,
+                          7.76756 -21.5561 -10,
+                          7.92497 -20.3272 -10,
+                          8.68181 -20.0154 -10,
+                          7.76756 -21.5561 -10,
+                          8.68181 -20.0154 -10,
+                          8.68001 -21.2057 -10,
+                          13.6889 -18.3743 -10,
+                          10.7671 -18.9762 -10,
+                          14.1061 -16.6457 -10,
+                          10.4849 -20.3732 -10,
+                          8.68001 -21.2057 -10,
+                          10.7671 -18.9762 -10,
+                          10.4849 -20.3732 -10,
+                          10.7671 -18.9762 -10,
+                          13.6889 -18.3743 -10,
+                          13.6889 -18.3743 -10,
+                          14.1061 -16.6457 -10,
+                          15.6703 -16.7149 -10,
+                          3.70526 -21.5005 -10,
+                          2.35555 -23.3179 -5.16965,
+                          4.56213 -21.3351 -10,
+                          1.43235 -21.7703 -10,
+                          0.732585 -23.4324 -5.13689,
+                          2.35555 -23.3179 -5.16965,
+                          1.86187 -21.7378 -10,
+                          1.43235 -21.7703 -10,
+                          2.35555 -23.3179 -5.16965,
+                          3.70526 -21.5005 -10,
+                          1.86187 -21.7378 -10,
+                          2.35555 -23.3179 -5.16965,
+                          5.55845 -22.2284 -10,
+                          4.56213 -21.3351 -10,
+                          5.61355 -21.0829 -10,
+                          4.5675 -22.4531 -10,
+                          3.70526 -21.5005 -10,
+                          4.56213 -21.3351 -10,
+                          5.55845 -22.2284 -10,
+                          4.5675 -22.4531 -10,
+                          4.56213 -21.3351 -10,
+                          7.76756 -21.5561 -10,
+                          5.61355 -21.0829 -10,
+                          7.92497 -20.3272 -10,
+                          5.55845 -22.2284 -10,
+                          5.61355 -21.0829 -10,
+                          7.76756 -21.5561 -10,
+                          -0.745972 -23.4321 -5.13627,
+                          0.732585 -23.4324 -5.13689,
+                          1.43235 -21.7703 -10,
+                          1.85243 -22.8379 -10,
+                          1.43235 -21.7703 -10,
+                          1.86187 -21.7378 -10,
+                          -1.52176e-15 -21.8174 -10,
+                          -0.745972 -23.4321 -5.13627,
+                          1.43235 -21.7703 -10,
+                          -1.09109e-15 -22.9129 -10,
+                          -1.52176e-15 -21.8174 -10,
+                          1.43235 -21.7703 -10,
+                          -1.09109e-15 -22.9129 -10,
+                          1.43235 -21.7703 -10,
+                          1.43179 -22.8681 -10,
+                          1.85243 -22.8379 -10,
+                          1.43179 -22.8681 -10,
+                          1.43235 -21.7703 -10,
+                          3.68914 -22.6139 -10,
+                          1.86187 -21.7378 -10,
+                          3.70526 -21.5005 -10,
+                          1.85243 -22.8379 -10,
+                          1.86187 -21.7378 -10,
+                          3.68914 -22.6139 -10,
+                          3.68914 -22.6139 -10,
+                          3.70526 -21.5005 -10,
+                          4.5675 -22.4531 -10,
+                          -1.52176e-15 -21.8174 -10,
+                          -1.45843 -21.7686 -10,
+                          -0.745972 -23.4321 -5.13627,
+                          -2.37184 -23.3162 -5.17014,
+                          -0.745972 -23.4321 -5.13627,
+                          -1.45843 -21.7686 -10,
+                          -1.45786 -22.8664 -10,
+                          -1.45843 -21.7686 -10,
+                          -1.52176e-15 -21.8174 -10,
+                          -1.86195 -21.7378 -10,
+                          -2.37184 -23.3162 -5.17014,
+                          -1.45843 -21.7686 -10,
+                          -1.85253 -22.8379 -10,
+                          -1.86195 -21.7378 -10,
+                          -1.45843 -21.7686 -10,
+                          -1.85253 -22.8379 -10,
+                          -1.45843 -21.7686 -10,
+                          -1.45786 -22.8664 -10,
+                          -1.09109e-15 -22.9129 -10,
+                          -1.45786 -22.8664 -10,
+                          -1.52176e-15 -21.8174 -10,
+                          -3.70541 -21.5005 -10,
+                          -4.59308 -21.3284 -10,
+                          -2.37184 -23.3162 -5.17014,
+                          -6.0395 -22.1661 -6.94187,
+                          -2.37184 -23.3162 -5.17014,
+                          -4.59308 -21.3284 -10,
+                          -1.86195 -21.7378 -10,
+                          -3.70541 -21.5005 -10,
+                          -2.37184 -23.3162 -5.17014,
+                          -6.0395 -22.1661 -6.94187,
+                          -3.07915 -23.5371 -3.5392,
+                          -2.37184 -23.3162 -5.17014,
+                          -4.59867 -22.4467 -10,
+                          -4.59308 -21.3284 -10,
+                          -3.70541 -21.5005 -10,
+                          -5.61372 -21.0828 -10,
+                          -6.0395 -22.1661 -6.94187,
+                          -4.59308 -21.3284 -10,
+                          -5.55866 -22.2284 -10,
+                          -5.61372 -21.0828 -10,
+                          -4.59308 -21.3284 -10,
+                          -5.55866 -22.2284 -10,
+                          -4.59308 -21.3284 -10,
+                          -4.59867 -22.4467 -10,
+                          -3.68933 -22.6139 -10,
+                          -3.70541 -21.5005 -10,
+                          -1.86195 -21.7378 -10,
+                          -3.68933 -22.6139 -10,
+                          -4.59867 -22.4467 -10,
+                          -3.70541 -21.5005 -10,
+                          -3.68933 -22.6139 -10,
+                          -1.86195 -21.7378 -10,
+                          -1.85253 -22.8379 -10,
+                          -7.92518 -20.3271 -10,
+                          -8.72801 -19.9952 -10,
+                          -6.0395 -22.1661 -6.94187,
+                          -5.61372 -21.0828 -10,
+                          -7.92518 -20.3271 -10,
+                          -6.0395 -22.1661 -6.94187,
+                          -8.7259 -21.1869 -10,
+                          -8.72801 -19.9952 -10,
+                          -7.92518 -20.3271 -10,
+                          -10.4852 -20.373 -10,
+                          -10.7674 -18.976 -10,
+                          -8.72801 -19.9952 -10,
+                          -10.4852 -20.373 -10,
+                          -8.72801 -19.9952 -10,
+                          -8.7259 -21.1869 -10,
+                          -7.76781 -21.556 -10,
+                          -7.92518 -20.3271 -10,
+                          -5.61372 -21.0828 -10,
+                          -7.76781 -21.556 -10,
+                          -8.7259 -21.1869 -10,
+                          -7.92518 -20.3271 -10,
+                          -7.76781 -21.556 -10,
+                          -5.61372 -21.0828 -10,
+                          -5.55866 -22.2284 -10,
+                          -13.6892 -18.374 -10,
+                          -14.1064 -16.6455 -10,
+                          -10.7674 -18.976 -10,
+                          -13.6892 -18.374 -10,
+                          -15.7577 -16.6324 -10,
+                          -14.1064 -16.6455 -10,
+                          -13.6892 -18.374 -10,
+                          -10.7674 -18.976 -10,
+                          -10.4852 -20.373 -10,
+                          -7.04331 -23.9873 1.99177e-14,
+                          -6.21304 -24.1481 -1.80698,
+                          4.2539e-15 -25 2.61179e-14,
+                          -5.88702 -24.0036 -3.76438,
+                          4.2539e-15 -25 2.61179e-14,
+                          -6.21304 -24.1481 -1.80698,
+                          -6.80332 -23.9873 1.82294,
+                          -7.04331 -23.9873 1.99177e-14,
+                          4.2539e-15 -25 2.61179e-14,
+                          -4.56377 -24.0136 -5.24565,
+                          4.2539e-15 -25 2.61179e-14,
+                          -5.88702 -24.0036 -3.76438,
+                          -2.36554 -24.3478 -5.15641,
+                          4.2539e-15 -25 2.61179e-14,
+                          -4.56377 -24.0136 -5.24565,
+                          -0.744423 -24.4576 -5.1256,
+                          4.2539e-15 -25 2.61179e-14,
+                          -2.36554 -24.3478 -5.15641,
+                          0.731065 -24.4579 -5.12623,
+                          4.2539e-15 -25 2.61179e-14,
+                          -0.744423 -24.4576 -5.1256,
+                          2.34934 -24.3495 -5.15602,
+                          4.2539e-15 -25 2.61179e-14,
+                          0.731065 -24.4579 -5.12623,
+                          4.53844 -24.0189 -5.24369,
+                          4.2539e-15 -25 2.61179e-14,
+                          2.34934 -24.3495 -5.15602,
+                          5.84811 -24.0137 -3.76071,
+                          4.2539e-15 -25 2.61179e-14,
+                          4.53844 -24.0189 -5.24369,
+                          6.20838 -24.1481 -1.82294,
+                          4.2539e-15 -25 2.61179e-14,
+                          5.84811 -24.0137 -3.76071,
+                          7.04331 -23.9873 2.92262e-14,
+                          4.2539e-15 -25 2.61179e-14,
+                          6.20838 -24.1481 -1.82294,
+                          6.80332 -23.9873 1.82294,
+                          4.2539e-15 -25 2.61179e-14,
+                          7.04331 -23.9873 2.92262e-14,
+                          -6.09969 -23.9873 3.52166,
+                          -6.80332 -23.9873 1.82294,
+                          4.2539e-15 -25 2.61179e-14,
+                          -4.98037 -23.9873 4.98037,
+                          -6.09969 -23.9873 3.52166,
+                          4.2539e-15 -25 2.61179e-14,
+                          -3.52166 -23.9873 6.09969,
+                          -4.98037 -23.9873 4.98037,
+                          4.2539e-15 -25 2.61179e-14,
+                          -1.82294 -23.9873 6.80332,
+                          -3.52166 -23.9873 6.09969,
+                          4.2539e-15 -25 2.61179e-14,
+                          -7.3214e-16 -23.9873 7.04331,
+                          -1.82294 -23.9873 6.80332,
+                          4.2539e-15 -25 2.61179e-14,
+                          1.82294 -23.9873 6.80332,
+                          -7.3214e-16 -23.9873 7.04331,
+                          4.2539e-15 -25 2.61179e-14,
+                          3.52166 -23.9873 6.09969,
+                          1.82294 -23.9873 6.80332,
+                          4.2539e-15 -25 2.61179e-14,
+                          4.98037 -23.9873 4.98037,
+                          3.52166 -23.9873 6.09969,
+                          4.2539e-15 -25 2.61179e-14,
+                          6.09969 -23.9873 3.52166,
+                          4.98037 -23.9873 4.98037,
+                          4.2539e-15 -25 2.61179e-14,
+                          6.80332 -23.9873 1.82294,
+                          6.09969 -23.9873 3.52166,
+                          4.2539e-15 -25 2.61179e-14,
+                          -7.04331 -23.9873 1.99177e-14,
+                          -12.0027 -21.6506 -3.49082,
+                          -6.21304 -24.1481 -1.80698,
+                          -5.88702 -24.0036 -3.76438,
+                          -6.21304 -24.1481 -1.80698,
+                          -12.0027 -21.6506 -3.49082,
+                          -13.522 -21.0275 1.33868e-14,
+                          -16.9743 -17.6777 -4.93676,
+                          -12.0027 -21.6506 -3.49082,
+                          -11.3048 -21.0938 -7.22869,
+                          -12.0027 -21.6506 -3.49082,
+                          -16.9743 -17.6777 -4.93676,
+                          -7.04331 -23.9873 1.99177e-14,
+                          -13.522 -21.0275 1.33868e-14,
+                          -12.0027 -21.6506 -3.49082,
+                          -11.3048 -21.0938 -7.22869,
+                          -5.88702 -24.0036 -3.76438,
+                          -12.0027 -21.6506 -3.49082,
+                          -18.9031 -16.3607 7.06119e-15,
+                          -20.7892 -12.5 -6.04627,
+                          -16.9743 -17.6777 -4.93676,
+                          -15.7577 -16.6324 -10,
+                          -16.9743 -17.6777 -4.93676,
+                          -20.7892 -12.5 -6.04627,
+                          -13.522 -21.0275 1.33868e-14,
+                          -18.9031 -16.3607 7.06119e-15,
+                          -16.9743 -17.6777 -4.93676,
+                          -15.7577 -16.6324 -10,
+                          -11.3048 -21.0938 -7.22869,
+                          -16.9743 -17.6777 -4.93676,
+                          -22.7497 -10.3659 1.45438e-15,
+                          -23.1874 -6.47048 -6.74374,
+                          -20.7892 -12.5 -6.04627,
+                          -20.6937 -9.83719 -10,
+                          -20.7892 -12.5 -6.04627,
+                          -23.1874 -6.47048 -6.74374,
+                          -18.9031 -16.3607 7.06119e-15,
+                          -22.7497 -10.3659 1.45438e-15,
+                          -20.7892 -12.5 -6.04627,
+                          -17.2582 -15.0717 -10,
+                          -15.7577 -16.6324 -10,
+                          -20.7892 -12.5 -6.04627,
+                          -20.6937 -9.83719 -10,
+                          -17.2582 -15.0717 -10,
+                          -20.7892 -12.5 -6.04627,
+                          -24.7496 -3.5296 -2.97853e-15,
+                          -24.0054 -1.48569e-14 -6.98163,
+                          -23.1874 -6.47048 -6.74374,
+                          -22.6632 -3.3736 -10,
+                          -23.1874 -6.47048 -6.74374,
+                          -24.0054 -1.48569e-14 -6.98163,
+                          -22.7497 -10.3659 1.45438e-15,
+                          -24.7496 -3.5296 -2.97853e-15,
+                          -23.1874 -6.47048 -6.74374,
+                          -22.6632 -3.3736 -10,
+                          -20.6937 -9.83719 -10,
+                          -23.1874 -6.47048 -6.74374,
+                          -24.7404 3.5932 -5.87768e-15,
+                          -23.1874 6.47048 -6.74374,
+                          -24.0054 -1.48569e-14 -6.98163,
+                          -22.6631 3.37428 -10,
+                          -24.0054 -1.48569e-14 -6.98163,
+                          -23.1874 6.47048 -6.74374,
+                          -24.7496 -3.5296 -2.97853e-15,
+                          -24.7404 3.5932 -5.87768e-15,
+                          -24.0054 -1.48569e-14 -6.98163,
+                          -22.6631 3.37428 -10,
+                          -22.6632 -3.3736 -10,
+                          -24.0054 -1.48569e-14 -6.98163,
+                          -22.723 10.4243 3.08329e-15,
+                          -20.7892 12.5 -6.04627,
+                          -23.1874 6.47048 -6.74374,
+                          -20.6934 9.83782 -10,
+                          -23.1874 6.47048 -6.74374,
+                          -20.7892 12.5 -6.04627,
+                          -24.7404 3.5932 -5.87768e-15,
+                          -22.723 10.4243 3.08329e-15,
+                          -23.1874 6.47048 -6.74374,
+                          -20.6934 9.83782 -10,
+                          -22.6631 3.37428 -10,
+                          -23.1874 6.47048 -6.74374,
+                          -18.861 16.4093 -6.27697e-15,
+                          -16.9743 17.6777 -4.93676,
+                          -20.7892 12.5 -6.04627,
+                          -17.2578 15.0721 -10,
+                          -20.7892 12.5 -6.04627,
+                          -16.9743 17.6777 -4.93676,
+                          -22.723 10.4243 3.08329e-15,
+                          -18.861 16.4093 -6.27697e-15,
+                          -20.7892 12.5 -6.04627,
+                          -17.2578 15.0721 -10,
+                          -20.6934 9.83782 -10,
+                          -20.7892 12.5 -6.04627,
+                          -13.4679 21.0622 -3.7447e-15,
+                          -12.0027 21.6506 -3.49082,
+                          -16.9743 17.6777 -4.93676,
+                          -11.3048 21.0938 -7.22869,
+                          -16.9743 17.6777 -4.93676,
+                          -12.0027 21.6506 -3.49082,
+                          -18.861 16.4093 -6.27697e-15,
+                          -13.4679 21.0622 -3.7447e-15,
+                          -16.9743 17.6777 -4.93676,
+                          -15.7577 16.6324 -10,
+                          -17.2578 15.0721 -10,
+                          -16.9743 17.6777 -4.93676,
+                          -11.3048 21.0938 -7.22869,
+                          -15.7577 16.6324 -10,
+                          -16.9743 17.6777 -4.93676,
+                          -6.98163 24.0054 3.83521e-16,
+                          -6.21304 24.1481 -1.80698,
+                          -12.0027 21.6506 -3.49082,
+                          -5.88702 24.0036 -3.76438,
+                          -12.0027 21.6506 -3.49082,
+                          -6.21304 24.1481 -1.80698,
+                          -13.4679 21.0622 -3.7447e-15,
+                          -6.98163 24.0054 3.83521e-16,
+                          -12.0027 21.6506 -3.49082,
+                          -5.88702 24.0036 -3.76438,
+                          -11.3048 21.0938 -7.22869,
+                          -12.0027 21.6506 -3.49082,
+                          -6.98163 24.0054 3.83521e-16,
+                          -2.72839e-14 25 3.14895e-15,
+                          -6.21304 24.1481 -1.80698,
+                          -5.88702 24.0036 -3.76438,
+                          -6.21304 24.1481 -1.80698,
+                          -2.72839e-14 25 3.14895e-15,
+                          -6.74374 24.0054 1.80698,
+                          -2.72839e-14 25 3.14895e-15,
+                          -6.98163 24.0054 3.83521e-16,
+                          -4.56378 24.0136 -5.24565,
+                          -5.88702 24.0036 -3.76438,
+                          -2.72839e-14 25 3.14895e-15,
+                          5.84812 24.0137 -3.76072,
+                          -2.72839e-14 25 3.14895e-15,
+                          6.20838 24.1481 -1.82294,
+                          6.98163 24.0054 9.61052e-15,
+                          6.20838 24.1481 -1.82294,
+                          -2.72839e-14 25 3.14895e-15,
+                          4.53844 24.0189 -5.24369,
+                          -2.72839e-14 25 3.14895e-15,
+                          5.84812 24.0137 -3.76072,
+                          6.74374 24.0054 1.80698,
+                          6.98163 24.0054 9.61052e-15,
+                          -2.72839e-14 25 3.14895e-15,
+                          2.34934 24.3495 -5.15602,
+                          -2.72839e-14 25 3.14895e-15,
+                          4.53844 24.0189 -5.24369,
+                          0.731065 24.4579 -5.12624,
+                          -2.72839e-14 25 3.14895e-15,
+                          2.34934 24.3495 -5.15602,
+                          -0.744422 24.4576 -5.1256,
+                          -2.72839e-14 25 3.14895e-15,
+                          0.731065 24.4579 -5.12624,
+                          -2.36554 24.3478 -5.15641,
+                          -2.72839e-14 25 3.14895e-15,
+                          -0.744422 24.4576 -5.1256,
+                          -4.56378 24.0136 -5.24565,
+                          -2.72839e-14 25 3.14895e-15,
+                          -2.36554 24.3478 -5.15641,
+                          6.04627 24.0054 3.49082,
+                          6.74374 24.0054 1.80698,
+                          -2.72839e-14 25 3.14895e-15,
+                          4.93676 24.0054 4.93676,
+                          6.04627 24.0054 3.49082,
+                          -2.72839e-14 25 3.14895e-15,
+                          3.49082 24.0054 6.04627,
+                          4.93676 24.0054 4.93676,
+                          -2.72839e-14 25 3.14895e-15,
+                          1.80698 24.0054 6.74374,
+                          3.49082 24.0054 6.04627,
+                          -2.72839e-14 25 3.14895e-15,
+                          -1.95868e-14 24.0054 6.98163,
+                          1.80698 24.0054 6.74374,
+                          -2.72839e-14 25 3.14895e-15,
+                          -1.80698 24.0054 6.74374,
+                          -1.95868e-14 24.0054 6.98163,
+                          -2.72839e-14 25 3.14895e-15,
+                          -3.49082 24.0054 6.04627,
+                          -1.80698 24.0054 6.74374,
+                          -2.72839e-14 25 3.14895e-15,
+                          -4.93676 24.0054 4.93676,
+                          -3.49082 24.0054 6.04627,
+                          -2.72839e-14 25 3.14895e-15,
+                          -6.04627 24.0054 3.49082,
+                          -4.93676 24.0054 4.93676,
+                          -2.72839e-14 25 3.14895e-15,
+                          -6.74374 24.0054 1.80698,
+                          -6.04627 24.0054 3.49082,
+                          -2.72839e-14 25 3.14895e-15,
+                          -13.009 21.0622 3.48576,
+                          -6.98163 24.0054 3.83521e-16,
+                          -13.4679 21.0622 -3.7447e-15,
+                          -13.009 21.0622 3.48576,
+                          -6.74374 24.0054 1.80698,
+                          -6.98163 24.0054 3.83521e-16,
+                          -18.2183 16.4093 4.88158,
+                          -13.4679 21.0622 -3.7447e-15,
+                          -18.861 16.4093 -6.27697e-15,
+                          -13.009 21.0622 3.48576,
+                          -13.4679 21.0622 -3.7447e-15,
+                          -18.2183 16.4093 4.88158,
+                          -21.9981 10.4243 5.69362,
+                          -18.861 16.4093 -6.27697e-15,
+                          -22.723 10.4243 3.08329e-15,
+                          -18.2183 16.4093 4.88158,
+                          -18.861 16.4093 -6.27697e-15,
+                          -21.9981 10.4243 5.69362,
+                          -24.1233 3.5932 5.49134,
+                          -22.723 10.4243 3.08329e-15,
+                          -24.7404 3.5932 -5.87768e-15,
+                          -24.1233 3.5932 5.49134,
+                          -21.9981 10.4243 5.69362,
+                          -22.723 10.4243 3.08329e-15,
+                          -24.1327 -3.5296 5.49133,
+                          -24.7404 3.5932 -5.87768e-15,
+                          -24.7496 -3.5296 -2.97853e-15,
+                          -24.1233 3.5932 5.49134,
+                          -24.7404 3.5932 -5.87768e-15,
+                          -24.1327 -3.5296 5.49133,
+                          -22.0274 -10.3659 5.68713,
+                          -24.7496 -3.5296 -2.97853e-15,
+                          -22.7497 -10.3659 1.45438e-15,
+                          -24.1327 -3.5296 5.49133,
+                          -24.7496 -3.5296 -2.97853e-15,
+                          -22.0274 -10.3659 5.68713,
+                          -18.259 -16.3607 4.89248,
+                          -22.7497 -10.3659 1.45438e-15,
+                          -18.9031 -16.3607 7.06119e-15,
+                          -22.0274 -10.3659 5.68713,
+                          -22.7497 -10.3659 1.45438e-15,
+                          -18.259 -16.3607 4.89248,
+                          -13.0613 -21.0275 3.49976,
+                          -18.9031 -16.3607 7.06119e-15,
+                          -13.522 -21.0275 1.33868e-14,
+                          -18.259 -16.3607 4.89248,
+                          -18.9031 -16.3607 7.06119e-15,
+                          -13.0613 -21.0275 3.49976,
+                          -6.80332 -23.9873 1.82294,
+                          -13.522 -21.0275 1.33868e-14,
+                          -7.04331 -23.9873 1.99177e-14,
+                          -13.0613 -21.0275 3.49976,
+                          -13.522 -21.0275 1.33868e-14,
+                          -6.80332 -23.9873 1.82294,
+                          -8.7259 -21.1869 -10,
+                          -5.88702 -24.0036 -3.76438,
+                          -11.3048 -21.0938 -7.22869,
+                          -8.7259 -21.1869 -10,
+                          -4.56377 -24.0136 -5.24565,
+                          -5.88702 -24.0036 -3.76438,
+                          -13.6892 -18.374 -10,
+                          -11.3048 -21.0938 -7.22869,
+                          -15.7577 -16.6324 -10,
+                          -10.4852 -20.373 -10,
+                          -8.7259 -21.1869 -10,
+                          -11.3048 -21.0938 -7.22869,
+                          -13.6892 -18.374 -10,
+                          -10.4852 -20.373 -10,
+                          -11.3048 -21.0938 -7.22869,
+                          -13.6889 18.3743 -10,
+                          -15.7577 16.6324 -10,
+                          -11.3048 21.0938 -7.22869,
+                          -8.7259 21.1869 -10,
+                          -11.3048 21.0938 -7.22869,
+                          -5.88702 24.0036 -3.76438,
+                          -10.4849 20.3732 -10,
+                          -11.3048 21.0938 -7.22869,
+                          -8.7259 21.1869 -10,
+                          -10.4849 20.3732 -10,
+                          -13.6889 18.3743 -10,
+                          -11.3048 21.0938 -7.22869,
+                          -8.7259 21.1869 -10,
+                          -5.88702 24.0036 -3.76438,
+                          -4.56378 24.0136 -5.24565,
+                          -7.76781 -21.556 -10,
+                          -4.56377 -24.0136 -5.24565,
+                          -8.7259 -21.1869 -10,
+                          -4.59867 -22.4467 -10,
+                          -2.36554 -24.3478 -5.15641,
+                          -4.56377 -24.0136 -5.24565,
+                          -5.55866 -22.2284 -10,
+                          -4.59867 -22.4467 -10,
+                          -4.56377 -24.0136 -5.24565,
+                          -7.76781 -21.556 -10,
+                          -5.55866 -22.2284 -10,
+                          -4.56377 -24.0136 -5.24565,
+                          -3.68933 -22.6139 -10,
+                          -2.36554 -24.3478 -5.15641,
+                          -4.59867 -22.4467 -10,
+                          -1.45786 -22.8664 -10,
+                          -0.744423 -24.4576 -5.1256,
+                          -2.36554 -24.3478 -5.15641,
+                          -1.85253 -22.8379 -10,
+                          -1.45786 -22.8664 -10,
+                          -2.36554 -24.3478 -5.15641,
+                          -3.68933 -22.6139 -10,
+                          -1.85253 -22.8379 -10,
+                          -2.36554 -24.3478 -5.15641,
+                          -1.09109e-15 -22.9129 -10,
+                          -0.744423 -24.4576 -5.1256,
+                          -1.45786 -22.8664 -10,
+                          -1.09109e-15 -22.9129 -10,
+                          0.731065 -24.4579 -5.12623,
+                          -0.744423 -24.4576 -5.1256,
+                          -1.09109e-15 -22.9129 -10,
+                          1.43179 -22.8681 -10,
+                          0.731065 -24.4579 -5.12623,
+                          2.34934 -24.3495 -5.15602,
+                          0.731065 -24.4579 -5.12623,
+                          1.43179 -22.8681 -10,
+                          1.85243 -22.8379 -10,
+                          2.34934 -24.3495 -5.15602,
+                          1.43179 -22.8681 -10,
+                          3.68914 -22.6139 -10,
+                          4.5675 -22.4531 -10,
+                          2.34934 -24.3495 -5.15602,
+                          4.53844 -24.0189 -5.24369,
+                          2.34934 -24.3495 -5.15602,
+                          4.5675 -22.4531 -10,
+                          1.85243 -22.8379 -10,
+                          3.68914 -22.6139 -10,
+                          2.34934 -24.3495 -5.15602,
+                          5.55845 -22.2284 -10,
+                          4.53844 -24.0189 -5.24369,
+                          4.5675 -22.4531 -10,
+                          7.76756 -21.5561 -10,
+                          8.68001 -21.2057 -10,
+                          4.53844 -24.0189 -5.24369,
+                          5.84811 -24.0137 -3.76071,
+                          4.53844 -24.0189 -5.24369,
+                          8.68001 -21.2057 -10,
+                          5.55845 -22.2284 -10,
+                          7.76756 -21.5561 -10,
+                          4.53844 -24.0189 -5.24369,
+                          11.2348 -21.1325 -7.22469,
+                          5.84811 -24.0137 -3.76071,
+                          8.68001 -21.2057 -10,
+                          10.4849 -20.3732 -10,
+                          11.2348 -21.1325 -7.22469,
+                          8.68001 -21.2057 -10,
+                          11.9937 -21.6506 -3.52166,
+                          5.84811 -24.0137 -3.76071,
+                          11.2348 -21.1325 -7.22469,
+                          11.9937 -21.6506 -3.52166,
+                          6.20838 -24.1481 -1.82294,
+                          5.84811 -24.0137 -3.76071,
+                          13.6889 -18.3743 -10,
+                          15.6703 -16.7149 -10,
+                          11.2348 -21.1325 -7.22469,
+                          16.9616 -17.6777 -4.98037,
+                          11.2348 -21.1325 -7.22469,
+                          15.6703 -16.7149 -10,
+                          10.4849 -20.3732 -10,
+                          13.6889 -18.3743 -10,
+                          11.2348 -21.1325 -7.22469,
+                          16.9616 -17.6777 -4.98037,
+                          11.9937 -21.6506 -3.52166,
+                          11.2348 -21.1325 -7.22469,
+                          17.2578 -15.0721 -10,
+                          16.9616 -17.6777 -4.98037,
+                          15.6703 -16.7149 -10,
+                          7.04331 -23.9873 2.92262e-14,
+                          6.20838 -24.1481 -1.82294,
+                          11.9937 -21.6506 -3.52166,
+                          13.522 -21.0275 3.12576e-14,
+                          11.9937 -21.6506 -3.52166,
+                          16.9616 -17.6777 -4.98037,
+                          13.522 -21.0275 3.12576e-14,
+                          7.04331 -23.9873 2.92262e-14,
+                          11.9937 -21.6506 -3.52166,
+                          17.2578 -15.0721 -10,
+                          20.7736 -12.5 -6.09969,
+                          16.9616 -17.6777 -4.98037,
+                          18.9031 -16.3607 3.20437e-14,
+                          16.9616 -17.6777 -4.98037,
+                          20.7736 -12.5 -6.09969,
+                          18.9031 -16.3607 3.20437e-14,
+                          13.522 -21.0275 3.12576e-14,
+                          16.9616 -17.6777 -4.98037,
+                          20.6934 -9.83782 -10,
+                          23.17 -6.47048 -6.80332,
+                          20.7736 -12.5 -6.09969,
+                          22.7497 -10.3659 3.15206e-14,
+                          20.7736 -12.5 -6.09969,
+                          23.17 -6.47048 -6.80332,
+                          17.2578 -15.0721 -10,
+                          20.6934 -9.83782 -10,
+                          20.7736 -12.5 -6.09969,
+                          22.7497 -10.3659 3.15206e-14,
+                          18.9031 -16.3607 3.20437e-14,
+                          20.7736 -12.5 -6.09969,
+                          22.6631 -3.37428 -10,
+                          23.9873 3.98589e-15 -7.04331,
+                          23.17 -6.47048 -6.80332,
+                          24.7496 -3.5296 2.97308e-14,
+                          23.17 -6.47048 -6.80332,
+                          23.9873 3.98589e-15 -7.04331,
+                          20.6934 -9.83782 -10,
+                          22.6631 -3.37428 -10,
+                          23.17 -6.47048 -6.80332,
+                          24.7496 -3.5296 2.97308e-14,
+                          22.7497 -10.3659 3.15206e-14,
+                          23.17 -6.47048 -6.80332,
+                          22.6632 3.3736 -10,
+                          23.17 6.47048 -6.80332,
+                          23.9873 3.98589e-15 -7.04331,
+                          24.7404 3.5932 2.68195e-14,
+                          23.9873 3.98589e-15 -7.04331,
+                          23.17 6.47048 -6.80332,
+                          22.6631 -3.37428 -10,
+                          22.6632 3.3736 -10,
+                          23.9873 3.98589e-15 -7.04331,
+                          24.7404 3.5932 2.68195e-14,
+                          24.7496 -3.5296 2.97308e-14,
+                          23.9873 3.98589e-15 -7.04331,
+                          20.6937 9.83719 -10,
+                          20.7736 12.5 -6.09969,
+                          23.17 6.47048 -6.80332,
+                          22.723 10.4243 2.30232e-14,
+                          23.17 6.47048 -6.80332,
+                          20.7736 12.5 -6.09969,
+                          22.6632 3.3736 -10,
+                          20.6937 9.83719 -10,
+                          23.17 6.47048 -6.80332,
+                          22.723 10.4243 2.30232e-14,
+                          24.7404 3.5932 2.68195e-14,
+                          23.17 6.47048 -6.80332,
+                          15.6703 16.7149 -10,
+                          16.9616 17.6777 -4.98037,
+                          20.7736 12.5 -6.09969,
+                          18.861 16.4093 1.86499e-14,
+                          20.7736 12.5 -6.09969,
+                          16.9616 17.6777 -4.98037,
+                          17.2582 15.0717 -10,
+                          15.6703 16.7149 -10,
+                          20.7736 12.5 -6.09969,
+                          20.6937 9.83719 -10,
+                          17.2582 15.0717 -10,
+                          20.7736 12.5 -6.09969,
+                          18.861 16.4093 1.86499e-14,
+                          22.723 10.4243 2.30232e-14,
+                          20.7736 12.5 -6.09969,
+                          11.2348 21.1325 -7.22469,
+                          11.9937 21.6506 -3.52166,
+                          16.9616 17.6777 -4.98037,
+                          13.4679 21.0622 1.40547e-14,
+                          16.9616 17.6777 -4.98037,
+                          11.9937 21.6506 -3.52166,
+                          15.6703 16.7149 -10,
+                          11.2348 21.1325 -7.22469,
+                          16.9616 17.6777 -4.98037,
+                          13.4679 21.0622 1.40547e-14,
+                          18.861 16.4093 1.86499e-14,
+                          16.9616 17.6777 -4.98037,
+                          5.84812 24.0137 -3.76072,
+                          6.20838 24.1481 -1.82294,
+                          11.9937 21.6506 -3.52166,
+                          6.98163 24.0054 9.61052e-15,
+                          11.9937 21.6506 -3.52166,
+                          6.20838 24.1481 -1.82294,
+                          11.2348 21.1325 -7.22469,
+                          5.84812 24.0137 -3.76072,
+                          11.9937 21.6506 -3.52166,
+                          6.98163 24.0054 9.61052e-15,
+                          13.4679 21.0622 1.40547e-14,
+                          11.9937 21.6506 -3.52166,
+                          8.68001 21.2057 -10,
+                          5.84812 24.0137 -3.76072,
+                          11.2348 21.1325 -7.22469,
+                          8.68001 21.2057 -10,
+                          4.53844 24.0189 -5.24369,
+                          5.84812 24.0137 -3.76072,
+                          13.6892 18.374 -10,
+                          11.2348 21.1325 -7.22469,
+                          15.6703 16.7149 -10,
+                          10.4852 20.373 -10,
+                          8.68001 21.2057 -10,
+                          11.2348 21.1325 -7.22469,
+                          13.6892 18.374 -10,
+                          10.4852 20.373 -10,
+                          11.2348 21.1325 -7.22469,
+                          13.0613 -21.0275 3.49976,
+                          7.04331 -23.9873 2.92262e-14,
+                          13.522 -21.0275 3.12576e-14,
+                          13.0613 -21.0275 3.49976,
+                          6.80332 -23.9873 1.82294,
+                          7.04331 -23.9873 2.92262e-14,
+                          18.259 -16.3607 4.89248,
+                          13.522 -21.0275 3.12576e-14,
+                          18.9031 -16.3607 3.20437e-14,
+                          18.259 -16.3607 4.89248,
+                          13.0613 -21.0275 3.49976,
+                          13.522 -21.0275 3.12576e-14,
+                          22.0274 -10.3659 5.68713,
+                          18.9031 -16.3607 3.20437e-14,
+                          22.7497 -10.3659 3.15206e-14,
+                          22.0274 -10.3659 5.68713,
+                          18.259 -16.3607 4.89248,
+                          18.9031 -16.3607 3.20437e-14,
+                          24.1327 -3.5296 5.49133,
+                          22.7497 -10.3659 3.15206e-14,
+                          24.7496 -3.5296 2.97308e-14,
+                          24.1327 -3.5296 5.49133,
+                          22.0274 -10.3659 5.68713,
+                          22.7497 -10.3659 3.15206e-14,
+                          24.1233 3.5932 5.49134,
+                          24.7496 -3.5296 2.97308e-14,
+                          24.7404 3.5932 2.68195e-14,
+                          24.1233 3.5932 5.49134,
+                          24.1327 -3.5296 5.49133,
+                          24.7496 -3.5296 2.97308e-14,
+                          21.9981 10.4243 5.69362,
+                          24.7404 3.5932 2.68195e-14,
+                          22.723 10.4243 2.30232e-14,
+                          21.9981 10.4243 5.69362,
+                          24.1233 3.5932 5.49134,
+                          24.7404 3.5932 2.68195e-14,
+                          18.2183 16.4093 4.88158,
+                          22.723 10.4243 2.30232e-14,
+                          18.861 16.4093 1.86499e-14,
+                          18.2183 16.4093 4.88158,
+                          21.9981 10.4243 5.69362,
+                          22.723 10.4243 2.30232e-14,
+                          13.009 21.0622 3.48576,
+                          18.861 16.4093 1.86499e-14,
+                          13.4679 21.0622 1.40547e-14,
+                          13.009 21.0622 3.48576,
+                          18.2183 16.4093 4.88158,
+                          18.861 16.4093 1.86499e-14,
+                          6.74374 24.0054 1.80698,
+                          13.4679 21.0622 1.40547e-14,
+                          6.98163 24.0054 9.61052e-15,
+                          13.009 21.0622 3.48576,
+                          13.4679 21.0622 1.40547e-14,
+                          6.74374 24.0054 1.80698,
+                          7.76781 21.556 -10,
+                          4.53844 24.0189 -5.24369,
+                          8.68001 21.2057 -10,
+                          4.5675 22.4531 -10,
+                          2.34934 24.3495 -5.15602,
+                          4.53844 24.0189 -5.24369,
+                          5.55866 22.2284 -10,
+                          4.5675 22.4531 -10,
+                          4.53844 24.0189 -5.24369,
+                          7.76781 21.556 -10,
+                          5.55866 22.2284 -10,
+                          4.53844 24.0189 -5.24369,
+                          3.68933 22.6139 -10,
+                          2.34934 24.3495 -5.15602,
+                          4.5675 22.4531 -10,
+                          1.43179 22.8681 -10,
+                          0.731065 24.4579 -5.12624,
+                          2.34934 24.3495 -5.15602,
+                          1.85253 22.8379 -10,
+                          1.43179 22.8681 -10,
+                          2.34934 24.3495 -5.15602,
+                          3.68933 22.6139 -10,
+                          1.85253 22.8379 -10,
+                          2.34934 24.3495 -5.15602,
+                          -0.744422 24.4576 -5.1256,
+                          0.731065 24.4579 -5.12624,
+                          1.43179 22.8681 -10,
+                          -1.55544e-14 22.9129 -10,
+                          -0.744422 24.4576 -5.1256,
+                          1.43179 22.8681 -10,
+                          -1.55544e-14 22.9129 -10,
+                          -1.45787 22.8664 -10,
+                          -0.744422 24.4576 -5.1256,
+                          -2.36554 24.3478 -5.15641,
+                          -0.744422 24.4576 -5.1256,
+                          -1.45787 22.8664 -10,
+                          -1.85243 22.8379 -10,
+                          -2.36554 24.3478 -5.15641,
+                          -1.45787 22.8664 -10,
+                          -3.68914 22.6139 -10,
+                          -4.59866 22.4467 -10,
+                          -2.36554 24.3478 -5.15641,
+                          -4.56378 24.0136 -5.24565,
+                          -2.36554 24.3478 -5.15641,
+                          -4.59866 22.4467 -10,
+                          -1.85243 22.8379 -10,
+                          -3.68914 22.6139 -10,
+                          -2.36554 24.3478 -5.15641,
+                          -5.55845 22.2284 -10,
+                          -4.56378 24.0136 -5.24565,
+                          -4.59866 22.4467 -10,
+                          -7.76756 21.5561 -10,
+                          -8.7259 21.1869 -10,
+                          -4.56378 24.0136 -5.24565,
+                          -5.55845 22.2284 -10,
+                          -7.76756 21.5561 -10,
+                          -4.56378 24.0136 -5.24565,
+                          12.5388 -20.1864 3.35977,
+                          6.53119 -23.0278 1.75003,
+                          5.8557 -23.0278 3.38079,
+                          11.242 -20.1864 6.49057,
+                          5.8557 -23.0278 3.38079,
+                          4.78116 -23.0278 4.78116,
+                          12.5388 -20.1864 3.35977,
+                          5.8557 -23.0278 3.38079,
+                          11.242 -20.1864 6.49057,
+                          9.17906 -20.1864 9.17906,
+                          4.78116 -23.0278 4.78116,
+                          3.38079 -23.0278 5.8557,
+                          11.242 -20.1864 6.49057,
+                          4.78116 -23.0278 4.78116,
+                          9.17906 -20.1864 9.17906,
+                          6.49057 -20.1864 11.242,
+                          3.38079 -23.0278 5.8557,
+                          1.75003 -23.0278 6.53119,
+                          9.17906 -20.1864 9.17906,
+                          3.38079 -23.0278 5.8557,
+                          6.49057 -20.1864 11.242,
+                          3.35977 -20.1864 12.5388,
+                          1.75003 -23.0278 6.53119,
+                          -1.0483e-15 -23.0278 6.76158,
+                          6.49057 -20.1864 11.242,
+                          1.75003 -23.0278 6.53119,
+                          3.35977 -20.1864 12.5388,
+                          -3.51328e-15 -20.1864 12.9811,
+                          -1.0483e-15 -23.0278 6.76158,
+                          -1.75003 -23.0278 6.53119,
+                          3.35977 -20.1864 12.5388,
+                          -1.0483e-15 -23.0278 6.76158,
+                          -3.51328e-15 -20.1864 12.9811,
+                          -3.35977 -20.1864 12.5388,
+                          -1.75003 -23.0278 6.53119,
+                          -3.38079 -23.0278 5.8557,
+                          -3.51328e-15 -20.1864 12.9811,
+                          -1.75003 -23.0278 6.53119,
+                          -3.35977 -20.1864 12.5388,
+                          -6.49057 -20.1864 11.242,
+                          -3.38079 -23.0278 5.8557,
+                          -4.78116 -23.0278 4.78116,
+                          -3.35977 -20.1864 12.5388,
+                          -3.38079 -23.0278 5.8557,
+                          -6.49057 -20.1864 11.242,
+                          -9.17906 -20.1864 9.17906,
+                          -4.78116 -23.0278 4.78116,
+                          -5.8557 -23.0278 3.38079,
+                          -6.49057 -20.1864 11.242,
+                          -4.78116 -23.0278 4.78116,
+                          -9.17906 -20.1864 9.17906,
+                          -11.242 -20.1864 6.49057,
+                          -5.8557 -23.0278 3.38079,
+                          -6.53119 -23.0278 1.75003,
+                          -9.17906 -20.1864 9.17906,
+                          -5.8557 -23.0278 3.38079,
+                          -11.242 -20.1864 6.49057,
+                          -11.242 -20.1864 6.49057,
+                          -6.53119 -23.0278 1.75003,
+                          -12.5388 -20.1864 3.35977,
+                          -12.4887 20.2197 3.34633,
+                          -6.47399 23.0451 1.7347,
+                          -5.80442 23.0451 3.35118,
+                          -11.197 20.2197 6.46461,
+                          -5.80442 23.0451 3.35118,
+                          -4.73929 23.0451 4.73929,
+                          -11.197 20.2197 6.46461,
+                          -12.4887 20.2197 3.34633,
+                          -5.80442 23.0451 3.35118,
+                          -9.14234 20.2197 9.14234,
+                          -4.73929 23.0451 4.73929,
+                          -3.35118 23.0451 5.80442,
+                          -9.14234 20.2197 9.14234,
+                          -11.197 20.2197 6.46461,
+                          -4.73929 23.0451 4.73929,
+                          -6.46461 20.2197 11.197,
+                          -3.35118 23.0451 5.80442,
+                          -1.7347 23.0451 6.47399,
+                          -6.46461 20.2197 11.197,
+                          -9.14234 20.2197 9.14234,
+                          -3.35118 23.0451 5.80442,
+                          -3.34633 20.2197 12.4887,
+                          -1.7347 23.0451 6.47399,
+                          -1.91487e-14 23.0451 6.70237,
+                          -3.34633 20.2197 12.4887,
+                          -6.46461 20.2197 11.197,
+                          -1.7347 23.0451 6.47399,
+                          -1.93874e-14 20.2197 12.9292,
+                          -1.91487e-14 23.0451 6.70237,
+                          1.7347 23.0451 6.47399,
+                          -1.93874e-14 20.2197 12.9292,
+                          -3.34633 20.2197 12.4887,
+                          -1.91487e-14 23.0451 6.70237,
+                          3.34633 20.2197 12.4887,
+                          1.7347 23.0451 6.47399,
+                          3.35118 23.0451 5.80442,
+                          3.34633 20.2197 12.4887,
+                          -1.93874e-14 20.2197 12.9292,
+                          1.7347 23.0451 6.47399,
+                          6.46461 20.2197 11.197,
+                          3.35118 23.0451 5.80442,
+                          4.73929 23.0451 4.73929,
+                          6.46461 20.2197 11.197,
+                          3.34633 20.2197 12.4887,
+                          3.35118 23.0451 5.80442,
+                          9.14234 20.2197 9.14234,
+                          4.73929 23.0451 4.73929,
+                          5.80442 23.0451 3.35118,
+                          9.14234 20.2197 9.14234,
+                          6.46461 20.2197 11.197,
+                          4.73929 23.0451 4.73929,
+                          11.197 20.2197 6.46461,
+                          5.80442 23.0451 3.35118,
+                          6.47399 23.0451 1.7347,
+                          11.197 20.2197 6.46461,
+                          9.14234 20.2197 9.14234,
+                          5.80442 23.0451 3.35118,
+                          12.4887 20.2197 3.34633,
+                          11.197 20.2197 6.46461,
+                          6.47399 23.0451 1.7347,
+                          -15.9387 15.7529 8.59099,
+                          -12.4887 20.2197 3.34633,
+                          -11.197 20.2197 6.46461,
+                          -15.9387 15.7529 8.59099,
+                          -17.5562 15.7529 4.43014,
+                          -12.4887 20.2197 3.34633,
+                          -13.3523 15.7529 12.2296,
+                          -11.197 20.2197 6.46461,
+                          -9.14234 20.2197 9.14234,
+                          -13.3523 15.7529 12.2296,
+                          -15.9387 15.7529 8.59099,
+                          -11.197 20.2197 6.46461,
+                          -9.95422 15.7529 15.1248,
+                          -9.14234 20.2197 9.14234,
+                          -6.46461 20.2197 11.197,
+                          -9.95422 15.7529 15.1248,
+                          -13.3523 15.7529 12.2296,
+                          -9.14234 20.2197 9.14234,
+                          -5.95107 15.7529 17.1006,
+                          -6.46461 20.2197 11.197,
+                          -3.34633 20.2197 12.4887,
+                          -5.95107 15.7529 17.1006,
+                          -9.95422 15.7529 15.1248,
+                          -6.46461 20.2197 11.197,
+                          -1.62787 15.917 17.8885,
+                          -3.34633 20.2197 12.4887,
+                          -1.93874e-14 20.2197 12.9292,
+                          -1.62787 15.917 17.8885,
+                          -5.95107 15.7529 17.1006,
+                          -3.34633 20.2197 12.4887,
+                          1.59569 15.9202 17.8885,
+                          -1.93874e-14 20.2197 12.9292,
+                          3.34633 20.2197 12.4887,
+                          -0.0440526 15.9999 17.8885,
+                          -1.62787 15.917 17.8885,
+                          -1.93874e-14 20.2197 12.9292,
+                          1.59569 15.9202 17.8885,
+                          -0.0440526 15.9999 17.8885,
+                          -1.93874e-14 20.2197 12.9292,
+                          5.92618 15.7529 17.1093,
+                          3.34633 20.2197 12.4887,
+                          6.46461 20.2197 11.197,
+                          5.92618 15.7529 17.1093,
+                          1.59569 15.9202 17.8885,
+                          3.34633 20.2197 12.4887,
+                          9.93661 15.7529 15.1364,
+                          6.46461 20.2197 11.197,
+                          9.14234 20.2197 9.14234,
+                          9.93661 15.7529 15.1364,
+                          5.92618 15.7529 17.1093,
+                          6.46461 20.2197 11.197,
+                          13.3416 15.7529 12.2413,
+                          9.14234 20.2197 9.14234,
+                          11.197 20.2197 6.46461,
+                          13.3416 15.7529 12.2413,
+                          9.93661 15.7529 15.1364,
+                          9.14234 20.2197 9.14234,
+                          15.9337 15.7529 8.60026,
+                          11.197 20.2197 6.46461,
+                          12.4887 20.2197 3.34633,
+                          15.9337 15.7529 8.60026,
+                          13.3416 15.7529 12.2413,
+                          11.197 20.2197 6.46461,
+                          17.5549 15.7529 4.43525,
+                          15.9337 15.7529 8.60026,
+                          12.4887 20.2197 3.34633,
+                          -19.3025 10.0074 10.162,
+                          -17.5562 15.7529 4.43014,
+                          -15.9387 15.7529 8.59099,
+                          -19.3025 10.0074 10.162,
+                          -21.1769 10.0074 5.23389,
+                          -17.5562 15.7529 4.43014,
+                          -16.3005 10.0074 14.4965,
+                          -15.9387 15.7529 8.59099,
+                          -13.3523 15.7529 12.2296,
+                          -16.3005 10.0074 14.4965,
+                          -19.3025 10.0074 10.162,
+                          -15.9387 15.7529 8.59099,
+                          -12.4532 10.0457 17.8885,
+                          -13.3523 15.7529 12.2296,
+                          -9.95422 15.7529 15.1248,
+                          -12.4532 10.0457 17.8885,
+                          -16.3005 10.0074 14.4965,
+                          -13.3523 15.7529 12.2296,
+                          -9.5832 12.8126 17.8885,
+                          -9.95422 15.7529 15.1248,
+                          -5.95107 15.7529 17.1006,
+                          -9.5832 12.8126 17.8885,
+                          -12.4532 10.0457 17.8885,
+                          -9.95422 15.7529 15.1248,
+                          -4.94955 15.2152 17.8885,
+                          -5.95107 15.7529 17.1006,
+                          -1.62787 15.917 17.8885,
+                          -4.94955 15.2152 17.8885,
+                          -9.5832 12.8126 17.8885,
+                          -5.95107 15.7529 17.1006,
+                          -4.94427 15.2169 18.2094,
+                          -1.62787 15.917 17.8885,
+                          -0.0440526 15.9999 17.8885,
+                          -4.94427 15.2169 18.2094,
+                          -4.94955 15.2152 17.8885,
+                          -1.62787 15.917 17.8885,
+                          1.66857e-12 16 18.2094,
+                          -0.0440526 15.9999 17.8885,
+                          1.59569 15.9202 17.8885,
+                          1.66857e-12 16 18.2094,
+                          -4.94427 15.2169 18.2094,
+                          -0.0440526 15.9999 17.8885,
+                          4.86538 15.2423 17.8885,
+                          1.59569 15.9202 17.8885,
+                          5.92618 15.7529 17.1093,
+                          1.66857e-12 16 18.2094,
+                          1.59569 15.9202 17.8885,
+                          4.86538 15.2423 17.8885,
+                          9.50373 12.8716 17.8885,
+                          5.92618 15.7529 17.1093,
+                          9.93661 15.7529 15.1364,
+                          9.50373 12.8716 17.8885,
+                          4.86538 15.2423 17.8885,
+                          5.92618 15.7529 17.1093,
+                          12.4528 10.0463 17.8885,
+                          9.93661 15.7529 15.1364,
+                          13.3416 15.7529 12.2413,
+                          12.4528 10.0463 17.8885,
+                          9.50373 12.8716 17.8885,
+                          9.93661 15.7529 15.1364,
+                          16.3045 10.0074 14.492,
+                          13.3416 15.7529 12.2413,
+                          15.9337 15.7529 8.60026,
+                          16.3045 10.0074 14.492,
+                          12.4528 10.0463 17.8885,
+                          13.3416 15.7529 12.2413,
+                          19.3044 10.0074 10.1585,
+                          15.9337 15.7529 8.60026,
+                          17.5549 15.7529 4.43525,
+                          19.3044 10.0074 10.1585,
+                          16.3045 10.0074 14.492,
+                          15.9337 15.7529 8.60026,
+                          21.1773 10.0074 5.23195,
+                          19.3044 10.0074 10.1585,
+                          17.5549 15.7529 4.43525,
+                          4.94427 15.2169 18.2094,
+                          4.86538 15.2423 17.8885,
+                          9.50373 12.8716 17.8885,
+                          4.94427 15.2169 18.2094,
+                          1.66857e-12 16 18.2094,
+                          4.86538 15.2423 17.8885,
+                          9.40456 12.9443 18.2094,
+                          9.50373 12.8716 17.8885,
+                          12.4528 10.0463 17.8885,
+                          9.40456 12.9443 18.2094,
+                          4.94427 15.2169 18.2094,
+                          9.50373 12.8716 17.8885,
+                          13.0342 9.2795 17.8885,
+                          12.4528 10.0463 17.8885,
+                          16.3045 10.0074 14.492,
+                          12.9443 9.40456 18.2094,
+                          12.4528 10.0463 17.8885,
+                          13.0342 9.2795 17.8885,
+                          12.9443 9.40456 18.2094,
+                          9.40456 12.9443 18.2094,
+                          12.4528 10.0463 17.8885,
+                          19.0017 3.44948 14.2491,
+                          16.3045 10.0074 14.492,
+                          19.3044 10.0074 10.1585,
+                          15.2549 4.82561 17.8885,
+                          13.0342 9.2795 17.8885,
+                          16.3045 10.0074 14.492,
+                          15.626 3.43912 17.8885,
+                          15.2549 4.82561 17.8885,
+                          16.3045 10.0074 14.492,
+                          19.0017 3.44948 14.2491,
+                          15.626 3.43912 17.8885,
+                          16.3045 10.0074 14.492,
+                          21.599 3.44948 9.87838,
+                          19.3044 10.0074 10.1585,
+                          21.1773 10.0074 5.23195,
+                          21.599 3.44948 9.87838,
+                          19.0017 3.44948 14.2491,
+                          19.3044 10.0074 10.1585,
+                          23.2066 3.44948 5.05501,
+                          21.599 3.44948 9.87838,
+                          21.1773 10.0074 5.23195,
+                          15.2169 4.94427 18.2094,
+                          13.0342 9.2795 17.8885,
+                          15.2549 4.82561 17.8885,
+                          15.2169 4.94427 18.2094,
+                          12.9443 9.40456 18.2094,
+                          13.0342 9.2795 17.8885,
+                          15.2169 4.94427 18.2094,
+                          15.2549 4.82561 17.8885,
+                          15.626 3.43912 17.8885,
+                          16 1.51836e-14 17.8885,
+                          15.626 3.43912 17.8885,
+                          19.0017 3.44948 14.2491,
+                          15.2169 4.94427 18.2094,
+                          15.626 3.43912 17.8885,
+                          16 1.51836e-14 17.8885,
+                          21.5917 -3.38842 9.9155,
+                          19.0017 3.44948 14.2491,
+                          21.599 3.44948 9.87838,
+                          18.9756 -3.38842 14.2985,
+                          16 1.51836e-14 17.8885,
+                          19.0017 3.44948 14.2491,
+                          21.5917 -3.38842 9.9155,
+                          18.9756 -3.38842 14.2985,
+                          19.0017 3.44948 14.2491,
+                          23.2113 -3.38842 5.07486,
+                          21.599 3.44948 9.87838,
+                          23.2066 3.44948 5.05501,
+                          23.2113 -3.38842 5.07486,
+                          21.5917 -3.38842 9.9155,
+                          21.599 3.44948 9.87838,
+                          18.9756 -3.38842 14.2985,
+                          15.6273 -3.43351 17.8885,
+                          16 1.51836e-14 17.8885,
+                          16 1.53145e-14 18.2094,
+                          16 1.51836e-14 17.8885,
+                          15.6273 -3.43351 17.8885,
+                          15.2169 4.94427 18.2094,
+                          16 1.51836e-14 17.8885,
+                          16 1.53145e-14 18.2094,
+                          16.4042 -9.95125 14.4179,
+                          15.6273 -3.43351 17.8885,
+                          18.9756 -3.38842 14.2985,
+                          16.4042 -9.95125 14.4179,
+                          14.9419 -5.72193 17.8885,
+                          15.6273 -3.43351 17.8885,
+                          15.2169 -4.94427 18.2094,
+                          15.6273 -3.43351 17.8885,
+                          14.9419 -5.72193 17.8885,
+                          15.2169 -4.94427 18.2094,
+                          16 1.53145e-14 18.2094,
+                          15.6273 -3.43351 17.8885,
+                          19.3647 -9.95125 10.0986,
+                          18.9756 -3.38842 14.2985,
+                          21.5917 -3.38842 9.9155,
+                          19.3647 -9.95125 10.0986,
+                          16.4042 -9.95125 14.4179,
+                          18.9756 -3.38842 14.2985,
+                          21.2119 -9.95125 5.19874,
+                          21.5917 -3.38842 9.9155,
+                          23.2113 -3.38842 5.07486,
+                          21.2119 -9.95125 5.19874,
+                          19.3647 -9.95125 10.0986,
+                          21.5917 -3.38842 9.9155,
+                          16.4042 -9.95125 14.4179,
+                          12.5052 -9.98094 17.8885,
+                          14.9419 -5.72193 17.8885,
+                          12.9443 -9.40456 18.2094,
+                          14.9419 -5.72193 17.8885,
+                          12.5052 -9.98094 17.8885,
+                          12.9443 -9.40456 18.2094,
+                          15.2169 -4.94427 18.2094,
+                          14.9419 -5.72193 17.8885,
+                          13.5114 -15.7063 12.1142,
+                          12.5052 -9.98094 17.8885,
+                          16.4042 -9.95125 14.4179,
+                          10.19 -15.7063 15.0159,
+                          12.3835 -10.1315 17.8885,
+                          12.5052 -9.98094 17.8885,
+                          12.9443 -9.40456 18.2094,
+                          12.5052 -9.98094 17.8885,
+                          12.3835 -10.1315 17.8885,
+                          13.5114 -15.7063 12.1142,
+                          10.19 -15.7063 15.0159,
+                          12.5052 -9.98094 17.8885,
+                          16.0348 -15.7063 8.49692,
+                          16.4042 -9.95125 14.4179,
+                          19.3647 -9.95125 10.0986,
+                          16.0348 -15.7063 8.49692,
+                          13.5114 -15.7063 12.1142,
+                          16.4042 -9.95125 14.4179,
+                          17.611 -15.7063 4.37775,
+                          19.3647 -9.95125 10.0986,
+                          21.2119 -9.95125 5.19874,
+                          17.611 -15.7063 4.37775,
+                          16.0348 -15.7063 8.49692,
+                          19.3647 -9.95125 10.0986,
+                          10.19 -15.7063 15.0159,
+                          8.88587 -13.3057 17.8885,
+                          12.3835 -10.1315 17.8885,
+                          9.40456 -12.9443 18.2094,
+                          12.3835 -10.1315 17.8885,
+                          8.88587 -13.3057 17.8885,
+                          9.40456 -12.9443 18.2094,
+                          12.9443 -9.40456 18.2094,
+                          12.3835 -10.1315 17.8885,
+                          6.26661 -15.7063 17.0306,
+                          4.66691 -15.3042 17.8885,
+                          8.88587 -13.3057 17.8885,
+                          4.94427 -15.2169 18.2094,
+                          8.88587 -13.3057 17.8885,
+                          4.66691 -15.3042 17.8885,
+                          10.19 -15.7063 15.0159,
+                          6.26661 -15.7063 17.0306,
+                          8.88587 -13.3057 17.8885,
+                          4.94427 -15.2169 18.2094,
+                          9.40456 -12.9443 18.2094,
+                          8.88587 -13.3057 17.8885,
+                          6.26661 -15.7063 17.0306,
+                          2.0524 -15.8678 17.8885,
+                          4.66691 -15.3042 17.8885,
+                          4.94427 -15.2169 18.2094,
+                          4.66691 -15.3042 17.8885,
+                          2.0524 -15.8678 17.8885,
+                          3.35977 -20.1864 12.5388,
+                          2.0524 -15.8678 17.8885,
+                          6.26661 -15.7063 17.0306,
+                          -3.51328e-15 -20.1864 12.9811,
+                          -0.00178409 -16 17.8885,
+                          2.0524 -15.8678 17.8885,
+                          1.68186e-12 -16 18.2094,
+                          2.0524 -15.8678 17.8885,
+                          -0.00178409 -16 17.8885,
+                          3.35977 -20.1864 12.5388,
+                          -3.51328e-15 -20.1864 12.9811,
+                          2.0524 -15.8678 17.8885,
+                          1.68186e-12 -16 18.2094,
+                          4.94427 -15.2169 18.2094,
+                          2.0524 -15.8678 17.8885,
+                          6.49057 -20.1864 11.242,
+                          6.26661 -15.7063 17.0306,
+                          10.19 -15.7063 15.0159,
+                          6.49057 -20.1864 11.242,
+                          3.35977 -20.1864 12.5388,
+                          6.26661 -15.7063 17.0306,
+                          9.17906 -20.1864 9.17906,
+                          10.19 -15.7063 15.0159,
+                          13.5114 -15.7063 12.1142,
+                          9.17906 -20.1864 9.17906,
+                          6.49057 -20.1864 11.242,
+                          10.19 -15.7063 15.0159,
+                          11.242 -20.1864 6.49057,
+                          13.5114 -15.7063 12.1142,
+                          16.0348 -15.7063 8.49692,
+                          11.242 -20.1864 6.49057,
+                          9.17906 -20.1864 9.17906,
+                          13.5114 -15.7063 12.1142,
+                          12.5388 -20.1864 3.35977,
+                          16.0348 -15.7063 8.49692,
+                          17.611 -15.7063 4.37775,
+                          12.5388 -20.1864 3.35977,
+                          11.242 -20.1864 6.49057,
+                          16.0348 -15.7063 8.49692,
+                          -3.35977 -20.1864 12.5388,
+                          -2.05023 -15.8681 17.8885,
+                          -0.00178409 -16 17.8885,
+                          1.68186e-12 -16 18.2094,
+                          -0.00178409 -16 17.8885,
+                          -2.05023 -15.8681 17.8885,
+                          -3.51328e-15 -20.1864 12.9811,
+                          -3.35977 -20.1864 12.5388,
+                          -0.00178409 -16 17.8885,
+                          -3.35977 -20.1864 12.5388,
+                          -6.26514 -15.7063 17.0312,
+                          -2.05023 -15.8681 17.8885,
+                          -4.67559 -15.3016 17.8885,
+                          -2.05023 -15.8681 17.8885,
+                          -6.26514 -15.7063 17.0312,
+                          1.68186e-12 -16 18.2094,
+                          -2.05023 -15.8681 17.8885,
+                          -4.67559 -15.3016 17.8885,
+                          -6.49057 -20.1864 11.242,
+                          -10.1889 -15.7063 15.0166,
+                          -6.26514 -15.7063 17.0312,
+                          -8.89141 -13.302 17.8885,
+                          -6.26514 -15.7063 17.0312,
+                          -10.1889 -15.7063 15.0166,
+                          -3.35977 -20.1864 12.5388,
+                          -6.49057 -20.1864 11.242,
+                          -6.26514 -15.7063 17.0312,
+                          -8.89141 -13.302 17.8885,
+                          -4.67559 -15.3016 17.8885,
+                          -6.26514 -15.7063 17.0312,
+                          -9.17906 -20.1864 9.17906,
+                          -13.5108 -15.7063 12.1149,
+                          -10.1889 -15.7063 15.0166,
+                          -12.386 -10.1285 17.8885,
+                          -10.1889 -15.7063 15.0166,
+                          -13.5108 -15.7063 12.1149,
+                          -6.49057 -20.1864 11.242,
+                          -9.17906 -20.1864 9.17906,
+                          -10.1889 -15.7063 15.0166,
+                          -12.386 -10.1285 17.8885,
+                          -8.89141 -13.302 17.8885,
+                          -10.1889 -15.7063 15.0166,
+                          -11.242 -20.1864 6.49057,
+                          -16.0345 -15.7063 8.49747,
+                          -13.5108 -15.7063 12.1149,
+                          -16.4045 -9.95125 14.4175,
+                          -13.5108 -15.7063 12.1149,
+                          -16.0345 -15.7063 8.49747,
+                          -9.17906 -20.1864 9.17906,
+                          -11.242 -20.1864 6.49057,
+                          -13.5108 -15.7063 12.1149,
+                          -12.5055 -9.98059 17.8885,
+                          -13.5108 -15.7063 12.1149,
+                          -16.4045 -9.95125 14.4175,
+                          -12.386 -10.1285 17.8885,
+                          -13.5108 -15.7063 12.1149,
+                          -12.5055 -9.98059 17.8885,
+                          -12.5388 -20.1864 3.35977,
+                          -17.6109 -15.7063 4.37805,
+                          -16.0345 -15.7063 8.49747,
+                          -19.3648 -9.95125 10.0983,
+                          -16.0345 -15.7063 8.49747,
+                          -17.6109 -15.7063 4.37805,
+                          -11.242 -20.1864 6.49057,
+                          -12.5388 -20.1864 3.35977,
+                          -16.0345 -15.7063 8.49747,
+                          -16.4045 -9.95125 14.4175,
+                          -16.0345 -15.7063 8.49747,
+                          -19.3648 -9.95125 10.0983,
+                          -19.3648 -9.95125 10.0983,
+                          -17.6109 -15.7063 4.37805,
+                          -21.212 -9.95125 5.19858,
+                          -21.5997 3.44948 9.87705,
+                          -21.1769 10.0074 5.23389,
+                          -19.3025 10.0074 10.162,
+                          -21.5997 3.44948 9.87705,
+                          -23.2068 3.44948 5.0543,
+                          -21.1769 10.0074 5.23389,
+                          -19.003 3.44948 14.2473,
+                          -19.3025 10.0074 10.162,
+                          -16.3005 10.0074 14.4965,
+                          -19.003 3.44948 14.2473,
+                          -21.5997 3.44948 9.87705,
+                          -19.3025 10.0074 10.162,
+                          -13.0783 9.21727 17.8885,
+                          -16.3005 10.0074 14.4965,
+                          -12.4532 10.0457 17.8885,
+                          -15.6256 3.44121 17.8885,
+                          -19.003 3.44948 14.2473,
+                          -16.3005 10.0074 14.4965,
+                          -15.2652 4.79306 17.8885,
+                          -15.6256 3.44121 17.8885,
+                          -16.3005 10.0074 14.4965,
+                          -13.0783 9.21727 17.8885,
+                          -15.2652 4.79306 17.8885,
+                          -16.3005 10.0074 14.4965,
+                          -12.9443 9.40456 18.2094,
+                          -12.4532 10.0457 17.8885,
+                          -9.5832 12.8126 17.8885,
+                          -12.9443 9.40456 18.2094,
+                          -13.0783 9.21727 17.8885,
+                          -12.4532 10.0457 17.8885,
+                          -9.40456 12.9443 18.2094,
+                          -9.5832 12.8126 17.8885,
+                          -4.94955 15.2152 17.8885,
+                          -9.40456 12.9443 18.2094,
+                          -12.9443 9.40456 18.2094,
+                          -9.5832 12.8126 17.8885,
+                          -4.94427 15.2169 18.2094,
+                          -9.40456 12.9443 18.2094,
+                          -4.94955 15.2152 17.8885,
+                          -23.2113 -3.38842 5.07487,
+                          -23.2068 3.44948 5.0543,
+                          -21.5997 3.44948 9.87705,
+                          -21.5917 -3.38842 9.91551,
+                          -21.5997 3.44948 9.87705,
+                          -19.003 3.44948 14.2473,
+                          -21.5917 -3.38842 9.91551,
+                          -23.2113 -3.38842 5.07487,
+                          -21.5997 3.44948 9.87705,
+                          -18.9755 -3.38842 14.2985,
+                          -19.003 3.44948 14.2473,
+                          -15.6256 3.44121 17.8885,
+                          -18.9755 -3.38842 14.2985,
+                          -21.5917 -3.38842 9.91551,
+                          -19.003 3.44948 14.2473,
+                          -16 3.10661e-14 18.2094,
+                          -15.6256 3.44121 17.8885,
+                          -15.2652 4.79306 17.8885,
+                          -16 6.52175e-15 17.8885,
+                          -18.9755 -3.38842 14.2985,
+                          -15.6256 3.44121 17.8885,
+                          -16 3.10661e-14 18.2094,
+                          -16 6.52175e-15 17.8885,
+                          -15.6256 3.44121 17.8885,
+                          -15.2169 4.94427 18.2094,
+                          -15.2652 4.79306 17.8885,
+                          -13.0783 9.21727 17.8885,
+                          -15.2169 4.94427 18.2094,
+                          -16 3.10661e-14 18.2094,
+                          -15.2652 4.79306 17.8885,
+                          -12.9443 9.40456 18.2094,
+                          -15.2169 4.94427 18.2094,
+                          -13.0783 9.21727 17.8885,
+                          -21.212 -9.95125 5.19858,
+                          -23.2113 -3.38842 5.07487,
+                          -21.5917 -3.38842 9.91551,
+                          -19.3648 -9.95125 10.0983,
+                          -21.5917 -3.38842 9.91551,
+                          -18.9755 -3.38842 14.2985,
+                          -19.3648 -9.95125 10.0983,
+                          -21.212 -9.95125 5.19858,
+                          -21.5917 -3.38842 9.91551,
+                          -16 6.52175e-15 17.8885,
+                          -15.627 -3.43467 17.8885,
+                          -18.9755 -3.38842 14.2985,
+                          -16.4045 -9.95125 14.4175,
+                          -18.9755 -3.38842 14.2985,
+                          -15.627 -3.43467 17.8885,
+                          -16.4045 -9.95125 14.4175,
+                          -19.3648 -9.95125 10.0983,
+                          -18.9755 -3.38842 14.2985,
+                          -15.2169 -4.94427 18.2094,
+                          -15.627 -3.43467 17.8885,
+                          -16 6.52175e-15 17.8885,
+                          -14.9418 -5.72224 17.8885,
+                          -16.4045 -9.95125 14.4175,
+                          -15.627 -3.43467 17.8885,
+                          -15.2169 -4.94427 18.2094,
+                          -14.9418 -5.72224 17.8885,
+                          -15.627 -3.43467 17.8885,
+                          -15.2169 -4.94427 18.2094,
+                          -16 6.52175e-15 17.8885,
+                          -16 3.10661e-14 18.2094,
+                          -14.9418 -5.72224 17.8885,
+                          -12.5055 -9.98059 17.8885,
+                          -16.4045 -9.95125 14.4175,
+                          -12.9443 -9.40456 18.2094,
+                          -12.5055 -9.98059 17.8885,
+                          -14.9418 -5.72224 17.8885,
+                          -9.40456 -12.9443 18.2094,
+                          -12.386 -10.1285 17.8885,
+                          -12.5055 -9.98059 17.8885,
+                          -12.9443 -9.40456 18.2094,
+                          -9.40456 -12.9443 18.2094,
+                          -12.5055 -9.98059 17.8885,
+                          -15.2169 -4.94427 18.2094,
+                          -12.9443 -9.40456 18.2094,
+                          -14.9418 -5.72224 17.8885,
+                          -4.94427 -15.2169 18.2094,
+                          -4.67559 -15.3016 17.8885,
+                          -8.89141 -13.302 17.8885,
+                          -4.94427 -15.2169 18.2094,
+                          1.68186e-12 -16 18.2094,
+                          -4.67559 -15.3016 17.8885,
+                          -9.40456 -12.9443 18.2094,
+                          -8.89141 -13.302 17.8885,
+                          -12.386 -10.1285 17.8885,
+                          -9.40456 -12.9443 18.2094,
+                          -4.94427 -15.2169 18.2094,
+                          -8.89141 -13.302 17.8885,
+                          13.009 21.0622 3.48576,
+                          6.74374 24.0054 1.80698,
+                          6.04627 24.0054 3.49082,
+                          11.6636 21.0622 6.73397,
+                          6.04627 24.0054 3.49082,
+                          4.93676 24.0054 4.93676,
+                          13.009 21.0622 3.48576,
+                          6.04627 24.0054 3.49082,
+                          11.6636 21.0622 6.73397,
+                          9.52327 21.0622 9.52327,
+                          4.93676 24.0054 4.93676,
+                          3.49082 24.0054 6.04627,
+                          11.6636 21.0622 6.73397,
+                          4.93676 24.0054 4.93676,
+                          9.52327 21.0622 9.52327,
+                          6.73397 21.0622 11.6636,
+                          3.49082 24.0054 6.04627,
+                          1.80698 24.0054 6.74374,
+                          9.52327 21.0622 9.52327,
+                          3.49082 24.0054 6.04627,
+                          6.73397 21.0622 11.6636,
+                          3.48576 21.0622 13.009,
+                          1.80698 24.0054 6.74374,
+                          -1.95868e-14 24.0054 6.98163,
+                          6.73397 21.0622 11.6636,
+                          1.80698 24.0054 6.74374,
+                          3.48576 21.0622 13.009,
+                          -1.98353e-14 21.0622 13.4679,
+                          -1.95868e-14 24.0054 6.98163,
+                          -1.80698 24.0054 6.74374,
+                          3.48576 21.0622 13.009,
+                          -1.95868e-14 24.0054 6.98163,
+                          -1.98353e-14 21.0622 13.4679,
+                          -3.48576 21.0622 13.009,
+                          -1.80698 24.0054 6.74374,
+                          -3.49082 24.0054 6.04627,
+                          -1.98353e-14 21.0622 13.4679,
+                          -1.80698 24.0054 6.74374,
+                          -3.48576 21.0622 13.009,
+                          -6.73397 21.0622 11.6636,
+                          -3.49082 24.0054 6.04627,
+                          -4.93676 24.0054 4.93676,
+                          -3.48576 21.0622 13.009,
+                          -3.49082 24.0054 6.04627,
+                          -6.73397 21.0622 11.6636,
+                          -9.52327 21.0622 9.52327,
+                          -4.93676 24.0054 4.93676,
+                          -6.04627 24.0054 3.49082,
+                          -6.73397 21.0622 11.6636,
+                          -4.93676 24.0054 4.93676,
+                          -9.52327 21.0622 9.52327,
+                          -11.6636 21.0622 6.73397,
+                          -6.04627 24.0054 3.49082,
+                          -6.74374 24.0054 1.80698,
+                          -9.52327 21.0622 9.52327,
+                          -6.04627 24.0054 3.49082,
+                          -11.6636 21.0622 6.73397,
+                          -11.6636 21.0622 6.73397,
+                          -6.74374 24.0054 1.80698,
+                          -13.009 21.0622 3.48576,
+                          -13.0613 -21.0275 3.49976,
+                          -6.80332 -23.9873 1.82294,
+                          -6.09969 -23.9873 3.52166,
+                          -11.7104 -21.0275 6.76101,
+                          -6.09969 -23.9873 3.52166,
+                          -4.98037 -23.9873 4.98037,
+                          -11.7104 -21.0275 6.76101,
+                          -13.0613 -21.0275 3.49976,
+                          -6.09969 -23.9873 3.52166,
+                          -9.56152 -21.0275 9.56152,
+                          -4.98037 -23.9873 4.98037,
+                          -3.52166 -23.9873 6.09969,
+                          -9.56152 -21.0275 9.56152,
+                          -11.7104 -21.0275 6.76101,
+                          -4.98037 -23.9873 4.98037,
+                          -6.76101 -21.0275 11.7104,
+                          -3.52166 -23.9873 6.09969,
+                          -1.82294 -23.9873 6.80332,
+                          -6.76101 -21.0275 11.7104,
+                          -9.56152 -21.0275 9.56152,
+                          -3.52166 -23.9873 6.09969,
+                          -3.49976 -21.0275 13.0613,
+                          -1.82294 -23.9873 6.80332,
+                          -7.3214e-16 -23.9873 7.04331,
+                          -3.49976 -21.0275 13.0613,
+                          -6.76101 -21.0275 11.7104,
+                          -1.82294 -23.9873 6.80332,
+                          -3.29982e-15 -21.0275 13.522,
+                          -7.3214e-16 -23.9873 7.04331,
+                          1.82294 -23.9873 6.80332,
+                          -3.29982e-15 -21.0275 13.522,
+                          -3.49976 -21.0275 13.0613,
+                          -7.3214e-16 -23.9873 7.04331,
+                          3.49976 -21.0275 13.0613,
+                          1.82294 -23.9873 6.80332,
+                          3.52166 -23.9873 6.09969,
+                          3.49976 -21.0275 13.0613,
+                          -3.29982e-15 -21.0275 13.522,
+                          1.82294 -23.9873 6.80332,
+                          6.76101 -21.0275 11.7104,
+                          3.52166 -23.9873 6.09969,
+                          4.98037 -23.9873 4.98037,
+                          6.76101 -21.0275 11.7104,
+                          3.49976 -21.0275 13.0613,
+                          3.52166 -23.9873 6.09969,
+                          9.56152 -21.0275 9.56152,
+                          4.98037 -23.9873 4.98037,
+                          6.09969 -23.9873 3.52166,
+                          9.56152 -21.0275 9.56152,
+                          6.76101 -21.0275 11.7104,
+                          4.98037 -23.9873 4.98037,
+                          11.7104 -21.0275 6.76101,
+                          6.09969 -23.9873 3.52166,
+                          6.80332 -23.9873 1.82294,
+                          11.7104 -21.0275 6.76101,
+                          9.56152 -21.0275 9.56152,
+                          6.09969 -23.9873 3.52166,
+                          13.0613 -21.0275 3.49976,
+                          11.7104 -21.0275 6.76101,
+                          6.80332 -23.9873 1.82294,
+                          -18.259 -16.3607 4.89248,
+                          -13.0613 -21.0275 3.49976,
+                          -11.7104 -21.0275 6.76101,
+                          -16.3706 -16.3607 9.45154,
+                          -11.7104 -21.0275 6.76101,
+                          -9.56152 -21.0275 9.56152,
+                          -16.3706 -16.3607 9.45154,
+                          -18.259 -16.3607 4.89248,
+                          -11.7104 -21.0275 6.76101,
+                          -13.3665 -16.3607 13.3665,
+                          -9.56152 -21.0275 9.56152,
+                          -6.76101 -21.0275 11.7104,
+                          -13.3665 -16.3607 13.3665,
+                          -16.3706 -16.3607 9.45154,
+                          -9.56152 -21.0275 9.56152,
+                          -9.45154 -16.3607 16.3706,
+                          -6.76101 -21.0275 11.7104,
+                          -3.49976 -21.0275 13.0613,
+                          -9.45154 -16.3607 16.3706,
+                          -13.3665 -16.3607 13.3665,
+                          -6.76101 -21.0275 11.7104,
+                          -4.89248 -16.3607 18.259,
+                          -3.49976 -21.0275 13.0613,
+                          -3.29982e-15 -21.0275 13.522,
+                          -4.89248 -16.3607 18.259,
+                          -9.45154 -16.3607 16.3706,
+                          -3.49976 -21.0275 13.0613,
+                          -6.30069e-15 -16.3607 18.9031,
+                          -3.29982e-15 -21.0275 13.522,
+                          3.49976 -21.0275 13.0613,
+                          -6.30069e-15 -16.3607 18.9031,
+                          -4.89248 -16.3607 18.259,
+                          -3.29982e-15 -21.0275 13.522,
+                          4.89248 -16.3607 18.259,
+                          3.49976 -21.0275 13.0613,
+                          6.76101 -21.0275 11.7104,
+                          4.89248 -16.3607 18.259,
+                          -6.30069e-15 -16.3607 18.9031,
+                          3.49976 -21.0275 13.0613,
+                          9.45154 -16.3607 16.3706,
+                          6.76101 -21.0275 11.7104,
+                          9.56152 -21.0275 9.56152,
+                          9.45154 -16.3607 16.3706,
+                          4.89248 -16.3607 18.259,
+                          6.76101 -21.0275 11.7104,
+                          13.3665 -16.3607 13.3665,
+                          9.56152 -21.0275 9.56152,
+                          11.7104 -21.0275 6.76101,
+                          13.3665 -16.3607 13.3665,
+                          9.45154 -16.3607 16.3706,
+                          9.56152 -21.0275 9.56152,
+                          16.3706 -16.3607 9.45154,
+                          11.7104 -21.0275 6.76101,
+                          13.0613 -21.0275 3.49976,
+                          16.3706 -16.3607 9.45154,
+                          13.3665 -16.3607 13.3665,
+                          11.7104 -21.0275 6.76101,
+                          18.259 -16.3607 4.89248,
+                          16.3706 -16.3607 9.45154,
+                          13.0613 -21.0275 3.49976,
+                          -19.9063 -10.3659 11.0131,
+                          -18.259 -16.3607 4.89248,
+                          -16.3706 -16.3607 9.45154,
+                          -19.9063 -10.3659 11.0131,
+                          -22.0274 -10.3659 5.68713,
+                          -18.259 -16.3607 4.89248,
+                          -16.5211 -10.3659 15.6397,
+                          -16.3706 -16.3607 9.45154,
+                          -13.3665 -16.3607 13.3665,
+                          -16.5211 -10.3659 15.6397,
+                          -19.9063 -10.3659 11.0131,
+                          -16.3706 -16.3607 9.45154,
+                          -12.126 -10.4384 19.2094,
+                          -13.3665 -16.3607 13.3665,
+                          -9.45154 -16.3607 16.3706,
+                          -12.126 -10.4384 19.2094,
+                          -16.5211 -10.3659 15.6397,
+                          -13.3665 -16.3607 13.3665,
+                          -9.05827 -13.1891 19.2094,
+                          -9.45154 -16.3607 16.3706,
+                          -4.89248 -16.3607 18.259,
+                          -9.05827 -13.1891 19.2094,
+                          -12.126 -10.4384 19.2094,
+                          -9.45154 -16.3607 16.3706,
+                          -4.84567 -15.2489 19.2094,
+                          -4.89248 -16.3607 18.259,
+                          -6.30069e-15 -16.3607 18.9031,
+                          -4.84567 -15.2489 19.2094,
+                          -9.05827 -13.1891 19.2094,
+                          -4.89248 -16.3607 18.259,
+                          2.40644e-05 -16 19.2094,
+                          -6.30069e-15 -16.3607 18.9031,
+                          4.89248 -16.3607 18.259,
+                          2.40644e-05 -16 19.2094,
+                          -4.84567 -15.2489 19.2094,
+                          -6.30069e-15 -16.3607 18.9031,
+                          9.05829 -13.189 19.2094,
+                          4.89248 -16.3607 18.259,
+                          9.45154 -16.3607 16.3706,
+                          4.8457 -15.2489 19.2094,
+                          2.40644e-05 -16 19.2094,
+                          4.89248 -16.3607 18.259,
+                          9.05829 -13.189 19.2094,
+                          4.8457 -15.2489 19.2094,
+                          4.89248 -16.3607 18.259,
+                          12.126 -10.4384 19.2094,
+                          9.45154 -16.3607 16.3706,
+                          13.3665 -16.3607 13.3665,
+                          12.126 -10.4384 19.2094,
+                          9.05829 -13.189 19.2094,
+                          9.45154 -16.3607 16.3706,
+                          16.5211 -10.3659 15.6397,
+                          13.3665 -16.3607 13.3665,
+                          16.3706 -16.3607 9.45154,
+                          16.5211 -10.3659 15.6397,
+                          12.126 -10.4384 19.2094,
+                          13.3665 -16.3607 13.3665,
+                          19.9063 -10.3659 11.0131,
+                          16.3706 -16.3607 9.45154,
+                          18.259 -16.3607 4.89248,
+                          19.9063 -10.3659 11.0131,
+                          16.5211 -10.3659 15.6397,
+                          16.3706 -16.3607 9.45154,
+                          22.0274 -10.3659 5.68713,
+                          19.9063 -10.3659 11.0131,
+                          18.259 -16.3607 4.89248,
+                          -22.3128 -3.5296 10.7089,
+                          -22.0274 -10.3659 5.68713,
+                          -19.9063 -10.3659 11.0131,
+                          -22.3128 -3.5296 10.7089,
+                          -24.1327 -3.5296 5.49133,
+                          -22.0274 -10.3659 5.68713,
+                          -19.3806 -3.5296 15.3927,
+                          -19.9063 -10.3659 11.0131,
+                          -16.5211 -10.3659 15.6397,
+                          -19.3806 -3.5296 15.3927,
+                          -22.3128 -3.5296 10.7089,
+                          -19.9063 -10.3659 11.0131,
+                          -12.5848 -9.87828 19.2094,
+                          -16.5211 -10.3659 15.6397,
+                          -12.126 -10.4384 19.2094,
+                          -15.6009 -3.55126 19.2094,
+                          -19.3806 -3.5296 15.3927,
+                          -16.5211 -10.3659 15.6397,
+                          -15.1121 -5.25464 19.2094,
+                          -15.6009 -3.55126 19.2094,
+                          -16.5211 -10.3659 15.6397,
+                          -12.5848 -9.87828 19.2094,
+                          -15.1121 -5.25464 19.2094,
+                          -16.5211 -10.3659 15.6397,
+                          -12.0699 10.5037 19.2094,
+                          -12.126 -10.4384 19.2094,
+                          -9.05827 -13.1891 19.2094,
+                          -12.5848 9.87826 19.2094,
+                          -12.126 -10.4384 19.2094,
+                          -12.0699 10.5037 19.2094,
+                          -12.5848 9.87826 19.2094,
+                          -12.5848 -9.87828 19.2094,
+                          -12.126 -10.4384 19.2094,
+                          -6.9291 -11.3701 19.2094,
+                          -9.05827 -13.1891 19.2094,
+                          -4.84567 -15.2489 19.2094,
+                          -12.0699 10.5037 19.2094,
+                          -9.05827 -13.1891 19.2094,
+                          -9.05829 13.189 19.2094,
+                          -7.5 -8.5 19.2094,
+                          -9.05829 13.189 19.2094,
+                          -9.05827 -13.1891 19.2094,
+                          -6.9291 -11.3701 19.2094,
+                          -7.5 -8.5 19.2094,
+                          -9.05827 -13.1891 19.2094,
+                          -2.87013 -15.4291 19.2094,
+                          -4.84567 -15.2489 19.2094,
+                          2.40644e-05 -16 19.2094,
+                          -5.3033 -13.8033 19.2094,
+                          -6.9291 -11.3701 19.2094,
+                          -4.84567 -15.2489 19.2094,
+                          -2.87013 -15.4291 19.2094,
+                          -5.3033 -13.8033 19.2094,
+                          -4.84567 -15.2489 19.2094,
+                          2.87014 -15.4291 19.2094,
+                          2.40644e-05 -16 19.2094,
+                          4.8457 -15.2489 19.2094,
+                          2.87014 -15.4291 19.2094,
+                          1.68186e-12 -16 18.2094,
+                          2.40644e-05 -16 19.2094,
+                          -2.87013 -15.4291 18.2094,
+                          2.40644e-05 -16 19.2094,
+                          1.68186e-12 -16 18.2094,
+                          -2.87013 -15.4291 18.2094,
+                          -2.87013 -15.4291 19.2094,
+                          2.40644e-05 -16 19.2094,
+                          5.30331 -13.8033 19.2094,
+                          4.8457 -15.2489 19.2094,
+                          9.05829 -13.189 19.2094,
+                          5.30331 -13.8033 19.2094,
+                          2.87014 -15.4291 19.2094,
+                          4.8457 -15.2489 19.2094,
+                          9.05827 13.1891 19.2094,
+                          9.05829 -13.189 19.2094,
+                          12.126 -10.4384 19.2094,
+                          7.5 8.5 19.2094,
+                          9.05829 -13.189 19.2094,
+                          9.05827 13.1891 19.2094,
+                          7.5 -8.5 19.2094,
+                          9.05829 -13.189 19.2094,
+                          7.5 8.5 19.2094,
+                          6.9291 -11.3701 19.2094,
+                          5.30331 -13.8033 19.2094,
+                          9.05829 -13.189 19.2094,
+                          7.5 -8.5 19.2094,
+                          6.9291 -11.3701 19.2094,
+                          9.05829 -13.189 19.2094,
+                          12.5848 -9.87826 19.2094,
+                          12.126 -10.4384 19.2094,
+                          16.5211 -10.3659 15.6397,
+                          12.0699 10.5037 19.2094,
+                          12.126 -10.4384 19.2094,
+                          12.5848 -9.87826 19.2094,
+                          9.05827 13.1891 19.2094,
+                          12.126 -10.4384 19.2094,
+                          12.0699 10.5037 19.2094,
+                          19.3806 -3.5296 15.3927,
+                          16.5211 -10.3659 15.6397,
+                          19.9063 -10.3659 11.0131,
+                          15.1121 -5.25462 19.2094,
+                          12.5848 -9.87826 19.2094,
+                          16.5211 -10.3659 15.6397,
+                          15.6009 -3.55126 19.2094,
+                          15.1121 -5.25462 19.2094,
+                          16.5211 -10.3659 15.6397,
+                          19.3806 -3.5296 15.3927,
+                          15.6009 -3.55126 19.2094,
+                          16.5211 -10.3659 15.6397,
+                          22.3128 -3.5296 10.7089,
+                          19.9063 -10.3659 11.0131,
+                          22.0274 -10.3659 5.68713,
+                          22.3128 -3.5296 10.7089,
+                          19.3806 -3.5296 15.3927,
+                          19.9063 -10.3659 11.0131,
+                          24.1327 -3.5296 5.49133,
+                          22.3128 -3.5296 10.7089,
+                          22.0274 -10.3659 5.68713,
+                          12.5848 9.87828 19.2094,
+                          12.5848 -9.87826 19.2094,
+                          15.1121 -5.25462 19.2094,
+                          12.0699 10.5037 19.2094,
+                          12.5848 -9.87826 19.2094,
+                          12.5848 9.87828 19.2094,
+                          15.1121 5.25464 19.2094,
+                          15.1121 -5.25462 19.2094,
+                          15.6009 -3.55126 19.2094,
+                          12.5848 9.87828 19.2094,
+                          15.1121 -5.25462 19.2094,
+                          15.1121 5.25464 19.2094,
+                          15.9997 1.29433e-05 19.2094,
+                          15.6009 -3.55126 19.2094,
+                          19.3806 -3.5296 15.3927,
+                          15.5864 3.61444 19.2094,
+                          15.6009 -3.55126 19.2094,
+                          15.9997 1.29433e-05 19.2094,
+                          15.1121 5.25464 19.2094,
+                          15.6009 -3.55126 19.2094,
+                          15.5864 3.61444 19.2094,
+                          22.3027 3.5932 10.7087,
+                          19.3806 -3.5296 15.3927,
+                          22.3128 -3.5296 10.7089,
+                          19.3695 3.5932 15.3919,
+                          15.9997 1.29433e-05 19.2094,
+                          19.3806 -3.5296 15.3927,
+                          22.3027 3.5932 10.7087,
+                          19.3695 3.5932 15.3919,
+                          19.3806 -3.5296 15.3927,
+                          24.1233 3.5932 5.49134,
+                          22.3128 -3.5296 10.7089,
+                          24.1327 -3.5296 5.49133,
+                          24.1233 3.5932 5.49134,
+                          22.3027 3.5932 10.7087,
+                          22.3128 -3.5296 10.7089,
+                          19.3695 3.5932 15.3919,
+                          15.5864 3.61444 19.2094,
+                          15.9997 1.29433e-05 19.2094,
+                          16.4736 10.4243 15.651,
+                          15.5864 3.61444 19.2094,
+                          19.3695 3.5932 15.3919,
+                          16.4736 10.4243 15.651,
+                          15.1121 5.25464 19.2094,
+                          15.5864 3.61444 19.2094,
+                          19.8697 10.4243 11.024,
+                          19.3695 3.5932 15.3919,
+                          22.3027 3.5932 10.7087,
+                          19.8697 10.4243 11.024,
+                          16.4736 10.4243 15.651,
+                          19.3695 3.5932 15.3919,
+                          21.9981 10.4243 5.69362,
+                          22.3027 3.5932 10.7087,
+                          24.1233 3.5932 5.49134,
+                          21.9981 10.4243 5.69362,
+                          19.8697 10.4243 11.024,
+                          22.3027 3.5932 10.7087,
+                          16.4736 10.4243 15.651,
+                          12.5848 9.87828 19.2094,
+                          15.1121 5.25464 19.2094,
+                          16.4736 10.4243 15.651,
+                          12.0699 10.5037 19.2094,
+                          12.5848 9.87828 19.2094,
+                          13.3367 16.4093 13.3367,
+                          12.0699 10.5037 19.2094,
+                          16.4736 10.4243 15.651,
+                          9.43049 16.4093 16.3341,
+                          9.05827 13.1891 19.2094,
+                          12.0699 10.5037 19.2094,
+                          13.3367 16.4093 13.3367,
+                          9.43049 16.4093 16.3341,
+                          12.0699 10.5037 19.2094,
+                          16.3341 16.4093 9.43049,
+                          16.4736 10.4243 15.651,
+                          19.8697 10.4243 11.024,
+                          16.3341 16.4093 9.43049,
+                          13.3367 16.4093 13.3367,
+                          16.4736 10.4243 15.651,
+                          18.2183 16.4093 4.88158,
+                          19.8697 10.4243 11.024,
+                          21.9981 10.4243 5.69362,
+                          18.2183 16.4093 4.88158,
+                          16.3341 16.4093 9.43049,
+                          19.8697 10.4243 11.024,
+                          4.88158 16.4093 18.2183,
+                          4.84567 15.2489 19.2094,
+                          9.05827 13.1891 19.2094,
+                          6.9291 11.3701 19.2094,
+                          9.05827 13.1891 19.2094,
+                          4.84567 15.2489 19.2094,
+                          9.43049 16.4093 16.3341,
+                          4.88158 16.4093 18.2183,
+                          9.05827 13.1891 19.2094,
+                          6.9291 11.3701 19.2094,
+                          7.5 8.5 19.2094,
+                          9.05827 13.1891 19.2094,
+                          -1.91748e-14 16.4093 18.861,
+                          -2.40658e-05 16 19.2094,
+                          4.84567 15.2489 19.2094,
+                          2.87013 15.4291 19.2094,
+                          4.84567 15.2489 19.2094,
+                          -2.40658e-05 16 19.2094,
+                          4.88158 16.4093 18.2183,
+                          -1.91748e-14 16.4093 18.861,
+                          4.84567 15.2489 19.2094,
+                          5.3033 13.8033 19.2094,
+                          6.9291 11.3701 19.2094,
+                          4.84567 15.2489 19.2094,
+                          2.87013 15.4291 19.2094,
+                          5.3033 13.8033 19.2094,
+                          4.84567 15.2489 19.2094,
+                          -4.88158 16.4093 18.2183,
+                          -4.8457 15.2489 19.2094,
+                          -2.40658e-05 16 19.2094,
+                          -2.87014 15.4291 19.2094,
+                          -2.40658e-05 16 19.2094,
+                          -4.8457 15.2489 19.2094,
+                          -1.91748e-14 16.4093 18.861,
+                          -4.88158 16.4093 18.2183,
+                          -2.40658e-05 16 19.2094,
+                          -2.87014 15.4291 19.2094,
+                          1.66857e-12 16 18.2094,
+                          -2.40658e-05 16 19.2094,
+                          2.87013 15.4291 18.2094,
+                          -2.40658e-05 16 19.2094,
+                          1.66857e-12 16 18.2094,
+                          2.87013 15.4291 18.2094,
+                          2.87013 15.4291 19.2094,
+                          -2.40658e-05 16 19.2094,
+                          -4.88158 16.4093 18.2183,
+                          -9.05829 13.189 19.2094,
+                          -4.8457 15.2489 19.2094,
+                          -5.30331 13.8033 19.2094,
+                          -4.8457 15.2489 19.2094,
+                          -9.05829 13.189 19.2094,
+                          -5.30331 13.8033 19.2094,
+                          -2.87014 15.4291 19.2094,
+                          -4.8457 15.2489 19.2094,
+                          -9.43049 16.4093 16.3341,
+                          -12.0699 10.5037 19.2094,
+                          -9.05829 13.189 19.2094,
+                          -4.88158 16.4093 18.2183,
+                          -9.43049 16.4093 16.3341,
+                          -9.05829 13.189 19.2094,
+                          -7.5 -8.5 19.2094,
+                          -7.5 8.5 19.2094,
+                          -9.05829 13.189 19.2094,
+                          -6.9291 11.3701 19.2094,
+                          -9.05829 13.189 19.2094,
+                          -7.5 8.5 19.2094,
+                          -6.9291 11.3701 19.2094,
+                          -5.30331 13.8033 19.2094,
+                          -9.05829 13.189 19.2094,
+                          -13.3367 16.4093 13.3367,
+                          -16.4736 10.4243 15.651,
+                          -12.0699 10.5037 19.2094,
+                          -12.5848 9.87826 19.2094,
+                          -12.0699 10.5037 19.2094,
+                          -16.4736 10.4243 15.651,
+                          -9.43049 16.4093 16.3341,
+                          -13.3367 16.4093 13.3367,
+                          -12.0699 10.5037 19.2094,
+                          -16.3341 16.4093 9.43049,
+                          -19.8697 10.4243 11.024,
+                          -16.4736 10.4243 15.651,
+                          -19.3695 3.5932 15.3919,
+                          -16.4736 10.4243 15.651,
+                          -19.8697 10.4243 11.024,
+                          -13.3367 16.4093 13.3367,
+                          -16.3341 16.4093 9.43049,
+                          -16.4736 10.4243 15.651,
+                          -15.5864 3.61444 19.2094,
+                          -16.4736 10.4243 15.651,
+                          -19.3695 3.5932 15.3919,
+                          -15.1121 5.25462 19.2094,
+                          -16.4736 10.4243 15.651,
+                          -15.5864 3.61444 19.2094,
+                          -15.1121 5.25462 19.2094,
+                          -12.5848 9.87826 19.2094,
+                          -16.4736 10.4243 15.651,
+                          -18.2183 16.4093 4.88158,
+                          -21.9981 10.4243 5.69362,
+                          -19.8697 10.4243 11.024,
+                          -22.3027 3.5932 10.7087,
+                          -19.8697 10.4243 11.024,
+                          -21.9981 10.4243 5.69362,
+                          -16.3341 16.4093 9.43049,
+                          -18.2183 16.4093 4.88158,
+                          -19.8697 10.4243 11.024,
+                          -19.3695 3.5932 15.3919,
+                          -19.8697 10.4243 11.024,
+                          -22.3027 3.5932 10.7087,
+                          -22.3027 3.5932 10.7087,
+                          -21.9981 10.4243 5.69362,
+                          -24.1233 3.5932 5.49134,
+                          -13.009 21.0622 3.48576,
+                          -18.2183 16.4093 4.88158,
+                          -16.3341 16.4093 9.43049,
+                          -11.6636 21.0622 6.73397,
+                          -16.3341 16.4093 9.43049,
+                          -13.3367 16.4093 13.3367,
+                          -11.6636 21.0622 6.73397,
+                          -13.009 21.0622 3.48576,
+                          -16.3341 16.4093 9.43049,
+                          -9.52327 21.0622 9.52327,
+                          -13.3367 16.4093 13.3367,
+                          -9.43049 16.4093 16.3341,
+                          -9.52327 21.0622 9.52327,
+                          -11.6636 21.0622 6.73397,
+                          -13.3367 16.4093 13.3367,
+                          -6.73397 21.0622 11.6636,
+                          -9.43049 16.4093 16.3341,
+                          -4.88158 16.4093 18.2183,
+                          -6.73397 21.0622 11.6636,
+                          -9.52327 21.0622 9.52327,
+                          -9.43049 16.4093 16.3341,
+                          -3.48576 21.0622 13.009,
+                          -4.88158 16.4093 18.2183,
+                          -1.91748e-14 16.4093 18.861,
+                          -3.48576 21.0622 13.009,
+                          -6.73397 21.0622 11.6636,
+                          -4.88158 16.4093 18.2183,
+                          -1.98353e-14 21.0622 13.4679,
+                          -1.91748e-14 16.4093 18.861,
+                          4.88158 16.4093 18.2183,
+                          -1.98353e-14 21.0622 13.4679,
+                          -3.48576 21.0622 13.009,
+                          -1.91748e-14 16.4093 18.861,
+                          3.48576 21.0622 13.009,
+                          4.88158 16.4093 18.2183,
+                          9.43049 16.4093 16.3341,
+                          3.48576 21.0622 13.009,
+                          -1.98353e-14 21.0622 13.4679,
+                          4.88158 16.4093 18.2183,
+                          6.73397 21.0622 11.6636,
+                          9.43049 16.4093 16.3341,
+                          13.3367 16.4093 13.3367,
+                          6.73397 21.0622 11.6636,
+                          3.48576 21.0622 13.009,
+                          9.43049 16.4093 16.3341,
+                          9.52327 21.0622 9.52327,
+                          13.3367 16.4093 13.3367,
+                          16.3341 16.4093 9.43049,
+                          9.52327 21.0622 9.52327,
+                          6.73397 21.0622 11.6636,
+                          13.3367 16.4093 13.3367,
+                          11.6636 21.0622 6.73397,
+                          16.3341 16.4093 9.43049,
+                          18.2183 16.4093 4.88158,
+                          11.6636 21.0622 6.73397,
+                          9.52327 21.0622 9.52327,
+                          16.3341 16.4093 9.43049,
+                          13.009 21.0622 3.48576,
+                          11.6636 21.0622 6.73397,
+                          18.2183 16.4093 4.88158,
+                          -24.1233 3.5932 5.49134,
+                          -24.1327 -3.5296 5.49133,
+                          -22.3128 -3.5296 10.7089,
+                          -22.3027 3.5932 10.7087,
+                          -22.3128 -3.5296 10.7089,
+                          -19.3806 -3.5296 15.3927,
+                          -22.3027 3.5932 10.7087,
+                          -24.1233 3.5932 5.49134,
+                          -22.3128 -3.5296 10.7089,
+                          -19.3695 3.5932 15.3919,
+                          -19.3806 -3.5296 15.3927,
+                          -15.6009 -3.55126 19.2094,
+                          -19.3695 3.5932 15.3919,
+                          -22.3027 3.5932 10.7087,
+                          -19.3806 -3.5296 15.3927,
+                          -15.5864 3.61444 19.2094,
+                          -15.6009 -3.55126 19.2094,
+                          -15.1121 -5.25464 19.2094,
+                          -15.9997 -1.29441e-05 19.2094,
+                          -19.3695 3.5932 15.3919,
+                          -15.6009 -3.55126 19.2094,
+                          -15.9997 -1.29441e-05 19.2094,
+                          -15.6009 -3.55126 19.2094,
+                          -15.5864 3.61444 19.2094,
+                          -15.1121 5.25462 19.2094,
+                          -15.1121 -5.25464 19.2094,
+                          -12.5848 -9.87828 19.2094,
+                          -15.1121 5.25462 19.2094,
+                          -15.5864 3.61444 19.2094,
+                          -15.1121 -5.25464 19.2094,
+                          -15.1121 5.25462 19.2094,
+                          -12.5848 -9.87828 19.2094,
+                          -12.5848 9.87826 19.2094,
+                          -15.9997 -1.29441e-05 19.2094,
+                          -15.5864 3.61444 19.2094,
+                          -19.3695 3.5932 15.3919,
+                          1.66809 -1.18792 18.2094,
+                          -16 3.10661e-14 18.2094,
+                          16 1.53145e-14 18.2094,
+                          -1.66809 1.18792 18.2094,
+                          16 1.53145e-14 18.2094,
+                          -16 3.10661e-14 18.2094,
+                          -4.67576 -2.63625 18.2094,
+                          -15.2169 -4.94427 18.2094,
+                          -16 3.10661e-14 18.2094,
+                          -1.66809 1.18792 18.2094,
+                          -16 3.10661e-14 18.2094,
+                          -15.2169 4.94427 18.2094,
+                          -1.66809 -1.18792 18.2094,
+                          -4.67576 -2.63625 18.2094,
+                          -16 3.10661e-14 18.2094,
+                          1.66809 -1.18792 18.2094,
+                          -1.66809 -1.18792 18.2094,
+                          -16 3.10661e-14 18.2094,
+                          1.66809 -1.18792 18.2094,
+                          16 1.53145e-14 18.2094,
+                          15.2169 -4.94427 18.2094,
+                          4.67576 2.63625 18.2094,
+                          15.2169 4.94427 18.2094,
+                          16 1.53145e-14 18.2094,
+                          1.66809 1.18792 18.2094,
+                          4.67576 2.63625 18.2094,
+                          16 1.53145e-14 18.2094,
+                          -1.66809 1.18792 18.2094,
+                          1.66809 1.18792 18.2094,
+                          16 1.53145e-14 18.2094,
+                          6.75747 -5.2467 18.2094,
+                          15.2169 -4.94427 18.2094,
+                          12.9443 -9.40456 18.2094,
+                          4.67576 -2.63625 18.2094,
+                          1.66809 -1.18792 18.2094,
+                          15.2169 -4.94427 18.2094,
+                          6.75747 -5.2467 18.2094,
+                          4.67576 -2.63625 18.2094,
+                          15.2169 -4.94427 18.2094,
+                          6.9291 -11.3701 18.2094,
+                          12.9443 -9.40456 18.2094,
+                          9.40456 -12.9443 18.2094,
+                          7.5 -8.5 18.2094,
+                          6.75747 -5.2467 18.2094,
+                          12.9443 -9.40456 18.2094,
+                          6.9291 -11.3701 18.2094,
+                          7.5 -8.5 18.2094,
+                          12.9443 -9.40456 18.2094,
+                          5.3033 -13.8033 18.2094,
+                          9.40456 -12.9443 18.2094,
+                          4.94427 -15.2169 18.2094,
+                          5.3033 -13.8033 18.2094,
+                          6.9291 -11.3701 18.2094,
+                          9.40456 -12.9443 18.2094,
+                          2.87013 -15.4291 18.2094,
+                          4.94427 -15.2169 18.2094,
+                          1.68186e-12 -16 18.2094,
+                          2.87013 -15.4291 18.2094,
+                          5.3033 -13.8033 18.2094,
+                          4.94427 -15.2169 18.2094,
+                          -2.87013 -15.4291 18.2094,
+                          1.68186e-12 -16 18.2094,
+                          -4.94427 -15.2169 18.2094,
+                          2.87013 -15.4291 18.2094,
+                          1.68186e-12 -16 18.2094,
+                          2.87014 -15.4291 19.2094,
+                          -5.3033 -13.8033 18.2094,
+                          -4.94427 -15.2169 18.2094,
+                          -9.40456 -12.9443 18.2094,
+                          -5.3033 -13.8033 18.2094,
+                          -2.87013 -15.4291 18.2094,
+                          -4.94427 -15.2169 18.2094,
+                          -6.9291 -11.3701 18.2094,
+                          -9.40456 -12.9443 18.2094,
+                          -12.9443 -9.40456 18.2094,
+                          -6.9291 -11.3701 18.2094,
+                          -5.3033 -13.8033 18.2094,
+                          -9.40456 -12.9443 18.2094,
+                          -7.5 -8.5 18.2094,
+                          -12.9443 -9.40456 18.2094,
+                          -15.2169 -4.94427 18.2094,
+                          -7.5 -8.5 18.2094,
+                          -6.9291 -11.3701 18.2094,
+                          -12.9443 -9.40456 18.2094,
+                          -6.75747 -5.2467 18.2094,
+                          -7.5 -8.5 18.2094,
+                          -15.2169 -4.94427 18.2094,
+                          -4.67576 -2.63625 18.2094,
+                          -6.75747 -5.2467 18.2094,
+                          -15.2169 -4.94427 18.2094,
+                          -6.75747 5.2467 18.2094,
+                          -15.2169 4.94427 18.2094,
+                          -12.9443 9.40456 18.2094,
+                          -4.67576 2.63625 18.2094,
+                          -1.66809 1.18792 18.2094,
+                          -15.2169 4.94427 18.2094,
+                          -6.75747 5.2467 18.2094,
+                          -4.67576 2.63625 18.2094,
+                          -15.2169 4.94427 18.2094,
+                          -6.9291 11.3701 18.2094,
+                          -12.9443 9.40456 18.2094,
+                          -9.40456 12.9443 18.2094,
+                          -6.9291 11.3701 18.2094,
+                          -7.5 8.5 18.2094,
+                          -12.9443 9.40456 18.2094,
+                          -6.75747 5.2467 18.2094,
+                          -12.9443 9.40456 18.2094,
+                          -7.5 8.5 18.2094,
+                          -5.3033 13.8033 18.2094,
+                          -9.40456 12.9443 18.2094,
+                          -4.94427 15.2169 18.2094,
+                          -5.3033 13.8033 18.2094,
+                          -6.9291 11.3701 18.2094,
+                          -9.40456 12.9443 18.2094,
+                          -2.87013 15.4291 18.2094,
+                          -4.94427 15.2169 18.2094,
+                          1.66857e-12 16 18.2094,
+                          -2.87013 15.4291 18.2094,
+                          -5.3033 13.8033 18.2094,
+                          -4.94427 15.2169 18.2094,
+                          2.87013 15.4291 18.2094,
+                          1.66857e-12 16 18.2094,
+                          4.94427 15.2169 18.2094,
+                          -2.87013 15.4291 18.2094,
+                          1.66857e-12 16 18.2094,
+                          -2.87014 15.4291 19.2094,
+                          5.3033 13.8033 18.2094,
+                          4.94427 15.2169 18.2094,
+                          9.40456 12.9443 18.2094,
+                          5.3033 13.8033 18.2094,
+                          2.87013 15.4291 18.2094,
+                          4.94427 15.2169 18.2094,
+                          6.9291 11.3701 18.2094,
+                          9.40456 12.9443 18.2094,
+                          12.9443 9.40456 18.2094,
+                          6.9291 11.3701 18.2094,
+                          5.3033 13.8033 18.2094,
+                          9.40456 12.9443 18.2094,
+                          7.5 8.5 18.2094,
+                          12.9443 9.40456 18.2094,
+                          15.2169 4.94427 18.2094,
+                          7.5 8.5 18.2094,
+                          6.9291 11.3701 18.2094,
+                          12.9443 9.40456 18.2094,
+                          6.75747 5.2467 18.2094,
+                          7.5 8.5 18.2094,
+                          15.2169 4.94427 18.2094,
+                          4.67576 2.63625 18.2094,
+                          6.75747 5.2467 18.2094,
+                          15.2169 4.94427 18.2094,
+                          -6.75747 -5.2467 19.2094,
+                          -6.75747 5.2467 19.2094,
+                          -7.5 8.5 19.2094,
+                          -7.5 8.5 18.2094,
+                          -7.5 8.5 19.2094,
+                          -6.75747 5.2467 19.2094,
+                          -7.5 -8.5 19.2094,
+                          -6.75747 -5.2467 19.2094,
+                          -7.5 8.5 19.2094,
+                          -6.9291 11.3701 18.2094,
+                          -6.9291 11.3701 19.2094,
+                          -7.5 8.5 19.2094,
+                          -6.9291 11.3701 18.2094,
+                          -7.5 8.5 19.2094,
+                          -7.5 8.5 18.2094,
+                          -4.67576 -2.63625 19.2094,
+                          -4.67576 2.63625 19.2094,
+                          -6.75747 5.2467 19.2094,
+                          -6.75747 5.2467 18.2094,
+                          -6.75747 5.2467 19.2094,
+                          -4.67576 2.63625 19.2094,
+                          -6.75747 -5.2467 19.2094,
+                          -4.67576 -2.63625 19.2094,
+                          -6.75747 5.2467 19.2094,
+                          -6.75747 5.2467 18.2094,
+                          -7.5 8.5 18.2094,
+                          -6.75747 5.2467 19.2094,
+                          -1.66809 -1.18792 19.2094,
+                          -1.66809 1.18792 19.2094,
+                          -4.67576 2.63625 19.2094,
+                          -4.67576 2.63625 18.2094,
+                          -4.67576 2.63625 19.2094,
+                          -1.66809 1.18792 19.2094,
+                          -4.67576 -2.63625 19.2094,
+                          -1.66809 -1.18792 19.2094,
+                          -4.67576 2.63625 19.2094,
+                          -6.75747 5.2467 18.2094,
+                          -4.67576 2.63625 19.2094,
+                          -4.67576 2.63625 18.2094,
+                          1.66809 -1.18792 19.2094,
+                          1.66809 1.18792 19.2094,
+                          -1.66809 1.18792 19.2094,
+                          -1.66809 1.18792 18.2094,
+                          -1.66809 1.18792 19.2094,
+                          1.66809 1.18792 19.2094,
+                          -1.66809 -1.18792 19.2094,
+                          1.66809 -1.18792 19.2094,
+                          -1.66809 1.18792 19.2094,
+                          -4.67576 2.63625 18.2094,
+                          -1.66809 1.18792 19.2094,
+                          -1.66809 1.18792 18.2094,
+                          4.67576 -2.63625 19.2094,
+                          4.67576 2.63625 19.2094,
+                          1.66809 1.18792 19.2094,
+                          1.66809 1.18792 18.2094,
+                          1.66809 1.18792 19.2094,
+                          4.67576 2.63625 19.2094,
+                          1.66809 -1.18792 19.2094,
+                          4.67576 -2.63625 19.2094,
+                          1.66809 1.18792 19.2094,
+                          -1.66809 1.18792 18.2094,
+                          1.66809 1.18792 19.2094,
+                          1.66809 1.18792 18.2094,
+                          6.75747 -5.2467 19.2094,
+                          6.75747 5.2467 19.2094,
+                          4.67576 2.63625 19.2094,
+                          4.67576 2.63625 18.2094,
+                          4.67576 2.63625 19.2094,
+                          6.75747 5.2467 19.2094,
+                          4.67576 -2.63625 19.2094,
+                          6.75747 -5.2467 19.2094,
+                          4.67576 2.63625 19.2094,
+                          1.66809 1.18792 18.2094,
+                          4.67576 2.63625 19.2094,
+                          4.67576 2.63625 18.2094,
+                          7.5 -8.5 19.2094,
+                          7.5 8.5 19.2094,
+                          6.75747 5.2467 19.2094,
+                          6.75747 5.2467 18.2094,
+                          6.75747 5.2467 19.2094,
+                          7.5 8.5 19.2094,
+                          6.75747 -5.2467 19.2094,
+                          7.5 -8.5 19.2094,
+                          6.75747 5.2467 19.2094,
+                          4.67576 2.63625 18.2094,
+                          6.75747 5.2467 19.2094,
+                          6.75747 5.2467 18.2094,
+                          7.5 8.5 18.2094,
+                          7.5 8.5 19.2094,
+                          6.9291 11.3701 19.2094,
+                          6.75747 5.2467 18.2094,
+                          7.5 8.5 19.2094,
+                          7.5 8.5 18.2094,
+                          6.9291 11.3701 18.2094,
+                          6.9291 11.3701 19.2094,
+                          5.3033 13.8033 19.2094,
+                          7.5 8.5 18.2094,
+                          6.9291 11.3701 19.2094,
+                          6.9291 11.3701 18.2094,
+                          5.3033 13.8033 18.2094,
+                          5.3033 13.8033 19.2094,
+                          2.87013 15.4291 19.2094,
+                          6.9291 11.3701 18.2094,
+                          5.3033 13.8033 19.2094,
+                          5.3033 13.8033 18.2094,
+                          5.3033 13.8033 18.2094,
+                          2.87013 15.4291 19.2094,
+                          2.87013 15.4291 18.2094,
+                          2.87013 -15.4291 18.2094,
+                          2.87014 -15.4291 19.2094,
+                          5.30331 -13.8033 19.2094,
+                          5.3033 -13.8033 18.2094,
+                          5.30331 -13.8033 19.2094,
+                          6.9291 -11.3701 19.2094,
+                          2.87013 -15.4291 18.2094,
+                          5.30331 -13.8033 19.2094,
+                          5.3033 -13.8033 18.2094,
+                          6.9291 -11.3701 18.2094,
+                          6.9291 -11.3701 19.2094,
+                          7.5 -8.5 19.2094,
+                          5.3033 -13.8033 18.2094,
+                          6.9291 -11.3701 19.2094,
+                          6.9291 -11.3701 18.2094,
+                          7.5 -8.5 18.2094,
+                          7.5 -8.5 19.2094,
+                          6.75747 -5.2467 19.2094,
+                          6.9291 -11.3701 18.2094,
+                          7.5 -8.5 19.2094,
+                          7.5 -8.5 18.2094,
+                          6.75747 -5.2467 18.2094,
+                          6.75747 -5.2467 19.2094,
+                          4.67576 -2.63625 19.2094,
+                          7.5 -8.5 18.2094,
+                          6.75747 -5.2467 19.2094,
+                          6.75747 -5.2467 18.2094,
+                          4.67576 -2.63625 18.2094,
+                          4.67576 -2.63625 19.2094,
+                          1.66809 -1.18792 19.2094,
+                          6.75747 -5.2467 18.2094,
+                          4.67576 -2.63625 19.2094,
+                          4.67576 -2.63625 18.2094,
+                          1.66809 -1.18792 18.2094,
+                          1.66809 -1.18792 19.2094,
+                          -1.66809 -1.18792 19.2094,
+                          4.67576 -2.63625 18.2094,
+                          1.66809 -1.18792 19.2094,
+                          1.66809 -1.18792 18.2094,
+                          -1.66809 -1.18792 18.2094,
+                          -1.66809 -1.18792 19.2094,
+                          -4.67576 -2.63625 19.2094,
+                          1.66809 -1.18792 18.2094,
+                          -1.66809 -1.18792 19.2094,
+                          -1.66809 -1.18792 18.2094,
+                          -4.67576 -2.63625 18.2094,
+                          -4.67576 -2.63625 19.2094,
+                          -6.75747 -5.2467 19.2094,
+                          -1.66809 -1.18792 18.2094,
+                          -4.67576 -2.63625 19.2094,
+                          -4.67576 -2.63625 18.2094,
+                          -6.75747 -5.2467 18.2094,
+                          -6.75747 -5.2467 19.2094,
+                          -7.5 -8.5 19.2094,
+                          -4.67576 -2.63625 18.2094,
+                          -6.75747 -5.2467 19.2094,
+                          -6.75747 -5.2467 18.2094,
+                          -7.5 -8.5 18.2094,
+                          -7.5 -8.5 19.2094,
+                          -6.9291 -11.3701 19.2094,
+                          -6.75747 -5.2467 18.2094,
+                          -7.5 -8.5 19.2094,
+                          -7.5 -8.5 18.2094,
+                          -6.9291 -11.3701 18.2094,
+                          -6.9291 -11.3701 19.2094,
+                          -5.3033 -13.8033 19.2094,
+                          -7.5 -8.5 18.2094,
+                          -6.9291 -11.3701 19.2094,
+                          -6.9291 -11.3701 18.2094,
+                          -5.3033 -13.8033 18.2094,
+                          -5.3033 -13.8033 19.2094,
+                          -2.87013 -15.4291 19.2094,
+                          -6.9291 -11.3701 18.2094,
+                          -5.3033 -13.8033 19.2094,
+                          -5.3033 -13.8033 18.2094,
+                          -5.3033 -13.8033 18.2094,
+                          -2.87013 -15.4291 19.2094,
+                          -2.87013 -15.4291 18.2094,
+                          -2.87013 15.4291 18.2094,
+                          -2.87014 15.4291 19.2094,
+                          -5.30331 13.8033 19.2094,
+                          -5.3033 13.8033 18.2094,
+                          -5.30331 13.8033 19.2094,
+                          -6.9291 11.3701 19.2094,
+                          -2.87013 15.4291 18.2094,
+                          -5.30331 13.8033 19.2094,
+                          -5.3033 13.8033 18.2094,
+                          -5.3033 13.8033 18.2094,
+                          -6.9291 11.3701 19.2094,
+                          -6.9291 11.3701 18.2094 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/eyes/eyes_pitch_link_left.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/eyes/eyes_pitch_link_left.iv
new file mode 100644
index 0000000000000000000000000000000000000000..4c69c0a114856883a90e5b2fcfcb15bc0c77c879
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/eyes/eyes_pitch_link_left.iv
@@ -0,0 +1,1475 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+
+    Material {
+        diffuseColor    0.48 0.36 1
+    }
+    Separator {
+        Normal {
+            vector      [ 1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 0.5 0.866025,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 1 -1.22461e-16,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.5 -0.866025,
+                          0 1 -1.22461e-16,
+                          0 1 -1.22461e-16,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.5 0.866025,
+                          0 0.5 0.866025,
+                          0 -0.5 0.866025,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.5 0.866025,
+                          0 1 1.22461e-16,
+                          0 0.5 0.866025,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.5 0.866025,
+                          0 -0.5 0.866025,
+                          0 -1 0,
+                          0 0.5 0.866025,
+                          0 -0.5 0.866025,
+                          0 -0.5 0.866025,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -0.5 -0.866025,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.5 0.866025,
+                          0 -1 0,
+                          0 -1 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.5 -0.866025,
+                          0 -0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -1 0,
+                          0 -0.5 -0.866025,
+                          0 -0.5 -0.866025,
+                          0 -0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          -2.8672e-16 0.866025 -0.5,
+                          -2.8672e-16 0.866025 -0.5,
+                          -4.96614e-16 0.5 -0.866025,
+                          -2.8672e-16 0.866025 -0.5,
+                          -4.96614e-16 0.5 -0.866025,
+                          -4.96614e-16 0.5 -0.866025,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 -1 1.22461e-16,
+                          0 -1 1.22461e-16,
+                          0 -1 1.22461e-16,
+                          0 -1 1.22461e-16,
+                          0 -1 1.22461e-16,
+                          0 -1 1.22461e-16,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0 -0.5 0.866025,
+                          0 -0.5 0.866025,
+                          0 -0.5 0.866025,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 -0.5 0.866025,
+                          0 -0.5 0.866025,
+                          0 -0.5 0.866025,
+                          0 1.83691e-16 1,
+                          0 1.83691e-16 1,
+                          0 0.707107 0.707107,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.707107 0.707107,
+                          0 0.707107 0.707107,
+                          0 1 -1.22461e-16,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.707107 0.707107,
+                          0 1.83691e-16 1,
+                          0 0.707107 0.707107,
+                          0 1 -1.22461e-16,
+                          0 1 -1.22461e-16,
+                          0 1 -1.22461e-16,
+                          0 0.707107 0.707107,
+                          0 1 -1.22461e-16,
+                          0 1 -1.22461e-16,
+                          0 1 -6.69495e-17,
+                          0 1 3.7714e-16,
+                          -2.8672e-16 0.866025 -0.5,
+                          0 1 -1.22461e-16,
+                          0 1 -1.22461e-16,
+                          0 1 -1.22461e-16,
+                          0 1 -6.69495e-17,
+                          -2.8672e-16 0.866025 -0.5,
+                          -2.8672e-16 0.866025 -0.5,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -10 -13 -19.5,
+                          -10 -2.00048 -3.46353,
+                          -10 -4 -7.10543e-15,
+                          -16 -4 -7.10543e-15,
+                          -10 -4 -7.10543e-15,
+                          -10 -2.00048 -3.46353,
+                          -10 -4.69873 10.5,
+                          -10 -4 -7.10543e-15,
+                          -10 -2.00048 3.46353,
+                          -16 -2.00048 3.46353,
+                          -10 -2.00048 3.46353,
+                          -10 -4 -7.10543e-15,
+                          -10 -4.69873 10.5,
+                          -10 -13 -19.5,
+                          -10 -4 -7.10543e-15,
+                          -16 -2.00048 3.46353,
+                          -10 -4 -7.10543e-15,
+                          -16 -4 -7.10543e-15,
+                          -10 9 -6.79829,
+                          -10 2.00048 -3.46353,
+                          -10 -2.00048 -3.46353,
+                          -16 -2.00048 -3.46353,
+                          -10 -2.00048 -3.46353,
+                          -10 2.00048 -3.46353,
+                          -10 -13 -19.5,
+                          -10 9 -6.79829,
+                          -10 -2.00048 -3.46353,
+                          -16 -2.00048 -3.46353,
+                          -16 -4 -7.10543e-15,
+                          -10 -2.00048 -3.46353,
+                          -10 9 -6.79829,
+                          -10 4 -7.10543e-15,
+                          -10 2.00048 -3.46353,
+                          -16 2.00048 -3.46353,
+                          -10 2.00048 -3.46353,
+                          -10 4 -7.10543e-15,
+                          -16 -2.00048 -3.46353,
+                          -10 2.00048 -3.46353,
+                          -16 2.00048 -3.46353,
+                          -10 6 10.5,
+                          -10 2.00048 3.46353,
+                          -10 4 -7.10543e-15,
+                          -16 4 -7.10543e-15,
+                          -10 4 -7.10543e-15,
+                          -10 2.00048 3.46353,
+                          -10 6 10.5,
+                          -10 4 -7.10543e-15,
+                          -10 9 -6.79829,
+                          -16 2.00048 -3.46353,
+                          -10 4 -7.10543e-15,
+                          -16 4 -7.10543e-15,
+                          -10 -4.69873 10.5,
+                          -10 -2.00048 3.46353,
+                          -10 2.00048 3.46353,
+                          -16 2.00048 3.46353,
+                          -10 2.00048 3.46353,
+                          -10 -2.00048 3.46353,
+                          -10 6 10.5,
+                          -10 -4.69873 10.5,
+                          -10 2.00048 3.46353,
+                          -16 4 -7.10543e-15,
+                          -10 2.00048 3.46353,
+                          -16 2.00048 3.46353,
+                          -16 2.00048 3.46353,
+                          -10 -2.00048 3.46353,
+                          -16 -2.00048 3.46353,
+                          -16 9 -6.79829,
+                          -10 9 -6.79829,
+                          -10 -13 -19.5,
+                          -10 10.2425 8.74255,
+                          -10 6 10.5,
+                          -10 9 -6.79829,
+                          -10 11.1962 -4.60214,
+                          -10 10.2425 8.74255,
+                          -10 9 -6.79829,
+                          -16 11.1962 -4.60214,
+                          -10 11.1962 -4.60214,
+                          -10 9 -6.79829,
+                          -16 11.1962 -4.60214,
+                          -10 9 -6.79829,
+                          -16 9 -6.79829,
+                          -10 -48 -14.5,
+                          -10 -48 -19.5,
+                          -10 -13 -19.5,
+                          -16 -13 -19.5,
+                          -10 -13 -19.5,
+                          -10 -48 -19.5,
+                          -10 -4.69873 10.5,
+                          -10 -48 -14.5,
+                          -10 -13 -19.5,
+                          -16 9 -6.79829,
+                          -10 -13 -19.5,
+                          -16 -13 -19.5,
+                          -16 -48 -14.5,
+                          -10 -48 -19.5,
+                          -10 -48 -14.5,
+                          -16 -48 -19.5,
+                          -10 -48 -19.5,
+                          -16 -48 -14.5,
+                          -16 -13 -19.5,
+                          -10 -48 -19.5,
+                          -16 -48 -19.5,
+                          -16 -48 -14.5,
+                          -10 -48 -14.5,
+                          -10 -4.69873 10.5,
+                          -16 -4.69873 10.5,
+                          -10 -4.69873 10.5,
+                          -10 6 10.5,
+                          -16 -48 -14.5,
+                          -10 -4.69873 10.5,
+                          -16 -4.69873 10.5,
+                          -16 6 10.5,
+                          -10 6 10.5,
+                          -10 10.2425 8.74255,
+                          -16 -4.69873 10.5,
+                          -10 6 10.5,
+                          -16 6 10.5,
+                          -10 12 -1.60214,
+                          -10 12 4.5,
+                          -10 10.2425 8.74255,
+                          -16 10.2425 8.74255,
+                          -10 10.2425 8.74255,
+                          -10 12 4.5,
+                          -10 11.1962 -4.60214,
+                          -10 12 -1.60214,
+                          -10 10.2425 8.74255,
+                          -16 10.2425 8.74255,
+                          -16 6 10.5,
+                          -10 10.2425 8.74255,
+                          -16 12 4.5,
+                          -10 12 4.5,
+                          -10 12 -1.60214,
+                          -16 10.2425 8.74255,
+                          -10 12 4.5,
+                          -16 12 4.5,
+                          -16 12 -1.60214,
+                          -10 12 -1.60214,
+                          -10 11.1962 -4.60214,
+                          -16 12 4.5,
+                          -10 12 -1.60214,
+                          -16 12 -1.60214,
+                          -16 12 -1.60214,
+                          -10 11.1962 -4.60214,
+                          -16 11.1962 -4.60214,
+                          -16 -4.69873 10.5,
+                          -16 -2.00048 3.46353,
+                          -16 -4 -7.10543e-15,
+                          -16 -13 -19.5,
+                          -16 -4 -7.10543e-15,
+                          -16 -2.00048 -3.46353,
+                          -16 -13 -19.5,
+                          -16 -4.69873 10.5,
+                          -16 -4 -7.10543e-15,
+                          -16 6 10.5,
+                          -16 2.00048 3.46353,
+                          -16 -2.00048 3.46353,
+                          -16 -4.69873 10.5,
+                          -16 6 10.5,
+                          -16 -2.00048 3.46353,
+                          -16 6 10.5,
+                          -16 4 -7.10543e-15,
+                          -16 2.00048 3.46353,
+                          -16 9 -6.79829,
+                          -16 2.00048 -3.46353,
+                          -16 4 -7.10543e-15,
+                          -16 9 -6.79829,
+                          -16 4 -7.10543e-15,
+                          -16 6 10.5,
+                          -16 -13 -19.5,
+                          -16 -2.00048 -3.46353,
+                          -16 2.00048 -3.46353,
+                          -16 9 -6.79829,
+                          -16 -13 -19.5,
+                          -16 2.00048 -3.46353,
+                          -16 10.2425 8.74255,
+                          -16 9 -6.79829,
+                          -16 6 10.5,
+                          -16 -48 -19.5,
+                          -16 -48 -14.5,
+                          -16 -4.69873 10.5,
+                          -16 -13 -19.5,
+                          -16 -48 -19.5,
+                          -16 -4.69873 10.5,
+                          -16 10.2425 8.74255,
+                          -16 11.1962 -4.60214,
+                          -16 9 -6.79829,
+                          -16 12 4.5,
+                          -16 12 -1.60214,
+                          -16 11.1962 -4.60214,
+                          -16 10.2425 8.74255,
+                          -16 12 4.5,
+                          -16 11.1962 -4.60214 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.71 0.75 0.92
+    }
+    Separator {
+        Normal {
+            vector      [ 0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0 -1 1.22461e-16,
+                          0 -1 1.22461e-16,
+                          0 -1 1.22461e-16,
+                          -0.707092 -0.707122 8.65946e-17,
+                          -0.707092 -0.707122 8.65946e-17,
+                          0 -1 1.22461e-16,
+                          -0.707092 -0.707122 8.65946e-17,
+                          0 -1 1.22461e-16,
+                          0 -1 1.22461e-16,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0 -1 1.22461e-16,
+                          0 -1 1.22461e-16,
+                          0 -1 1.22461e-16,
+                          0 1 -1.22461e-16,
+                          0 1 -1.22461e-16,
+                          0 1 -1.22461e-16,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          -0.573581 0.819149 -1.00313e-16,
+                          -0.573581 0.819149 -1.00313e-16,
+                          -0.573581 0.819149 -1.00313e-16,
+                          0 1 -1.22461e-16,
+                          0 1 -1.22461e-16,
+                          0 1 -1.22461e-16,
+                          -0.573581 0.819149 -1.00313e-16,
+                          -0.573581 0.819149 -1.00313e-16,
+                          0.461746 0.887012 -1.08624e-16,
+                          -0.573581 0.819149 -1.00313e-16,
+                          -0.573581 0.819149 -1.00313e-16,
+                          -0.573581 0.819149 -1.00313e-16,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0.461746 0.887012 -1.08624e-16,
+                          0.461746 0.887012 -1.08624e-16,
+                          1 -1.22461e-16 0,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          -0.573581 0.819149 -1.00313e-16,
+                          0.461746 0.887012 -1.08624e-16,
+                          0.461746 0.887012 -1.08624e-16,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0.461746 0.887012 -1.08624e-16,
+                          1 -1.22461e-16 0,
+                          1 -1.22461e-16 0,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          1 0 0,
+                          1 0 0,
+                          0.707107 0.707107 -8.65927e-17,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0.707107 0.707107 -8.65927e-17,
+                          0.707107 0.707107 -8.65927e-17,
+                          6.12303e-17 1 -1.22461e-16,
+                          1 0 0,
+                          0.707107 0.707107 -8.65927e-17,
+                          0.707107 0.707107 -8.65927e-17,
+                          6.12303e-17 1 -1.22461e-16,
+                          6.12303e-17 1 -1.22461e-16,
+                          -0.707107 0.707107 -8.65927e-17,
+                          0.707107 0.707107 -8.65927e-17,
+                          6.12303e-17 1 -1.22461e-16,
+                          6.12303e-17 1 -1.22461e-16,
+                          -0.707107 0.707107 -8.65927e-17,
+                          -0.707107 0.707107 -8.65927e-17,
+                          -1 1.22461e-16 0,
+                          6.12303e-17 1 -1.22461e-16,
+                          -0.707107 0.707107 -8.65927e-17,
+                          -0.707107 0.707107 -8.65927e-17,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.707107 0.707107 -8.65927e-17,
+                          -1 1.22461e-16 0,
+                          -1 1.22461e-16 0,
+                          -1 -6.12303e-17 0,
+                          -1 -6.12303e-17 0,
+                          -0.707092 -0.707122 8.65946e-17,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.707092 -0.707122 8.65946e-17,
+                          -1 -6.12303e-17 0,
+                          -0.707092 -0.707122 8.65946e-17,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -51.6563 -45.6566 -22.5,
+                          -10 -48 -22.5,
+                          -46 -48 -22.5,
+                          -46 -48 -19.5,
+                          -46 -48 -22.5,
+                          -10 -48 -22.5,
+                          -51.6563 -45.6566 -19.5,
+                          -51.6563 -45.6566 -22.5,
+                          -46 -48 -22.5,
+                          -51.6563 -45.6566 -19.5,
+                          -46 -48 -22.5,
+                          -46 -48 -19.5,
+                          -16 -13 -22.5,
+                          -10 -13 -22.5,
+                          -10 -48 -22.5,
+                          -10 -48 -19.5,
+                          -10 -48 -22.5,
+                          -10 -13 -22.5,
+                          -31.1321 -23.5957 -22.5,
+                          -16 -13 -22.5,
+                          -10 -48 -22.5,
+                          -36.3087 -23.9351 -22.5,
+                          -31.1321 -23.5957 -22.5,
+                          -10 -48 -22.5,
+                          -54 -40 -22.5,
+                          -36.3087 -23.9351 -22.5,
+                          -10 -48 -22.5,
+                          -51.6563 -45.6566 -22.5,
+                          -54 -40 -22.5,
+                          -10 -48 -22.5,
+                          -46 -48 -19.5,
+                          -10 -48 -22.5,
+                          -10 -48 -19.5,
+                          -10 -13 -19.5,
+                          -10 -13 -22.5,
+                          -16 -13 -22.5,
+                          -10 -48 -19.5,
+                          -10 -13 -22.5,
+                          -10 -13 -19.5,
+                          -16 -13 -19.5,
+                          -16 -13 -22.5,
+                          -31.1321 -23.5957 -22.5,
+                          -10 -13 -19.5,
+                          -16 -13 -22.5,
+                          -16 -13 -19.5,
+                          -31.1321 -23.5957 -19.5,
+                          -31.1321 -23.5957 -22.5,
+                          -36.3087 -23.9351 -22.5,
+                          -16 -13 -19.5,
+                          -31.1321 -23.5957 -22.5,
+                          -31.1321 -23.5957 -19.5,
+                          -54 -7.10543e-15 -22.5,
+                          -39 -19.5 -22.5,
+                          -36.3087 -23.9351 -22.5,
+                          -36.3087 -23.9351 -19.5,
+                          -36.3087 -23.9351 -22.5,
+                          -39 -19.5 -22.5,
+                          -54 -40 -22.5,
+                          -54 -7.10543e-15 -22.5,
+                          -36.3087 -23.9351 -22.5,
+                          -31.1321 -23.5957 -19.5,
+                          -36.3087 -23.9351 -22.5,
+                          -36.3087 -23.9351 -19.5,
+                          -54 -7.10543e-15 -22.5,
+                          -39 -7.10543e-15 -22.5,
+                          -39 -19.5 -22.5,
+                          -39 -19.5 -19.5,
+                          -39 -19.5 -22.5,
+                          -39 -7.10543e-15 -22.5,
+                          -36.3087 -23.9351 -19.5,
+                          -39 -19.5 -22.5,
+                          -39 -19.5 -19.5,
+                          -51.8033 5.3033 -22.5,
+                          -41.1967 5.3033 -22.5,
+                          -39 -7.10543e-15 -22.5,
+                          -39 -7.10543e-15 -19.5,
+                          -39 -7.10543e-15 -22.5,
+                          -41.1967 5.3033 -22.5,
+                          -54 -7.10543e-15 -22.5,
+                          -51.8033 5.3033 -22.5,
+                          -39 -7.10543e-15 -22.5,
+                          -39 -19.5 -19.5,
+                          -39 -7.10543e-15 -22.5,
+                          -39 -7.10543e-15 -19.5,
+                          -51.8033 5.3033 -22.5,
+                          -46.5 7.5 -22.5,
+                          -41.1967 5.3033 -22.5,
+                          -41.1967 5.3033 -19.5,
+                          -41.1967 5.3033 -22.5,
+                          -46.5 7.5 -22.5,
+                          -39 -7.10543e-15 -19.5,
+                          -41.1967 5.3033 -22.5,
+                          -41.1967 5.3033 -19.5,
+                          -46.5 7.5 -19.5,
+                          -46.5 7.5 -22.5,
+                          -51.8033 5.3033 -22.5,
+                          -41.1967 5.3033 -19.5,
+                          -46.5 7.5 -22.5,
+                          -46.5 7.5 -19.5,
+                          -51.8033 5.3033 -19.5,
+                          -51.8033 5.3033 -22.5,
+                          -54 -7.10543e-15 -22.5,
+                          -46.5 7.5 -19.5,
+                          -51.8033 5.3033 -22.5,
+                          -51.8033 5.3033 -19.5,
+                          -54 -7.10543e-15 -19.5,
+                          -54 -7.10543e-15 -22.5,
+                          -54 -40 -22.5,
+                          -51.8033 5.3033 -19.5,
+                          -54 -7.10543e-15 -22.5,
+                          -54 -7.10543e-15 -19.5,
+                          -54 -40 -19.5,
+                          -54 -40 -22.5,
+                          -51.6563 -45.6566 -22.5,
+                          -54 -7.10543e-15 -19.5,
+                          -54 -40 -22.5,
+                          -54 -40 -19.5,
+                          -51.6563 -45.6566 -19.5,
+                          -54 -40 -19.5,
+                          -51.6563 -45.6566 -22.5,
+                          -39 -7.10543e-15 -19.5,
+                          -54 -7.10543e-15 -19.5,
+                          -54 -40 -19.5,
+                          -39 -19.5 -19.5,
+                          -39 -7.10543e-15 -19.5,
+                          -54 -40 -19.5,
+                          -36.3087 -23.9351 -19.5,
+                          -39 -19.5 -19.5,
+                          -54 -40 -19.5,
+                          -31.1321 -23.5957 -19.5,
+                          -36.3087 -23.9351 -19.5,
+                          -54 -40 -19.5,
+                          -10 -13 -19.5,
+                          -31.1321 -23.5957 -19.5,
+                          -54 -40 -19.5,
+                          -51.6563 -45.6566 -19.5,
+                          -10 -13 -19.5,
+                          -54 -40 -19.5,
+                          -41.1967 5.3033 -19.5,
+                          -51.8033 5.3033 -19.5,
+                          -54 -7.10543e-15 -19.5,
+                          -39 -7.10543e-15 -19.5,
+                          -41.1967 5.3033 -19.5,
+                          -54 -7.10543e-15 -19.5,
+                          -41.1967 5.3033 -19.5,
+                          -46.5 7.5 -19.5,
+                          -51.8033 5.3033 -19.5,
+                          -10 -13 -19.5,
+                          -16 -13 -19.5,
+                          -31.1321 -23.5957 -19.5,
+                          -46 -48 -19.5,
+                          -10 -48 -19.5,
+                          -10 -13 -19.5,
+                          -51.6563 -45.6566 -19.5,
+                          -46 -48 -19.5,
+                          -10 -13 -19.5 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0 0.65 1
+    }
+    Separator {
+        Normal {
+            vector      [ 8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          1 5.55112e-16 8.65927e-17,
+                          1 5.55112e-16 8.65927e-17,
+                          0.707107 0.707107 -8.65927e-17,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          0.707107 -0.707107 2.09053e-16,
+                          0.707107 -0.707107 2.09053e-16,
+                          1 3.1019e-16 8.65927e-17,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          0.707107 -0.707107 2.09053e-16,
+                          1 3.1019e-16 8.65927e-17,
+                          1 3.1019e-16 8.65927e-17,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          0.707107 0.707107 -8.65927e-17,
+                          0.707107 0.707107 -8.65927e-17,
+                          -1.27104e-15 1 -2.09053e-16,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          0.707107 0.707107 -8.65927e-17,
+                          1 5.55112e-16 8.65927e-17,
+                          0.707107 0.707107 -8.65927e-17,
+                          -1.27104e-15 1 -2.09053e-16,
+                          -1.27104e-15 1 -2.09053e-16,
+                          -0.707107 0.707107 -2.09053e-16,
+                          0.707107 0.707107 -8.65927e-17,
+                          -1.27104e-15 1 -2.09053e-16,
+                          -1.27104e-15 1 -2.09053e-16,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          -0.707107 0.707107 -2.09053e-16,
+                          -0.707107 0.707107 -2.09053e-16,
+                          -1 -4.32651e-16 -8.65927e-17,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          -1.27104e-15 1 -2.09053e-16,
+                          -0.707107 0.707107 -2.09053e-16,
+                          -0.707107 0.707107 -2.09053e-16,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          -1 -4.32651e-16 -8.65927e-17,
+                          -1 -4.32651e-16 -8.65927e-17,
+                          -0.707107 -0.707107 8.65927e-17,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          -0.707107 0.707107 -2.09053e-16,
+                          -1 -4.32651e-16 -8.65927e-17,
+                          -1 -4.32651e-16 -8.65927e-17,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          -0.707107 -0.707107 8.65927e-17,
+                          -0.707107 -0.707107 8.65927e-17,
+                          1.14858e-15 -1 2.09053e-16,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          -1 -4.32651e-16 -8.65927e-17,
+                          -0.707107 -0.707107 8.65927e-17,
+                          -0.707107 -0.707107 8.65927e-17,
+                          1.14858e-15 -1 2.09053e-16,
+                          1.14858e-15 -1 2.09053e-16,
+                          0.707107 -0.707107 2.09053e-16,
+                          -0.707107 -0.707107 8.65927e-17,
+                          1.14858e-15 -1 2.09053e-16,
+                          1.14858e-15 -1 2.09053e-16,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          1.14858e-15 -1 2.09053e-16,
+                          0.707107 -0.707107 2.09053e-16,
+                          0.707107 -0.707107 2.09053e-16,
+                          1.33227e-15 -1 2.09053e-16,
+                          1.33227e-15 -1 2.09053e-16,
+                          -0.866025 -0.5 2.95352e-17,
+                          0.866025 -0.5 1.79518e-16,
+                          0.866025 -0.5 1.79518e-16,
+                          1.57719e-15 -1 2.09053e-16,
+                          0.866025 -0.5 1.79518e-16,
+                          1.57719e-15 -1 2.09053e-16,
+                          1.57719e-15 -1 2.09053e-16,
+                          -0.866025 -0.5 2.95352e-17,
+                          -0.866025 -0.5 2.95352e-17,
+                          -0.866025 0.5 -1.79518e-16,
+                          -0.866025 -0.5 2.95352e-17,
+                          1.33227e-15 -1 2.09053e-16,
+                          -0.866025 -0.5 2.95352e-17,
+                          -0.866025 0.5 -1.79518e-16,
+                          -0.866025 0.5 -1.79518e-16,
+                          -1.45473e-15 1 -2.09053e-16,
+                          -0.866025 -0.5 2.95352e-17,
+                          -0.866025 0.5 -1.79518e-16,
+                          -0.866025 0.5 -1.79518e-16,
+                          -1.45473e-15 1 -2.09053e-16,
+                          -1.45473e-15 1 -2.09053e-16,
+                          0.866025 0.5 -2.95352e-17,
+                          -0.866025 0.5 -1.79518e-16,
+                          -1.45473e-15 1 -2.09053e-16,
+                          -1.45473e-15 1 -2.09053e-16,
+                          0.866025 0.5 -2.95352e-17,
+                          0.866025 0.5 -2.95352e-17,
+                          0.866025 -0.5 1.79518e-16,
+                          -1.45473e-15 1 -2.09053e-16,
+                          0.866025 0.5 -2.95352e-17,
+                          0.866025 0.5 -2.95352e-17,
+                          0.866025 0.5 -2.95352e-17,
+                          0.866025 -0.5 1.79518e-16,
+                          0.866025 -0.5 1.79518e-16,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          1 5.55112e-16 8.65927e-17,
+                          1 5.55112e-16 8.65927e-17,
+                          0.707107 0.707107 -8.65927e-17,
+                          0.707107 -0.707107 2.09053e-16,
+                          0.707107 -0.707107 2.09053e-16,
+                          1 3.1019e-16 8.65927e-17,
+                          0.707107 -0.707107 2.09053e-16,
+                          1 3.1019e-16 8.65927e-17,
+                          1 3.1019e-16 8.65927e-17,
+                          0.707107 0.707107 -8.65927e-17,
+                          0.707107 0.707107 -8.65927e-17,
+                          -8.26948e-16 1 -2.09053e-16,
+                          0.707107 0.707107 -8.65927e-17,
+                          1 5.55112e-16 8.65927e-17,
+                          0.707107 0.707107 -8.65927e-17,
+                          -1.27104e-15 1 -2.09053e-16,
+                          -8.26948e-16 1 -2.09053e-16,
+                          -0.707107 0.707107 -2.09053e-16,
+                          0.707107 0.707107 -8.65927e-17,
+                          -8.26948e-16 1 -2.09053e-16,
+                          -1.27104e-15 1 -2.09053e-16,
+                          -0.707107 0.707107 -2.09053e-16,
+                          -0.707107 0.707107 -2.09053e-16,
+                          -1 -4.32651e-16 -8.65927e-17,
+                          -1.27104e-15 1 -2.09053e-16,
+                          -0.707107 0.707107 -2.09053e-16,
+                          -0.707107 0.707107 -2.09053e-16,
+                          -1 -4.32651e-16 -8.65927e-17,
+                          -1 -4.32651e-16 -8.65927e-17,
+                          -0.707107 -0.707107 8.65927e-17,
+                          -0.707107 0.707107 -2.09053e-16,
+                          -1 -4.32651e-16 -8.65927e-17,
+                          -1 -4.32651e-16 -8.65927e-17,
+                          -0.707107 -0.707107 8.65927e-17,
+                          -0.707107 -0.707107 8.65927e-17,
+                          1.14858e-15 -1 2.09053e-16,
+                          -1 -4.32651e-16 -8.65927e-17,
+                          -0.707107 -0.707107 8.65927e-17,
+                          -0.707107 -0.707107 8.65927e-17,
+                          1.14858e-15 -1 2.09053e-16,
+                          1.14858e-15 -1 2.09053e-16,
+                          0.707107 -0.707107 2.09053e-16,
+                          -0.707107 -0.707107 8.65927e-17,
+                          1.14858e-15 -1 2.09053e-16,
+                          1.14858e-15 -1 2.09053e-16,
+                          1.14858e-15 -1 2.09053e-16,
+                          0.707107 -0.707107 2.09053e-16,
+                          0.707107 -0.707107 2.09053e-16,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          -8.65927e-17 2.09053e-16 1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          1.33227e-15 -1 2.09053e-16,
+                          1.33227e-15 -1 2.09053e-16,
+                          -0.707107 -0.707107 8.65927e-17,
+                          0.707107 -0.707107 2.09053e-16,
+                          0.707107 -0.707107 2.09053e-16,
+                          1.57719e-15 -1 2.09053e-16,
+                          0.707107 -0.707107 2.09053e-16,
+                          1.57719e-15 -1 2.09053e-16,
+                          1.57719e-15 -1 2.09053e-16,
+                          -0.707107 -0.707107 8.65927e-17,
+                          -0.707107 -0.707107 8.65927e-17,
+                          -1 -6.16342e-16 -8.65927e-17,
+                          -0.707107 -0.707107 8.65927e-17,
+                          1.33227e-15 -1 2.09053e-16,
+                          -0.707107 -0.707107 8.65927e-17,
+                          -1 -6.16342e-16 -8.65927e-17,
+                          -1 -6.16342e-16 -8.65927e-17,
+                          -0.707107 0.707107 -2.09053e-16,
+                          -0.707107 -0.707107 8.65927e-17,
+                          -1 -6.16342e-16 -8.65927e-17,
+                          -1 -6.16342e-16 -8.65927e-17,
+                          -0.707107 0.707107 -2.09053e-16,
+                          -0.707107 0.707107 -2.09053e-16,
+                          -1.45473e-15 1 -2.09053e-16,
+                          -1 -6.16342e-16 -8.65927e-17,
+                          -0.707107 0.707107 -2.09053e-16,
+                          -0.707107 0.707107 -2.09053e-16,
+                          -1.45473e-15 1 -2.09053e-16,
+                          -1.45473e-15 1 -2.09053e-16,
+                          0.707107 0.707107 -8.65927e-17,
+                          -0.707107 0.707107 -2.09053e-16,
+                          -1.45473e-15 1 -2.09053e-16,
+                          -1.45473e-15 1 -2.09053e-16,
+                          0.707107 0.707107 -8.65927e-17,
+                          0.707107 0.707107 -8.65927e-17,
+                          1 7.38802e-16 8.65927e-17,
+                          -1.45473e-15 1 -2.09053e-16,
+                          0.707107 0.707107 -8.65927e-17,
+                          0.707107 0.707107 -8.65927e-17,
+                          1 7.38802e-16 8.65927e-17,
+                          1 7.38802e-16 8.65927e-17,
+                          0.707107 -0.707107 2.09053e-16,
+                          0.707107 0.707107 -8.65927e-17,
+                          1 7.38802e-16 8.65927e-17,
+                          1 7.38802e-16 8.65927e-17,
+                          1 7.38802e-16 8.65927e-17,
+                          0.707107 -0.707107 2.09053e-16,
+                          0.707107 -0.707107 2.09053e-16,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1,
+                          8.65927e-17 -2.09053e-16 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -46 -36.5 -19.5,
+                          -40.3429 -34.3435 -19.5,
+                          -38 -40 -19.5,
+                          -38 -40 12.5,
+                          -38 -40 -19.5,
+                          -40.3429 -34.3435 -19.5,
+                          -42.9692 -41.7502 -19.5,
+                          -38 -40 -19.5,
+                          -40.3429 -45.6565 -19.5,
+                          -40.3429 -45.6565 12.5,
+                          -40.3429 -45.6565 -19.5,
+                          -38 -40 -19.5,
+                          -42.9692 -38.2498 -19.5,
+                          -46 -36.5 -19.5,
+                          -38 -40 -19.5,
+                          -42.9692 -41.7502 -19.5,
+                          -42.9692 -38.2498 -19.5,
+                          -38 -40 -19.5,
+                          -40.3429 -45.6565 12.5,
+                          -38 -40 -19.5,
+                          -38 -40 12.5,
+                          -51.6571 -34.3435 -19.5,
+                          -46 -32.0001 -19.5,
+                          -40.3429 -34.3435 -19.5,
+                          -40.3429 -34.3435 12.5,
+                          -40.3429 -34.3435 -19.5,
+                          -46 -32.0001 -19.5,
+                          -46 -36.5 -19.5,
+                          -51.6571 -34.3435 -19.5,
+                          -40.3429 -34.3435 -19.5,
+                          -40.3429 -34.3435 12.5,
+                          -38 -40 12.5,
+                          -40.3429 -34.3435 -19.5,
+                          -46 -32.0001 12.5,
+                          -46 -32.0001 -19.5,
+                          -51.6571 -34.3435 -19.5,
+                          -40.3429 -34.3435 12.5,
+                          -46 -32.0001 -19.5,
+                          -46 -32.0001 12.5,
+                          -49.0308 -38.2498 -19.5,
+                          -54 -40 -19.5,
+                          -51.6571 -34.3435 -19.5,
+                          -51.6571 -34.3435 12.5,
+                          -51.6571 -34.3435 -19.5,
+                          -54 -40 -19.5,
+                          -46 -36.5 -19.5,
+                          -49.0308 -38.2498 -19.5,
+                          -51.6571 -34.3435 -19.5,
+                          -46 -32.0001 12.5,
+                          -51.6571 -34.3435 -19.5,
+                          -51.6571 -34.3435 12.5,
+                          -46 -43.5 -19.5,
+                          -51.6571 -45.6565 -19.5,
+                          -54 -40 -19.5,
+                          -54 -40 12.5,
+                          -54 -40 -19.5,
+                          -51.6571 -45.6565 -19.5,
+                          -49.0308 -41.7502 -19.5,
+                          -46 -43.5 -19.5,
+                          -54 -40 -19.5,
+                          -49.0308 -38.2498 -19.5,
+                          -49.0308 -41.7502 -19.5,
+                          -54 -40 -19.5,
+                          -51.6571 -34.3435 12.5,
+                          -54 -40 -19.5,
+                          -54 -40 12.5,
+                          -40.3429 -45.6565 -19.5,
+                          -46 -47.9999 -19.5,
+                          -51.6571 -45.6565 -19.5,
+                          -51.6571 -45.6565 12.5,
+                          -51.6571 -45.6565 -19.5,
+                          -46 -47.9999 -19.5,
+                          -46 -43.5 -19.5,
+                          -40.3429 -45.6565 -19.5,
+                          -51.6571 -45.6565 -19.5,
+                          -54 -40 12.5,
+                          -51.6571 -45.6565 -19.5,
+                          -51.6571 -45.6565 12.5,
+                          -46 -47.9999 12.5,
+                          -46 -47.9999 -19.5,
+                          -40.3429 -45.6565 -19.5,
+                          -51.6571 -45.6565 12.5,
+                          -46 -47.9999 -19.5,
+                          -46 -47.9999 12.5,
+                          -42.9692 -41.7502 -19.5,
+                          -40.3429 -45.6565 -19.5,
+                          -46 -43.5 -19.5,
+                          -46 -47.9999 12.5,
+                          -40.3429 -45.6565 -19.5,
+                          -40.3429 -45.6565 12.5,
+                          -46 -43.5 -21,
+                          -46 -43.5 -19.5,
+                          -49.0308 -41.7502 -19.5,
+                          -42.9689 -41.75 -21,
+                          -42.9692 -41.7502 -19.5,
+                          -46 -43.5 -19.5,
+                          -42.9689 -41.75 -21,
+                          -46 -43.5 -19.5,
+                          -46 -43.5 -21,
+                          -49.0311 -41.75 -21,
+                          -49.0308 -41.7502 -19.5,
+                          -49.0308 -38.2498 -19.5,
+                          -49.0311 -41.75 -21,
+                          -46 -43.5 -21,
+                          -49.0308 -41.7502 -19.5,
+                          -49.0311 -38.25 -21,
+                          -49.0308 -38.2498 -19.5,
+                          -46 -36.5 -19.5,
+                          -49.0311 -41.75 -21,
+                          -49.0308 -38.2498 -19.5,
+                          -49.0311 -38.25 -21,
+                          -46 -36.5 -21,
+                          -46 -36.5 -19.5,
+                          -42.9692 -38.2498 -19.5,
+                          -49.0311 -38.25 -21,
+                          -46 -36.5 -19.5,
+                          -46 -36.5 -21,
+                          -42.9689 -38.25 -21,
+                          -42.9692 -38.2498 -19.5,
+                          -42.9692 -41.7502 -19.5,
+                          -46 -36.5 -21,
+                          -42.9692 -38.2498 -19.5,
+                          -42.9689 -38.25 -21,
+                          -42.9689 -38.25 -21,
+                          -42.9692 -41.7502 -19.5,
+                          -42.9689 -41.75 -21,
+                          -40.6967 -45.3033 12.5,
+                          -40.3429 -45.6565 12.5,
+                          -38 -40 12.5,
+                          -38.5 -40 12.5,
+                          -38 -40 12.5,
+                          -40.3429 -34.3435 12.5,
+                          -40.6967 -45.3033 12.5,
+                          -38 -40 12.5,
+                          -38.5 -40 12.5,
+                          -46 -47.5 12.5,
+                          -46 -47.9999 12.5,
+                          -40.3429 -45.6565 12.5,
+                          -40.6967 -45.3033 12.5,
+                          -46 -47.5 12.5,
+                          -40.3429 -45.6565 12.5,
+                          -46 -47.5 12.5,
+                          -51.6571 -45.6565 12.5,
+                          -46 -47.9999 12.5,
+                          -53.5 -40 12.5,
+                          -54 -40 12.5,
+                          -51.6571 -45.6565 12.5,
+                          -51.3033 -45.3033 12.5,
+                          -53.5 -40 12.5,
+                          -51.6571 -45.6565 12.5,
+                          -46 -47.5 12.5,
+                          -51.3033 -45.3033 12.5,
+                          -51.6571 -45.6565 12.5,
+                          -51.3033 -34.6967 12.5,
+                          -51.6571 -34.3435 12.5,
+                          -54 -40 12.5,
+                          -53.5 -40 12.5,
+                          -51.3033 -34.6967 12.5,
+                          -54 -40 12.5,
+                          -46 -32.5 12.5,
+                          -46 -32.0001 12.5,
+                          -51.6571 -34.3435 12.5,
+                          -51.3033 -34.6967 12.5,
+                          -46 -32.5 12.5,
+                          -51.6571 -34.3435 12.5,
+                          -46 -32.5 12.5,
+                          -40.3429 -34.3435 12.5,
+                          -46 -32.0001 12.5,
+                          -40.6967 -34.6967 12.5,
+                          -38.5 -40 12.5,
+                          -40.3429 -34.3435 12.5,
+                          -46 -32.5 12.5,
+                          -40.6967 -34.6967 12.5,
+                          -40.3429 -34.3435 12.5,
+                          -38.5 -40 23.4,
+                          -38.5 -40 12.5,
+                          -40.6967 -34.6967 12.5,
+                          -40.6971 -45.3036 23.4,
+                          -40.6967 -45.3033 12.5,
+                          -38.5 -40 12.5,
+                          -40.6971 -45.3036 23.4,
+                          -38.5 -40 12.5,
+                          -38.5 -40 23.4,
+                          -40.6971 -34.6964 23.4,
+                          -40.6967 -34.6967 12.5,
+                          -46 -32.5 12.5,
+                          -40.6971 -34.6964 23.4,
+                          -38.5 -40 23.4,
+                          -40.6967 -34.6967 12.5,
+                          -46 -32.5001 23.4,
+                          -46 -32.5 12.5,
+                          -51.3033 -34.6967 12.5,
+                          -40.6971 -34.6964 23.4,
+                          -46 -32.5 12.5,
+                          -46 -32.5001 23.4,
+                          -51.3029 -34.6964 23.4,
+                          -51.3033 -34.6967 12.5,
+                          -53.5 -40 12.5,
+                          -46 -32.5001 23.4,
+                          -51.3033 -34.6967 12.5,
+                          -51.3029 -34.6964 23.4,
+                          -53.5 -40 23.4,
+                          -53.5 -40 12.5,
+                          -51.3033 -45.3033 12.5,
+                          -51.3029 -34.6964 23.4,
+                          -53.5 -40 12.5,
+                          -53.5 -40 23.4,
+                          -51.3029 -45.3036 23.4,
+                          -51.3033 -45.3033 12.5,
+                          -46 -47.5 12.5,
+                          -53.5 -40 23.4,
+                          -51.3033 -45.3033 12.5,
+                          -51.3029 -45.3036 23.4,
+                          -46 -47.4999 23.4,
+                          -46 -47.5 12.5,
+                          -40.6967 -45.3033 12.5,
+                          -51.3029 -45.3036 23.4,
+                          -46 -47.5 12.5,
+                          -46 -47.4999 23.4,
+                          -46 -47.4999 23.4,
+                          -40.6967 -45.3033 12.5,
+                          -40.6971 -45.3036 23.4,
+                          -51.3029 -45.3036 23.4,
+                          -40.6971 -45.3036 23.4,
+                          -38.5 -40 23.4,
+                          -53.5 -40 23.4,
+                          -51.3029 -45.3036 23.4,
+                          -38.5 -40 23.4,
+                          -40.6971 -34.6964 23.4,
+                          -53.5 -40 23.4,
+                          -38.5 -40 23.4,
+                          -51.3029 -45.3036 23.4,
+                          -46 -47.4999 23.4,
+                          -40.6971 -45.3036 23.4,
+                          -40.6971 -34.6964 23.4,
+                          -51.3029 -34.6964 23.4,
+                          -53.5 -40 23.4,
+                          -40.6971 -34.6964 23.4,
+                          -46 -32.5001 23.4,
+                          -51.3029 -34.6964 23.4,
+                          -42.9689 -38.25 -21,
+                          -42.9689 -41.75 -21,
+                          -46 -43.5 -21,
+                          -44.9396 -41.0608 -21,
+                          -42.9689 -38.25 -21,
+                          -46 -43.5 -21,
+                          -46 -41.5 -21,
+                          -46 -43.5 -21,
+                          -49.0311 -41.75 -21,
+                          -44.9396 -41.0608 -21,
+                          -46 -43.5 -21,
+                          -46 -41.5 -21,
+                          -46 -38.5 -21,
+                          -46 -36.5 -21,
+                          -42.9689 -38.25 -21,
+                          -44.9396 -38.9392 -21,
+                          -46 -38.5 -21,
+                          -42.9689 -38.25 -21,
+                          -44.5001 -40 -21,
+                          -44.9396 -38.9392 -21,
+                          -42.9689 -38.25 -21,
+                          -44.9396 -41.0608 -21,
+                          -44.5001 -40 -21,
+                          -42.9689 -38.25 -21,
+                          -49.0311 -41.75 -21,
+                          -49.0311 -38.25 -21,
+                          -46 -36.5 -21,
+                          -47.0604 -38.9392 -21,
+                          -49.0311 -41.75 -21,
+                          -46 -36.5 -21,
+                          -46 -38.5 -21,
+                          -47.0604 -38.9392 -21,
+                          -46 -36.5 -21,
+                          -47.0604 -41.0608 -21,
+                          -46 -41.5 -21,
+                          -49.0311 -41.75 -21,
+                          -47.4999 -40 -21,
+                          -47.0604 -41.0608 -21,
+                          -49.0311 -41.75 -21,
+                          -47.0604 -38.9392 -21,
+                          -47.4999 -40 -21,
+                          -49.0311 -41.75 -21,
+                          -46 -41.5 -33.46,
+                          -46 -41.5 -21,
+                          -47.0604 -41.0608 -21,
+                          -44.9393 -41.0607 -33.46,
+                          -44.9396 -41.0608 -21,
+                          -46 -41.5 -21,
+                          -44.9393 -41.0607 -33.46,
+                          -46 -41.5 -21,
+                          -46 -41.5 -33.46,
+                          -47.0607 -41.0607 -33.46,
+                          -47.0604 -41.0608 -21,
+                          -47.4999 -40 -21,
+                          -47.0607 -41.0607 -33.46,
+                          -46 -41.5 -33.46,
+                          -47.0604 -41.0608 -21,
+                          -47.5 -40 -33.46,
+                          -47.4999 -40 -21,
+                          -47.0604 -38.9392 -21,
+                          -47.0607 -41.0607 -33.46,
+                          -47.4999 -40 -21,
+                          -47.5 -40 -33.46,
+                          -47.0607 -38.9393 -33.46,
+                          -47.0604 -38.9392 -21,
+                          -46 -38.5 -21,
+                          -47.5 -40 -33.46,
+                          -47.0604 -38.9392 -21,
+                          -47.0607 -38.9393 -33.46,
+                          -46 -38.5 -33.46,
+                          -46 -38.5 -21,
+                          -44.9396 -38.9392 -21,
+                          -47.0607 -38.9393 -33.46,
+                          -46 -38.5 -21,
+                          -46 -38.5 -33.46,
+                          -44.9393 -38.9393 -33.46,
+                          -44.9396 -38.9392 -21,
+                          -44.5001 -40 -21,
+                          -46 -38.5 -33.46,
+                          -44.9396 -38.9392 -21,
+                          -44.9393 -38.9393 -33.46,
+                          -44.5 -40 -33.46,
+                          -44.5001 -40 -21,
+                          -44.9396 -41.0608 -21,
+                          -44.9393 -38.9393 -33.46,
+                          -44.5001 -40 -21,
+                          -44.5 -40 -33.46,
+                          -44.5 -40 -33.46,
+                          -44.9396 -41.0608 -21,
+                          -44.9393 -41.0607 -33.46,
+                          -44.9393 -38.9393 -33.46,
+                          -44.9393 -41.0607 -33.46,
+                          -46 -41.5 -33.46,
+                          -46 -38.5 -33.46,
+                          -44.9393 -38.9393 -33.46,
+                          -46 -41.5 -33.46,
+                          -47.0607 -41.0607 -33.46,
+                          -46 -38.5 -33.46,
+                          -46 -41.5 -33.46,
+                          -44.9393 -38.9393 -33.46,
+                          -44.5 -40 -33.46,
+                          -44.9393 -41.0607 -33.46,
+                          -47.0607 -41.0607 -33.46,
+                          -47.0607 -38.9393 -33.46,
+                          -46 -38.5 -33.46,
+                          -47.0607 -41.0607 -33.46,
+                          -47.5 -40 -33.46,
+                          -47.0607 -38.9393 -33.46 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/eyes/eyes_pitch_link_right.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/eyes/eyes_pitch_link_right.iv
new file mode 100644
index 0000000000000000000000000000000000000000..5bbf618375ecc2afc122a28cab7e9e3b4a1ad0cc
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/eyes/eyes_pitch_link_right.iv
@@ -0,0 +1,1475 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+
+    Material {
+        diffuseColor    0.48 0.36 1
+    }
+    Separator {
+        Normal {
+            vector      [ 1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 1 2.44921e-16,
+                          0 1 2.44921e-16,
+                          0 0.5 0.866025,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 1 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.5 -0.866025,
+                          0 1 0,
+                          0 1 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.5 0.866025,
+                          0 0.5 0.866025,
+                          0 -0.5 0.866025,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.5 0.866025,
+                          0 1 2.44921e-16,
+                          0 0.5 0.866025,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.5 0.866025,
+                          0 -0.5 0.866025,
+                          0 -1 -1.22461e-16,
+                          0 0.5 0.866025,
+                          0 -0.5 0.866025,
+                          0 -0.5 0.866025,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -0.5 -0.866025,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.5 0.866025,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.5 -0.866025,
+                          0 -0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -1 -1.22461e-16,
+                          0 -0.5 -0.866025,
+                          0 -0.5 -0.866025,
+                          0 -0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          -2.8672e-16 0.866025 -0.5,
+                          -2.8672e-16 0.866025 -0.5,
+                          -4.96614e-16 0.5 -0.866025,
+                          -2.8672e-16 0.866025 -0.5,
+                          -4.96614e-16 0.5 -0.866025,
+                          -4.96614e-16 0.5 -0.866025,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          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.5 0.866025,
+                          0 -0.5 0.866025,
+                          0 -0.5 0.866025,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 -0.5 0.866025,
+                          0 -0.5 0.866025,
+                          0 -0.5 0.866025,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 0.707107 0.707107,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.707107 0.707107,
+                          0 0.707107 0.707107,
+                          0 1 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.707107 0.707107,
+                          0 6.12303e-17 1,
+                          0 0.707107 0.707107,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 0.707107 0.707107,
+                          0 1 0,
+                          0 1 0,
+                          0 1 5.55112e-17,
+                          0 1 4.996e-16,
+                          -2.8672e-16 0.866025 -0.5,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 5.55112e-17,
+                          -2.8672e-16 0.866025 -0.5,
+                          -2.8672e-16 0.866025 -0.5,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 16 -13 -19.5,
+                          16 -2.00048 -3.46353,
+                          16 -4 -7.10543e-15,
+                          10 -4 -7.10543e-15,
+                          16 -4 -7.10543e-15,
+                          16 -2.00048 -3.46353,
+                          16 -4.69873 10.5,
+                          16 -4 -7.10543e-15,
+                          16 -2.00048 3.46353,
+                          10 -2.00048 3.46353,
+                          16 -2.00048 3.46353,
+                          16 -4 -7.10543e-15,
+                          16 -4.69873 10.5,
+                          16 -13 -19.5,
+                          16 -4 -7.10543e-15,
+                          10 -2.00048 3.46353,
+                          16 -4 -7.10543e-15,
+                          10 -4 -7.10543e-15,
+                          16 9 -6.79829,
+                          16 2.00048 -3.46353,
+                          16 -2.00048 -3.46353,
+                          10 -2.00048 -3.46353,
+                          16 -2.00048 -3.46353,
+                          16 2.00048 -3.46353,
+                          16 -13 -19.5,
+                          16 9 -6.79829,
+                          16 -2.00048 -3.46353,
+                          10 -2.00048 -3.46353,
+                          10 -4 -7.10543e-15,
+                          16 -2.00048 -3.46353,
+                          16 9 -6.79829,
+                          16 4 -7.10543e-15,
+                          16 2.00048 -3.46353,
+                          10 2.00048 -3.46353,
+                          16 2.00048 -3.46353,
+                          16 4 -7.10543e-15,
+                          10 -2.00048 -3.46353,
+                          16 2.00048 -3.46353,
+                          10 2.00048 -3.46353,
+                          16 6 10.5,
+                          16 2.00048 3.46353,
+                          16 4 -7.10543e-15,
+                          10 4 -7.10543e-15,
+                          16 4 -7.10543e-15,
+                          16 2.00048 3.46353,
+                          16 6 10.5,
+                          16 4 -7.10543e-15,
+                          16 9 -6.79829,
+                          10 2.00048 -3.46353,
+                          16 4 -7.10543e-15,
+                          10 4 -7.10543e-15,
+                          16 -4.69873 10.5,
+                          16 -2.00048 3.46353,
+                          16 2.00048 3.46353,
+                          10 2.00048 3.46353,
+                          16 2.00048 3.46353,
+                          16 -2.00048 3.46353,
+                          16 6 10.5,
+                          16 -4.69873 10.5,
+                          16 2.00048 3.46353,
+                          10 4 -7.10543e-15,
+                          16 2.00048 3.46353,
+                          10 2.00048 3.46353,
+                          10 2.00048 3.46353,
+                          16 -2.00048 3.46353,
+                          10 -2.00048 3.46353,
+                          10 9 -6.79829,
+                          16 9 -6.79829,
+                          16 -13 -19.5,
+                          16 10.2425 8.74255,
+                          16 6 10.5,
+                          16 9 -6.79829,
+                          16 11.1962 -4.60214,
+                          16 10.2425 8.74255,
+                          16 9 -6.79829,
+                          10 11.1962 -4.60214,
+                          16 11.1962 -4.60214,
+                          16 9 -6.79829,
+                          10 11.1962 -4.60214,
+                          16 9 -6.79829,
+                          10 9 -6.79829,
+                          16 -48 -14.5,
+                          16 -48 -19.5,
+                          16 -13 -19.5,
+                          10 -13 -19.5,
+                          16 -13 -19.5,
+                          16 -48 -19.5,
+                          16 -4.69873 10.5,
+                          16 -48 -14.5,
+                          16 -13 -19.5,
+                          10 9 -6.79829,
+                          16 -13 -19.5,
+                          10 -13 -19.5,
+                          10 -48 -14.5,
+                          16 -48 -19.5,
+                          16 -48 -14.5,
+                          10 -48 -19.5,
+                          16 -48 -19.5,
+                          10 -48 -14.5,
+                          10 -13 -19.5,
+                          16 -48 -19.5,
+                          10 -48 -19.5,
+                          10 -48 -14.5,
+                          16 -48 -14.5,
+                          16 -4.69873 10.5,
+                          10 -4.69873 10.5,
+                          16 -4.69873 10.5,
+                          16 6 10.5,
+                          10 -48 -14.5,
+                          16 -4.69873 10.5,
+                          10 -4.69873 10.5,
+                          10 6 10.5,
+                          16 6 10.5,
+                          16 10.2425 8.74255,
+                          10 -4.69873 10.5,
+                          16 6 10.5,
+                          10 6 10.5,
+                          16 12 -1.60214,
+                          16 12 4.5,
+                          16 10.2425 8.74255,
+                          10 10.2425 8.74255,
+                          16 10.2425 8.74255,
+                          16 12 4.5,
+                          16 11.1962 -4.60214,
+                          16 12 -1.60214,
+                          16 10.2425 8.74255,
+                          10 10.2425 8.74255,
+                          10 6 10.5,
+                          16 10.2425 8.74255,
+                          10 12 4.5,
+                          16 12 4.5,
+                          16 12 -1.60214,
+                          10 10.2425 8.74255,
+                          16 12 4.5,
+                          10 12 4.5,
+                          10 12 -1.60214,
+                          16 12 -1.60214,
+                          16 11.1962 -4.60214,
+                          10 12 4.5,
+                          16 12 -1.60214,
+                          10 12 -1.60214,
+                          10 12 -1.60214,
+                          16 11.1962 -4.60214,
+                          10 11.1962 -4.60214,
+                          10 -4.69873 10.5,
+                          10 -2.00048 3.46353,
+                          10 -4 -7.10543e-15,
+                          10 -13 -19.5,
+                          10 -4 -7.10543e-15,
+                          10 -2.00048 -3.46353,
+                          10 -13 -19.5,
+                          10 -4.69873 10.5,
+                          10 -4 -7.10543e-15,
+                          10 6 10.5,
+                          10 2.00048 3.46353,
+                          10 -2.00048 3.46353,
+                          10 -4.69873 10.5,
+                          10 6 10.5,
+                          10 -2.00048 3.46353,
+                          10 6 10.5,
+                          10 4 -7.10543e-15,
+                          10 2.00048 3.46353,
+                          10 9 -6.79829,
+                          10 2.00048 -3.46353,
+                          10 4 -7.10543e-15,
+                          10 9 -6.79829,
+                          10 4 -7.10543e-15,
+                          10 6 10.5,
+                          10 -13 -19.5,
+                          10 -2.00048 -3.46353,
+                          10 2.00048 -3.46353,
+                          10 9 -6.79829,
+                          10 -13 -19.5,
+                          10 2.00048 -3.46353,
+                          10 10.2425 8.74255,
+                          10 9 -6.79829,
+                          10 6 10.5,
+                          10 -48 -19.5,
+                          10 -48 -14.5,
+                          10 -4.69873 10.5,
+                          10 -13 -19.5,
+                          10 -48 -19.5,
+                          10 -4.69873 10.5,
+                          10 10.2425 8.74255,
+                          10 11.1962 -4.60214,
+                          10 9 -6.79829,
+                          10 12 4.5,
+                          10 12 -1.60214,
+                          10 11.1962 -4.60214,
+                          10 10.2425 8.74255,
+                          10 12 4.5,
+                          10 11.1962 -4.60214 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.71 0.75 0.92
+    }
+    Separator {
+        Normal {
+            vector      [ -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -3.33067e-16 -1 2.27426e-16,
+                          -3.33067e-16 -1 2.27426e-16,
+                          -3.33067e-16 -1 2.27426e-16,
+                          0.707092 -0.707122 3.21629e-16,
+                          0.707092 -0.707122 3.21629e-16,
+                          -3.33067e-16 -1 2.27426e-16,
+                          0.707092 -0.707122 3.21629e-16,
+                          -3.33067e-16 -1 2.27426e-16,
+                          -3.33067e-16 -1 2.27426e-16,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -1 -3.33067e-16 -2.27426e-16,
+                          -1 -3.33067e-16 -2.27426e-16,
+                          -1 -3.33067e-16 -2.27426e-16,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -3.33067e-16 -1 2.27426e-16,
+                          -3.33067e-16 -1 2.27426e-16,
+                          -3.33067e-16 -1 2.27426e-16,
+                          3.33067e-16 1 -2.27426e-16,
+                          3.33067e-16 1 -2.27426e-16,
+                          3.33067e-16 1 -2.27426e-16,
+                          -1 -3.33067e-16 -2.27426e-16,
+                          -1 -3.33067e-16 -2.27426e-16,
+                          -1 -3.33067e-16 -2.27426e-16,
+                          0.573581 0.819149 -5.58483e-17,
+                          0.573581 0.819149 -5.58483e-17,
+                          0.573581 0.819149 -5.58483e-17,
+                          3.33067e-16 1 -2.27426e-16,
+                          3.33067e-16 1 -2.27426e-16,
+                          3.33067e-16 1 -2.27426e-16,
+                          0.573581 0.819149 -5.58483e-17,
+                          0.573581 0.819149 -5.58483e-17,
+                          -0.461746 0.887012 -3.06742e-16,
+                          0.573581 0.819149 -5.58483e-17,
+                          0.573581 0.819149 -5.58483e-17,
+                          0.573581 0.819149 -5.58483e-17,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -0.461746 0.887012 -3.06742e-16,
+                          -0.461746 0.887012 -3.06742e-16,
+                          -1 -4.55528e-16 -2.27426e-16,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          0.573581 0.819149 -5.58483e-17,
+                          -0.461746 0.887012 -3.06742e-16,
+                          -0.461746 0.887012 -3.06742e-16,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -1 -3.33067e-16 -2.27426e-16,
+                          -1 -3.33067e-16 -2.27426e-16,
+                          -1 -3.33067e-16 -2.27426e-16,
+                          -0.461746 0.887012 -3.06742e-16,
+                          -1 -4.55528e-16 -2.27426e-16,
+                          -1 -4.55528e-16 -2.27426e-16,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -1 -3.33067e-16 -2.27426e-16,
+                          -1 -3.33067e-16 -2.27426e-16,
+                          -0.707107 0.707107 -3.21629e-16,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -1 -3.33067e-16 -2.27426e-16,
+                          -1 -3.33067e-16 -2.27426e-16,
+                          -1 -3.33067e-16 -2.27426e-16,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -0.707107 0.707107 -3.21629e-16,
+                          -0.707107 0.707107 -3.21629e-16,
+                          2.71837e-16 1 -2.27426e-16,
+                          -1 -3.33067e-16 -2.27426e-16,
+                          -0.707107 0.707107 -3.21629e-16,
+                          -0.707107 0.707107 -3.21629e-16,
+                          2.71837e-16 1 -2.27426e-16,
+                          2.71837e-16 1 -2.27426e-16,
+                          0.707107 0.707107 -3.05684e-30,
+                          -0.707107 0.707107 -3.21629e-16,
+                          2.71837e-16 1 -2.27426e-16,
+                          2.71837e-16 1 -2.27426e-16,
+                          0.707107 0.707107 -3.05684e-30,
+                          0.707107 0.707107 -3.05684e-30,
+                          1 4.55528e-16 2.27426e-16,
+                          2.71837e-16 1 -2.27426e-16,
+                          0.707107 0.707107 -3.05684e-30,
+                          0.707107 0.707107 -3.05684e-30,
+                          1 3.33067e-16 2.27426e-16,
+                          1 3.33067e-16 2.27426e-16,
+                          1 3.33067e-16 2.27426e-16,
+                          0.707107 0.707107 -3.05684e-30,
+                          1 4.55528e-16 2.27426e-16,
+                          1 4.55528e-16 2.27426e-16,
+                          1 2.71837e-16 2.27426e-16,
+                          1 2.71837e-16 2.27426e-16,
+                          0.707092 -0.707122 3.21629e-16,
+                          1 3.33067e-16 2.27426e-16,
+                          1 3.33067e-16 2.27426e-16,
+                          1 3.33067e-16 2.27426e-16,
+                          0.707092 -0.707122 3.21629e-16,
+                          1 2.71837e-16 2.27426e-16,
+                          0.707092 -0.707122 3.21629e-16,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 51.6563 -45.6566 -19.5,
+                          10 -48 -19.5,
+                          46 -48 -19.5,
+                          46 -48 -22.5,
+                          46 -48 -19.5,
+                          10 -48 -19.5,
+                          51.6563 -45.6566 -22.5,
+                          51.6563 -45.6566 -19.5,
+                          46 -48 -19.5,
+                          51.6563 -45.6566 -22.5,
+                          46 -48 -19.5,
+                          46 -48 -22.5,
+                          16 -13 -19.5,
+                          10 -13 -19.5,
+                          10 -48 -19.5,
+                          10 -48 -22.5,
+                          10 -48 -19.5,
+                          10 -13 -19.5,
+                          31.1321 -23.5957 -19.5,
+                          16 -13 -19.5,
+                          10 -48 -19.5,
+                          36.3087 -23.9351 -19.5,
+                          31.1321 -23.5957 -19.5,
+                          10 -48 -19.5,
+                          54 -40 -19.5,
+                          36.3087 -23.9351 -19.5,
+                          10 -48 -19.5,
+                          51.6563 -45.6566 -19.5,
+                          54 -40 -19.5,
+                          10 -48 -19.5,
+                          46 -48 -22.5,
+                          10 -48 -19.5,
+                          10 -48 -22.5,
+                          10 -13 -22.5,
+                          10 -13 -19.5,
+                          16 -13 -19.5,
+                          10 -48 -22.5,
+                          10 -13 -19.5,
+                          10 -13 -22.5,
+                          16 -13 -22.5,
+                          16 -13 -19.5,
+                          31.1321 -23.5957 -19.5,
+                          10 -13 -22.5,
+                          16 -13 -19.5,
+                          16 -13 -22.5,
+                          31.1321 -23.5957 -22.5,
+                          31.1321 -23.5957 -19.5,
+                          36.3087 -23.9351 -19.5,
+                          16 -13 -22.5,
+                          31.1321 -23.5957 -19.5,
+                          31.1321 -23.5957 -22.5,
+                          54 0 -19.5,
+                          39 -19.5 -19.5,
+                          36.3087 -23.9351 -19.5,
+                          36.3087 -23.9351 -22.5,
+                          36.3087 -23.9351 -19.5,
+                          39 -19.5 -19.5,
+                          54 -40 -19.5,
+                          54 0 -19.5,
+                          36.3087 -23.9351 -19.5,
+                          31.1321 -23.5957 -22.5,
+                          36.3087 -23.9351 -19.5,
+                          36.3087 -23.9351 -22.5,
+                          54 0 -19.5,
+                          39 -7.10543e-15 -19.5,
+                          39 -19.5 -19.5,
+                          39 -19.5 -22.5,
+                          39 -19.5 -19.5,
+                          39 -7.10543e-15 -19.5,
+                          36.3087 -23.9351 -22.5,
+                          39 -19.5 -19.5,
+                          39 -19.5 -22.5,
+                          51.8033 5.3033 -19.5,
+                          41.1967 5.3033 -19.5,
+                          39 -7.10543e-15 -19.5,
+                          39 -7.10543e-15 -22.5,
+                          39 -7.10543e-15 -19.5,
+                          41.1967 5.3033 -19.5,
+                          54 0 -19.5,
+                          51.8033 5.3033 -19.5,
+                          39 -7.10543e-15 -19.5,
+                          39 -19.5 -22.5,
+                          39 -7.10543e-15 -19.5,
+                          39 -7.10543e-15 -22.5,
+                          51.8033 5.3033 -19.5,
+                          46.5 7.5 -19.5,
+                          41.1967 5.3033 -19.5,
+                          41.1967 5.3033 -22.5,
+                          41.1967 5.3033 -19.5,
+                          46.5 7.5 -19.5,
+                          39 -7.10543e-15 -22.5,
+                          41.1967 5.3033 -19.5,
+                          41.1967 5.3033 -22.5,
+                          46.5 7.5 -22.5,
+                          46.5 7.5 -19.5,
+                          51.8033 5.3033 -19.5,
+                          41.1967 5.3033 -22.5,
+                          46.5 7.5 -19.5,
+                          46.5 7.5 -22.5,
+                          51.8033 5.3033 -22.5,
+                          51.8033 5.3033 -19.5,
+                          54 0 -19.5,
+                          46.5 7.5 -22.5,
+                          51.8033 5.3033 -19.5,
+                          51.8033 5.3033 -22.5,
+                          54 0 -22.5,
+                          54 0 -19.5,
+                          54 -40 -19.5,
+                          51.8033 5.3033 -22.5,
+                          54 0 -19.5,
+                          54 0 -22.5,
+                          54 -40 -22.5,
+                          54 -40 -19.5,
+                          51.6563 -45.6566 -19.5,
+                          54 0 -22.5,
+                          54 -40 -19.5,
+                          54 -40 -22.5,
+                          51.6563 -45.6566 -22.5,
+                          54 -40 -22.5,
+                          51.6563 -45.6566 -19.5,
+                          39 -7.10543e-15 -22.5,
+                          54 0 -22.5,
+                          54 -40 -22.5,
+                          39 -19.5 -22.5,
+                          39 -7.10543e-15 -22.5,
+                          54 -40 -22.5,
+                          36.3087 -23.9351 -22.5,
+                          39 -19.5 -22.5,
+                          54 -40 -22.5,
+                          31.1321 -23.5957 -22.5,
+                          36.3087 -23.9351 -22.5,
+                          54 -40 -22.5,
+                          10 -13 -22.5,
+                          31.1321 -23.5957 -22.5,
+                          54 -40 -22.5,
+                          51.6563 -45.6566 -22.5,
+                          10 -13 -22.5,
+                          54 -40 -22.5,
+                          41.1967 5.3033 -22.5,
+                          51.8033 5.3033 -22.5,
+                          54 0 -22.5,
+                          39 -7.10543e-15 -22.5,
+                          41.1967 5.3033 -22.5,
+                          54 0 -22.5,
+                          41.1967 5.3033 -22.5,
+                          46.5 7.5 -22.5,
+                          51.8033 5.3033 -22.5,
+                          10 -13 -22.5,
+                          16 -13 -22.5,
+                          31.1321 -23.5957 -22.5,
+                          46 -48 -22.5,
+                          10 -48 -22.5,
+                          10 -13 -22.5,
+                          51.6563 -45.6566 -22.5,
+                          46 -48 -22.5,
+                          10 -13 -22.5 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0 0.65 1
+    }
+    Separator {
+        Normal {
+            vector      [ 2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          0 -1 2.27426e-16,
+                          0 -1 2.27426e-16,
+                          0.707107 -0.707107 3.21629e-16,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          -0.707107 -0.707107 2.68706e-30,
+                          -0.707107 -0.707107 2.68706e-30,
+                          -2.44921e-16 -1 2.27426e-16,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          -0.707107 -0.707107 2.68706e-30,
+                          -2.44921e-16 -1 2.27426e-16,
+                          -2.44921e-16 -1 2.27426e-16,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          0.707107 -0.707107 3.21629e-16,
+                          0.707107 -0.707107 3.21629e-16,
+                          1 -6.12303e-17 2.27426e-16,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          0.707107 -0.707107 3.21629e-16,
+                          0 -1 2.27426e-16,
+                          0.707107 -0.707107 3.21629e-16,
+                          1 -6.12303e-17 2.27426e-16,
+                          1 -6.12303e-17 2.27426e-16,
+                          0.707107 0.707107 -2.85962e-30,
+                          0.707107 -0.707107 3.21629e-16,
+                          1 -6.12303e-17 2.27426e-16,
+                          1 -6.12303e-17 2.27426e-16,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          0.707107 0.707107 -2.85962e-30,
+                          0.707107 0.707107 -2.85962e-30,
+                          1.22461e-16 1 -2.27426e-16,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          1 -6.12303e-17 2.27426e-16,
+                          0.707107 0.707107 -2.85962e-30,
+                          0.707107 0.707107 -2.85962e-30,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          1.22461e-16 1 -2.27426e-16,
+                          1.22461e-16 1 -2.27426e-16,
+                          -0.707107 0.707107 -3.21629e-16,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          0.707107 0.707107 -2.85962e-30,
+                          1.22461e-16 1 -2.27426e-16,
+                          1.22461e-16 1 -2.27426e-16,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          -0.707107 0.707107 -3.21629e-16,
+                          -0.707107 0.707107 -3.21629e-16,
+                          -1 1.83691e-16 -2.27426e-16,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          1.22461e-16 1 -2.27426e-16,
+                          -0.707107 0.707107 -3.21629e-16,
+                          -0.707107 0.707107 -3.21629e-16,
+                          -1 1.83691e-16 -2.27426e-16,
+                          -1 1.83691e-16 -2.27426e-16,
+                          -0.707107 -0.707107 2.68706e-30,
+                          -0.707107 0.707107 -3.21629e-16,
+                          -1 1.83691e-16 -2.27426e-16,
+                          -1 1.83691e-16 -2.27426e-16,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          -1 1.83691e-16 -2.27426e-16,
+                          -0.707107 -0.707107 2.68706e-30,
+                          -0.707107 -0.707107 2.68706e-30,
+                          -1 0 -2.27426e-16,
+                          -1 0 -2.27426e-16,
+                          -0.5 0.866025 -3.10669e-16,
+                          -0.5 -0.866025 8.32436e-17,
+                          -0.5 -0.866025 8.32436e-17,
+                          -1 -2.44921e-16 -2.27426e-16,
+                          -0.5 -0.866025 8.32436e-17,
+                          -1 -2.44921e-16 -2.27426e-16,
+                          -1 -2.44921e-16 -2.27426e-16,
+                          -0.5 0.866025 -3.10669e-16,
+                          -0.5 0.866025 -3.10669e-16,
+                          0.5 0.866025 -8.32436e-17,
+                          -0.5 0.866025 -3.10669e-16,
+                          -1 0 -2.27426e-16,
+                          -0.5 0.866025 -3.10669e-16,
+                          0.5 0.866025 -8.32436e-17,
+                          0.5 0.866025 -8.32436e-17,
+                          1 1.22461e-16 2.27426e-16,
+                          -0.5 0.866025 -3.10669e-16,
+                          0.5 0.866025 -8.32436e-17,
+                          0.5 0.866025 -8.32436e-17,
+                          1 1.22461e-16 2.27426e-16,
+                          1 1.22461e-16 2.27426e-16,
+                          0.5 -0.866025 3.10669e-16,
+                          0.5 0.866025 -8.32436e-17,
+                          1 1.22461e-16 2.27426e-16,
+                          1 1.22461e-16 2.27426e-16,
+                          0.5 -0.866025 3.10669e-16,
+                          0.5 -0.866025 3.10669e-16,
+                          -0.5 -0.866025 8.32436e-17,
+                          1 1.22461e-16 2.27426e-16,
+                          0.5 -0.866025 3.10669e-16,
+                          0.5 -0.866025 3.10669e-16,
+                          0.5 -0.866025 3.10669e-16,
+                          -0.5 -0.866025 8.32436e-17,
+                          -0.5 -0.866025 8.32436e-17,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          0 -1 2.27426e-16,
+                          0 -1 2.27426e-16,
+                          0.707107 -0.707107 3.21629e-16,
+                          -0.707107 -0.707107 2.68706e-30,
+                          -0.707107 -0.707107 2.68706e-30,
+                          -2.44921e-16 -1 2.27426e-16,
+                          -0.707107 -0.707107 2.68706e-30,
+                          -2.44921e-16 -1 2.27426e-16,
+                          -2.44921e-16 -1 2.27426e-16,
+                          0.707107 -0.707107 3.21629e-16,
+                          0.707107 -0.707107 3.21629e-16,
+                          1 -5.0532e-16 2.27426e-16,
+                          0.707107 -0.707107 3.21629e-16,
+                          0 -1 2.27426e-16,
+                          0.707107 -0.707107 3.21629e-16,
+                          1 -6.12303e-17 2.27426e-16,
+                          1 -5.0532e-16 2.27426e-16,
+                          0.707107 0.707107 -2.85962e-30,
+                          0.707107 -0.707107 3.21629e-16,
+                          1 -5.0532e-16 2.27426e-16,
+                          1 -6.12303e-17 2.27426e-16,
+                          0.707107 0.707107 -3.00753e-30,
+                          0.707107 0.707107 -2.85962e-30,
+                          1.22461e-16 1 -2.27426e-16,
+                          1 -6.12303e-17 2.27426e-16,
+                          0.707107 0.707107 -2.85962e-30,
+                          0.707107 0.707107 -3.00753e-30,
+                          1.22461e-16 1 -2.27426e-16,
+                          1.22461e-16 1 -2.27426e-16,
+                          -0.707107 0.707107 -3.21629e-16,
+                          0.707107 0.707107 -3.00753e-30,
+                          1.22461e-16 1 -2.27426e-16,
+                          1.22461e-16 1 -2.27426e-16,
+                          -0.707107 0.707107 -3.21629e-16,
+                          -0.707107 0.707107 -3.21629e-16,
+                          -1 1.83691e-16 -2.27426e-16,
+                          1.22461e-16 1 -2.27426e-16,
+                          -0.707107 0.707107 -3.21629e-16,
+                          -0.707107 0.707107 -3.21629e-16,
+                          -1 1.83691e-16 -2.27426e-16,
+                          -1 1.83691e-16 -2.27426e-16,
+                          -0.707107 -0.707107 2.68706e-30,
+                          -0.707107 0.707107 -3.21629e-16,
+                          -1 1.83691e-16 -2.27426e-16,
+                          -1 1.83691e-16 -2.27426e-16,
+                          -1 1.83691e-16 -2.27426e-16,
+                          -0.707107 -0.707107 2.68706e-30,
+                          -0.707107 -0.707107 2.68706e-30,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          -2.27426e-16 2.27426e-16 1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          -1 0 -2.27426e-16,
+                          -1 0 -2.27426e-16,
+                          -0.707107 0.707107 -3.21629e-16,
+                          -0.707107 -0.707107 3.10614e-30,
+                          -0.707107 -0.707107 2.81032e-30,
+                          -1 -2.44921e-16 -2.27426e-16,
+                          -0.707107 -0.707107 3.10614e-30,
+                          -1 -2.44921e-16 -2.27426e-16,
+                          -1 -2.44921e-16 -2.27426e-16,
+                          -0.707107 0.707107 -3.21629e-16,
+                          -0.707107 0.707107 -3.21629e-16,
+                          -6.12303e-17 1 -2.27426e-16,
+                          -0.707107 0.707107 -3.21629e-16,
+                          -1 0 -2.27426e-16,
+                          -0.707107 0.707107 -3.21629e-16,
+                          -6.12303e-17 1 -2.27426e-16,
+                          -6.12303e-17 1 -2.27426e-16,
+                          0.707107 0.707107 -3.20475e-30,
+                          -0.707107 0.707107 -3.21629e-16,
+                          -6.12303e-17 1 -2.27426e-16,
+                          -6.12303e-17 1 -2.27426e-16,
+                          0.707107 0.707107 -3.05684e-30,
+                          0.707107 0.707107 -3.20475e-30,
+                          1 1.22461e-16 2.27426e-16,
+                          -6.12303e-17 1 -2.27426e-16,
+                          0.707107 0.707107 -3.20475e-30,
+                          0.707107 0.707107 -3.05684e-30,
+                          1 1.22461e-16 2.27426e-16,
+                          1 1.22461e-16 2.27426e-16,
+                          0.707107 -0.707107 3.21629e-16,
+                          0.707107 0.707107 -3.05684e-30,
+                          1 1.22461e-16 2.27426e-16,
+                          1 1.22461e-16 2.27426e-16,
+                          0.707107 -0.707107 3.21629e-16,
+                          0.707107 -0.707107 3.21629e-16,
+                          1.83691e-16 -1 2.27426e-16,
+                          1 1.22461e-16 2.27426e-16,
+                          0.707107 -0.707107 3.21629e-16,
+                          0.707107 -0.707107 3.21629e-16,
+                          1.83691e-16 -1 2.27426e-16,
+                          1.83691e-16 -1 2.27426e-16,
+                          -0.707107 -0.707107 2.81032e-30,
+                          0.707107 -0.707107 3.21629e-16,
+                          1.83691e-16 -1 2.27426e-16,
+                          1.83691e-16 -1 2.27426e-16,
+                          1.83691e-16 -1 2.27426e-16,
+                          -0.707107 -0.707107 2.81032e-30,
+                          -0.707107 -0.707107 3.10614e-30,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1,
+                          2.27426e-16 -2.27426e-16 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 50 -40 -19.5,
+                          52.1565 -45.6571 -19.5,
+                          46.5 -48 -19.5,
+                          46.5 -48 12.5,
+                          46.5 -48 -19.5,
+                          52.1565 -45.6571 -19.5,
+                          44.7498 -43.0308 -19.5,
+                          46.5 -48 -19.5,
+                          40.8435 -45.6571 -19.5,
+                          40.8435 -45.6571 12.5,
+                          40.8435 -45.6571 -19.5,
+                          46.5 -48 -19.5,
+                          48.2502 -43.0308 -19.5,
+                          50 -40 -19.5,
+                          46.5 -48 -19.5,
+                          44.7498 -43.0308 -19.5,
+                          48.2502 -43.0308 -19.5,
+                          46.5 -48 -19.5,
+                          40.8435 -45.6571 12.5,
+                          46.5 -48 -19.5,
+                          46.5 -48 12.5,
+                          52.1565 -34.3429 -19.5,
+                          54.4999 -40 -19.5,
+                          52.1565 -45.6571 -19.5,
+                          52.1565 -45.6571 12.5,
+                          52.1565 -45.6571 -19.5,
+                          54.4999 -40 -19.5,
+                          50 -40 -19.5,
+                          52.1565 -34.3429 -19.5,
+                          52.1565 -45.6571 -19.5,
+                          52.1565 -45.6571 12.5,
+                          46.5 -48 12.5,
+                          52.1565 -45.6571 -19.5,
+                          54.4999 -40 12.5,
+                          54.4999 -40 -19.5,
+                          52.1565 -34.3429 -19.5,
+                          52.1565 -45.6571 12.5,
+                          54.4999 -40 -19.5,
+                          54.4999 -40 12.5,
+                          48.2502 -36.9692 -19.5,
+                          46.5 -32 -19.5,
+                          52.1565 -34.3429 -19.5,
+                          52.1565 -34.3429 12.5,
+                          52.1565 -34.3429 -19.5,
+                          46.5 -32 -19.5,
+                          50 -40 -19.5,
+                          48.2502 -36.9692 -19.5,
+                          52.1565 -34.3429 -19.5,
+                          54.4999 -40 12.5,
+                          52.1565 -34.3429 -19.5,
+                          52.1565 -34.3429 12.5,
+                          43 -40 -19.5,
+                          40.8435 -34.3429 -19.5,
+                          46.5 -32 -19.5,
+                          46.5 -32 12.5,
+                          46.5 -32 -19.5,
+                          40.8435 -34.3429 -19.5,
+                          44.7498 -36.9692 -19.5,
+                          43 -40 -19.5,
+                          46.5 -32 -19.5,
+                          48.2502 -36.9692 -19.5,
+                          44.7498 -36.9692 -19.5,
+                          46.5 -32 -19.5,
+                          52.1565 -34.3429 12.5,
+                          46.5 -32 -19.5,
+                          46.5 -32 12.5,
+                          40.8435 -45.6571 -19.5,
+                          38.5001 -40 -19.5,
+                          40.8435 -34.3429 -19.5,
+                          40.8435 -34.3429 12.5,
+                          40.8435 -34.3429 -19.5,
+                          38.5001 -40 -19.5,
+                          43 -40 -19.5,
+                          40.8435 -45.6571 -19.5,
+                          40.8435 -34.3429 -19.5,
+                          46.5 -32 12.5,
+                          40.8435 -34.3429 -19.5,
+                          40.8435 -34.3429 12.5,
+                          38.5001 -40 12.5,
+                          38.5001 -40 -19.5,
+                          40.8435 -45.6571 -19.5,
+                          40.8435 -34.3429 12.5,
+                          38.5001 -40 -19.5,
+                          38.5001 -40 12.5,
+                          44.7498 -43.0308 -19.5,
+                          40.8435 -45.6571 -19.5,
+                          43 -40 -19.5,
+                          38.5001 -40 12.5,
+                          40.8435 -45.6571 -19.5,
+                          40.8435 -45.6571 12.5,
+                          43 -40 -21,
+                          43 -40 -19.5,
+                          44.7498 -36.9692 -19.5,
+                          44.75 -43.0311 -21,
+                          44.7498 -43.0308 -19.5,
+                          43 -40 -19.5,
+                          44.75 -43.0311 -21,
+                          43 -40 -19.5,
+                          43 -40 -21,
+                          44.75 -36.9689 -21,
+                          44.7498 -36.9692 -19.5,
+                          48.2502 -36.9692 -19.5,
+                          44.75 -36.9689 -21,
+                          43 -40 -21,
+                          44.7498 -36.9692 -19.5,
+                          48.25 -36.9689 -21,
+                          48.2502 -36.9692 -19.5,
+                          50 -40 -19.5,
+                          44.75 -36.9689 -21,
+                          48.2502 -36.9692 -19.5,
+                          48.25 -36.9689 -21,
+                          50 -40 -21,
+                          50 -40 -19.5,
+                          48.2502 -43.0308 -19.5,
+                          48.25 -36.9689 -21,
+                          50 -40 -19.5,
+                          50 -40 -21,
+                          48.25 -43.0311 -21,
+                          48.2502 -43.0308 -19.5,
+                          44.7498 -43.0308 -19.5,
+                          50 -40 -21,
+                          48.2502 -43.0308 -19.5,
+                          48.25 -43.0311 -21,
+                          48.25 -43.0311 -21,
+                          44.7498 -43.0308 -19.5,
+                          44.75 -43.0311 -21,
+                          41.1967 -45.3033 12.5,
+                          40.8435 -45.6571 12.5,
+                          46.5 -48 12.5,
+                          46.5 -47.5 12.5,
+                          46.5 -48 12.5,
+                          52.1565 -45.6571 12.5,
+                          41.1967 -45.3033 12.5,
+                          46.5 -48 12.5,
+                          46.5 -47.5 12.5,
+                          39 -40 12.5,
+                          38.5001 -40 12.5,
+                          40.8435 -45.6571 12.5,
+                          41.1967 -45.3033 12.5,
+                          39 -40 12.5,
+                          40.8435 -45.6571 12.5,
+                          39 -40 12.5,
+                          40.8435 -34.3429 12.5,
+                          38.5001 -40 12.5,
+                          46.5 -32.5 12.5,
+                          46.5 -32 12.5,
+                          40.8435 -34.3429 12.5,
+                          41.1967 -34.6967 12.5,
+                          46.5 -32.5 12.5,
+                          40.8435 -34.3429 12.5,
+                          39 -40 12.5,
+                          41.1967 -34.6967 12.5,
+                          40.8435 -34.3429 12.5,
+                          51.8033 -34.6967 12.5,
+                          52.1565 -34.3429 12.5,
+                          46.5 -32 12.5,
+                          46.5 -32.5 12.5,
+                          51.8033 -34.6967 12.5,
+                          46.5 -32 12.5,
+                          54 -40 12.5,
+                          54.4999 -40 12.5,
+                          52.1565 -34.3429 12.5,
+                          51.8033 -34.6967 12.5,
+                          54 -40 12.5,
+                          52.1565 -34.3429 12.5,
+                          54 -40 12.5,
+                          52.1565 -45.6571 12.5,
+                          54.4999 -40 12.5,
+                          51.8033 -45.3033 12.5,
+                          46.5 -47.5 12.5,
+                          52.1565 -45.6571 12.5,
+                          54 -40 12.5,
+                          51.8033 -45.3033 12.5,
+                          52.1565 -45.6571 12.5,
+                          46.5 -47.5 23.4,
+                          46.5 -47.5 12.5,
+                          51.8033 -45.3033 12.5,
+                          41.1964 -45.3029 23.4,
+                          41.1967 -45.3033 12.5,
+                          46.5 -47.5 12.5,
+                          41.1964 -45.3029 23.4,
+                          46.5 -47.5 12.5,
+                          46.5 -47.5 23.4,
+                          51.8036 -45.3029 23.4,
+                          51.8033 -45.3033 12.5,
+                          54 -40 12.5,
+                          51.8036 -45.3029 23.4,
+                          46.5 -47.5 23.4,
+                          51.8033 -45.3033 12.5,
+                          53.9999 -40 23.4,
+                          54 -40 12.5,
+                          51.8033 -34.6967 12.5,
+                          51.8036 -45.3029 23.4,
+                          54 -40 12.5,
+                          53.9999 -40 23.4,
+                          51.8036 -34.6971 23.4,
+                          51.8033 -34.6967 12.5,
+                          46.5 -32.5 12.5,
+                          53.9999 -40 23.4,
+                          51.8033 -34.6967 12.5,
+                          51.8036 -34.6971 23.4,
+                          46.5 -32.5 23.4,
+                          46.5 -32.5 12.5,
+                          41.1967 -34.6967 12.5,
+                          51.8036 -34.6971 23.4,
+                          46.5 -32.5 12.5,
+                          46.5 -32.5 23.4,
+                          41.1964 -34.6971 23.4,
+                          41.1967 -34.6967 12.5,
+                          39 -40 12.5,
+                          46.5 -32.5 23.4,
+                          41.1967 -34.6967 12.5,
+                          41.1964 -34.6971 23.4,
+                          39.0001 -40 23.4,
+                          39 -40 12.5,
+                          41.1967 -45.3033 12.5,
+                          41.1964 -34.6971 23.4,
+                          39 -40 12.5,
+                          39.0001 -40 23.4,
+                          39.0001 -40 23.4,
+                          41.1967 -45.3033 12.5,
+                          41.1964 -45.3029 23.4,
+                          41.1964 -34.6971 23.4,
+                          41.1964 -45.3029 23.4,
+                          46.5 -47.5 23.4,
+                          46.5 -32.5 23.4,
+                          41.1964 -34.6971 23.4,
+                          46.5 -47.5 23.4,
+                          51.8036 -45.3029 23.4,
+                          46.5 -32.5 23.4,
+                          46.5 -47.5 23.4,
+                          41.1964 -34.6971 23.4,
+                          39.0001 -40 23.4,
+                          41.1964 -45.3029 23.4,
+                          51.8036 -45.3029 23.4,
+                          51.8036 -34.6971 23.4,
+                          46.5 -32.5 23.4,
+                          51.8036 -45.3029 23.4,
+                          53.9999 -40 23.4,
+                          51.8036 -34.6971 23.4,
+                          48.25 -43.0311 -21,
+                          44.75 -43.0311 -21,
+                          43 -40 -21,
+                          45.4392 -41.0604 -21,
+                          48.25 -43.0311 -21,
+                          43 -40 -21,
+                          45 -40 -21,
+                          43 -40 -21,
+                          44.75 -36.9689 -21,
+                          45.4392 -41.0604 -21,
+                          43 -40 -21,
+                          45 -40 -21,
+                          48 -40 -21,
+                          50 -40 -21,
+                          48.25 -43.0311 -21,
+                          47.5608 -41.0604 -21,
+                          48 -40 -21,
+                          48.25 -43.0311 -21,
+                          46.5 -41.4999 -21,
+                          47.5608 -41.0604 -21,
+                          48.25 -43.0311 -21,
+                          45.4392 -41.0604 -21,
+                          46.5 -41.4999 -21,
+                          48.25 -43.0311 -21,
+                          44.75 -36.9689 -21,
+                          48.25 -36.9689 -21,
+                          50 -40 -21,
+                          47.5608 -38.9396 -21,
+                          44.75 -36.9689 -21,
+                          50 -40 -21,
+                          48 -40 -21,
+                          47.5608 -38.9396 -21,
+                          50 -40 -21,
+                          45.4392 -38.9396 -21,
+                          45 -40 -21,
+                          44.75 -36.9689 -21,
+                          46.5 -38.5001 -21,
+                          45.4392 -38.9396 -21,
+                          44.75 -36.9689 -21,
+                          47.5608 -38.9396 -21,
+                          46.5 -38.5001 -21,
+                          44.75 -36.9689 -21,
+                          45 -40 -33.46,
+                          45 -40 -21,
+                          45.4392 -38.9396 -21,
+                          45.4393 -41.0607 -33.46,
+                          45.4392 -41.0604 -21,
+                          45 -40 -21,
+                          45.4393 -41.0607 -33.46,
+                          45 -40 -21,
+                          45 -40 -33.46,
+                          45.4393 -38.9393 -33.46,
+                          45.4392 -38.9396 -21,
+                          46.5 -38.5001 -21,
+                          45.4393 -38.9393 -33.46,
+                          45 -40 -33.46,
+                          45.4392 -38.9396 -21,
+                          46.5 -38.5 -33.46,
+                          46.5 -38.5001 -21,
+                          47.5608 -38.9396 -21,
+                          45.4393 -38.9393 -33.46,
+                          46.5 -38.5001 -21,
+                          46.5 -38.5 -33.46,
+                          47.5607 -38.9393 -33.46,
+                          47.5608 -38.9396 -21,
+                          48 -40 -21,
+                          46.5 -38.5 -33.46,
+                          47.5608 -38.9396 -21,
+                          47.5607 -38.9393 -33.46,
+                          48 -40 -33.46,
+                          48 -40 -21,
+                          47.5608 -41.0604 -21,
+                          47.5607 -38.9393 -33.46,
+                          48 -40 -21,
+                          48 -40 -33.46,
+                          47.5607 -41.0607 -33.46,
+                          47.5608 -41.0604 -21,
+                          46.5 -41.4999 -21,
+                          48 -40 -33.46,
+                          47.5608 -41.0604 -21,
+                          47.5607 -41.0607 -33.46,
+                          46.5 -41.5 -33.46,
+                          46.5 -41.4999 -21,
+                          45.4392 -41.0604 -21,
+                          47.5607 -41.0607 -33.46,
+                          46.5 -41.4999 -21,
+                          46.5 -41.5 -33.46,
+                          46.5 -41.5 -33.46,
+                          45.4392 -41.0604 -21,
+                          45.4393 -41.0607 -33.46,
+                          47.5607 -41.0607 -33.46,
+                          45.4393 -41.0607 -33.46,
+                          45 -40 -33.46,
+                          48 -40 -33.46,
+                          47.5607 -41.0607 -33.46,
+                          45 -40 -33.46,
+                          45.4393 -38.9393 -33.46,
+                          48 -40 -33.46,
+                          45 -40 -33.46,
+                          47.5607 -41.0607 -33.46,
+                          46.5 -41.5 -33.46,
+                          45.4393 -41.0607 -33.46,
+                          45.4393 -38.9393 -33.46,
+                          47.5607 -38.9393 -33.46,
+                          48 -40 -33.46,
+                          45.4393 -38.9393 -33.46,
+                          46.5 -38.5 -33.46,
+                          47.5607 -38.9393 -33.46 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/eyes/lid.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/eyes/lid.iv
new file mode 100644
index 0000000000000000000000000000000000000000..ab5fd96ef278c7dc8aaa14f4ee4d3e1edc7cf1ea
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/eyes/lid.iv
@@ -0,0 +1,2695 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    1 1 0.949
+    }
+    Separator {
+        Normal {
+            vector      [ 0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0.959493 -0.267944 -0.0870601,
+                          1 1.83691e-16 4.97208e-14,
+                          0.951057 -0.309017 4.72495e-14,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0.959493 0.268162 -0.0863865,
+                          0.951057 0.309017 4.72873e-14,
+                          1 1.83691e-16 4.97208e-14,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0.959493 -0.227874 -0.16567,
+                          1 1.83691e-16 4.97208e-14,
+                          0.959493 -0.267944 -0.0870601,
+                          0.959493 -0.165455 -0.22803,
+                          1 1.83691e-16 4.97208e-14,
+                          0.959493 -0.227874 -0.16567,
+                          0.959493 -0.0868076 -0.268026,
+                          1 1.83691e-16 4.97208e-14,
+                          0.959493 -0.165455 -0.22803,
+                          0.959493 0.000354035 -0.281732,
+                          1 1.83691e-16 4.97208e-14,
+                          0.959493 -0.0868076 -0.268026,
+                          0.959493 0.0874809 -0.267807,
+                          1 1.83691e-16 4.97208e-14,
+                          0.959493 0.000354035 -0.281732,
+                          0.959493 0.166028 -0.227614,
+                          1 1.83691e-16 4.97208e-14,
+                          0.959493 0.0874809 -0.267807,
+                          0.959493 0.22829 -0.165097,
+                          1 1.83691e-16 4.97208e-14,
+                          0.959493 0.166028 -0.227614,
+                          0.959493 0.268162 -0.0863865,
+                          1 1.83691e-16 4.97208e-14,
+                          0.959493 0.22829 -0.165097,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0.841254 -0.51418 -0.167067,
+                          0.951057 -0.309017 4.72495e-14,
+                          0.809017 -0.587785 4.0153e-14,
+                          0.841254 -0.51418 -0.167067,
+                          0.959493 -0.267944 -0.0870601,
+                          0.951057 -0.309017 4.72495e-14,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0.654861 -0.718761 -0.233539,
+                          0.809017 -0.587785 4.0153e-14,
+                          0.587785 -0.809017 2.91261e-14,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0.654861 -0.718761 -0.233539,
+                          0.841254 -0.51418 -0.167067,
+                          0.809017 -0.587785 4.0153e-14,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0.415415 -0.865111 -0.281092,
+                          0.587785 -0.809017 2.91261e-14,
+                          0.309017 -0.951057 1.52481e-14,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0.415415 -0.865111 -0.281092,
+                          0.654861 -0.718761 -0.233539,
+                          0.587785 -0.809017 2.91261e-14,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0.142315 -0.941376 -0.305872,
+                          0.309017 -0.951057 1.52481e-14,
+                          2.44921e-16 -1 -1.22461e-16,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0.142315 -0.941376 -0.305872,
+                          0.415415 -0.865111 -0.281092,
+                          0.309017 -0.951057 1.52481e-14,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          -0.142315 -0.941376 -0.305872,
+                          2.44921e-16 -1 -1.22461e-16,
+                          -0.309017 -0.951057 -1.5481e-14,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          -0.142315 -0.941376 -0.305872,
+                          0.142315 -0.941376 -0.305872,
+                          2.44921e-16 -1 -1.22461e-16,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          -0.415415 -0.865111 -0.281092,
+                          -0.309017 -0.951057 -1.5481e-14,
+                          -0.587785 -0.809017 -2.93242e-14,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          -0.415415 -0.865111 -0.281092,
+                          -0.142315 -0.941376 -0.305872,
+                          -0.309017 -0.951057 -1.5481e-14,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          -0.654861 -0.718761 -0.233539,
+                          -0.587785 -0.809017 -2.93242e-14,
+                          -0.809017 -0.587785 -4.0297e-14,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          -0.654861 -0.718761 -0.233539,
+                          -0.415415 -0.865111 -0.281092,
+                          -0.587785 -0.809017 -2.93242e-14,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          -0.841254 -0.51418 -0.167067,
+                          -0.809017 -0.587785 -4.0297e-14,
+                          -0.951057 -0.309017 -4.73252e-14,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          -0.841254 -0.51418 -0.167067,
+                          -0.654861 -0.718761 -0.233539,
+                          -0.809017 -0.587785 -4.0297e-14,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          -0.959493 -0.267944 -0.0870601,
+                          -0.951057 -0.309017 -4.73252e-14,
+                          -1 -3.06152e-16 -4.97208e-14,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          -0.959493 -0.267944 -0.0870601,
+                          -0.841254 -0.51418 -0.167067,
+                          -0.951057 -0.309017 -4.73252e-14,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          -0.959493 0.268162 -0.0863865,
+                          -1 -3.06152e-16 -4.97208e-14,
+                          -0.951057 0.309017 -4.72873e-14,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          -0.959493 -0.227874 -0.16567,
+                          -0.959493 -0.267944 -0.0870601,
+                          -1 -3.06152e-16 -4.97208e-14,
+                          -0.959493 -0.165455 -0.22803,
+                          -0.959493 -0.227874 -0.16567,
+                          -1 -3.06152e-16 -4.97208e-14,
+                          -0.959493 -0.0868076 -0.268026,
+                          -0.959493 -0.165455 -0.22803,
+                          -1 -3.06152e-16 -4.97208e-14,
+                          -0.959493 0.000354035 -0.281732,
+                          -0.959493 -0.0868076 -0.268026,
+                          -1 -3.06152e-16 -4.97208e-14,
+                          -0.959493 0.0874809 -0.267807,
+                          -0.959493 0.000354035 -0.281732,
+                          -1 -3.06152e-16 -4.97208e-14,
+                          -0.959493 0.166028 -0.227614,
+                          -0.959493 0.0874809 -0.267807,
+                          -1 -3.06152e-16 -4.97208e-14,
+                          -0.959493 0.22829 -0.165097,
+                          -0.959493 0.166028 -0.227614,
+                          -1 -3.06152e-16 -4.97208e-14,
+                          -0.959493 0.268162 -0.0863865,
+                          -0.959493 0.22829 -0.165097,
+                          -1 -3.06152e-16 -4.97208e-14,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          -0.841254 0.514598 -0.165774,
+                          -0.951057 0.309017 -4.72873e-14,
+                          -0.809017 0.587785 -4.0225e-14,
+                          -0.959493 0.268162 -0.0863865,
+                          -0.951057 0.309017 -4.72873e-14,
+                          -0.841254 0.514598 -0.165774,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          -0.654861 0.719345 -0.231732,
+                          -0.809017 0.587785 -4.0225e-14,
+                          -0.587785 0.809017 -2.92252e-14,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          -0.841254 0.514598 -0.165774,
+                          -0.809017 0.587785 -4.0225e-14,
+                          -0.654861 0.719345 -0.231732,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          -0.415415 0.865815 -0.278917,
+                          -0.587785 0.809017 -2.92252e-14,
+                          -0.309017 0.951057 -1.53646e-14,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          -0.654861 0.719345 -0.231732,
+                          -0.587785 0.809017 -2.92252e-14,
+                          -0.415415 0.865815 -0.278917,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          -0.142315 0.942142 -0.303505,
+                          -0.309017 0.951057 -1.53646e-14,
+                          2.44921e-16 1 1.21777e-29,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          -0.415415 0.865815 -0.278917,
+                          -0.309017 0.951057 -1.53646e-14,
+                          -0.142315 0.942142 -0.303505,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0.142315 0.942142 -0.303505,
+                          2.44921e-16 1 1.21777e-29,
+                          0.309017 0.951057 1.53646e-14,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          -0.142315 0.942142 -0.303505,
+                          2.44921e-16 1 1.21777e-29,
+                          0.142315 0.942142 -0.303505,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0.415415 0.865815 -0.278917,
+                          0.309017 0.951057 1.53646e-14,
+                          0.587785 0.809017 2.92252e-14,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0.142315 0.942142 -0.303505,
+                          0.309017 0.951057 1.53646e-14,
+                          0.415415 0.865815 -0.278917,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0.654861 0.719345 -0.231732,
+                          0.587785 0.809017 2.92252e-14,
+                          0.809017 0.587785 4.0225e-14,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0.415415 0.865815 -0.278917,
+                          0.587785 0.809017 2.92252e-14,
+                          0.654861 0.719345 -0.231732,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0.841254 0.514598 -0.165774,
+                          0.809017 0.587785 4.0225e-14,
+                          0.951057 0.309017 4.72873e-14,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0.654861 0.719345 -0.231732,
+                          0.809017 0.587785 4.0225e-14,
+                          0.841254 0.514598 -0.165774,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0 -2.78053e-27 -1,
+                          0.841254 0.514598 -0.165774,
+                          0.951057 0.309017 4.72873e-14,
+                          0.959493 0.268162 -0.0863865,
+                          0.959493 0.267944 0.0870601,
+                          1 3.06152e-16 4.97208e-14,
+                          0.951057 0.309017 4.73252e-14,
+                          0.959493 -0.268162 0.0863865,
+                          0.951057 -0.309017 4.72873e-14,
+                          1 3.06152e-16 4.97208e-14,
+                          0.959493 0.227874 0.16567,
+                          1 3.06152e-16 4.97208e-14,
+                          0.959493 0.267944 0.0870601,
+                          0.959493 0.165455 0.22803,
+                          1 3.06152e-16 4.97208e-14,
+                          0.959493 0.227874 0.16567,
+                          0.959493 0.0868076 0.268026,
+                          1 3.06152e-16 4.97208e-14,
+                          0.959493 0.165455 0.22803,
+                          0.959493 -0.000354035 0.281732,
+                          1 3.06152e-16 4.97208e-14,
+                          0.959493 0.0868076 0.268026,
+                          0.959493 -0.0874809 0.267807,
+                          1 3.06152e-16 4.97208e-14,
+                          0.959493 -0.000354035 0.281732,
+                          0.959493 -0.166028 0.227614,
+                          1 3.06152e-16 4.97208e-14,
+                          0.959493 -0.0874809 0.267807,
+                          0.959493 -0.22829 0.165097,
+                          1 3.06152e-16 4.97208e-14,
+                          0.959493 -0.166028 0.227614,
+                          0.959493 -0.268162 0.0863865,
+                          1 3.06152e-16 4.97208e-14,
+                          0.959493 -0.22829 0.165097,
+                          0.841254 0.51418 0.167067,
+                          0.951057 0.309017 4.73252e-14,
+                          0.809017 0.587785 4.0297e-14,
+                          0.841254 0.51418 0.167067,
+                          0.959493 0.267944 0.0870601,
+                          0.951057 0.309017 4.73252e-14,
+                          0.654861 0.718761 0.233539,
+                          0.809017 0.587785 4.0297e-14,
+                          0.587785 0.809017 2.93242e-14,
+                          0.654861 0.718761 0.233539,
+                          0.841254 0.51418 0.167067,
+                          0.809017 0.587785 4.0297e-14,
+                          0.415415 0.865111 0.281092,
+                          0.587785 0.809017 2.93242e-14,
+                          0.309017 0.951057 1.5481e-14,
+                          0.415415 0.865111 0.281092,
+                          0.654861 0.718761 0.233539,
+                          0.587785 0.809017 2.93242e-14,
+                          0.142315 0.941376 0.305872,
+                          0.309017 0.951057 1.5481e-14,
+                          -2.44921e-16 1 1.22461e-16,
+                          0.142315 0.941376 0.305872,
+                          0.415415 0.865111 0.281092,
+                          0.309017 0.951057 1.5481e-14,
+                          -0.142315 0.941376 0.305872,
+                          -2.44921e-16 1 1.22461e-16,
+                          -0.309017 0.951057 -1.52481e-14,
+                          -0.142315 0.941376 0.305872,
+                          0.142315 0.941376 0.305872,
+                          -2.44921e-16 1 1.22461e-16,
+                          -0.415415 0.865111 0.281092,
+                          -0.309017 0.951057 -1.52481e-14,
+                          -0.587785 0.809017 -2.91261e-14,
+                          -0.415415 0.865111 0.281092,
+                          -0.142315 0.941376 0.305872,
+                          -0.309017 0.951057 -1.52481e-14,
+                          -0.654861 0.718761 0.233539,
+                          -0.587785 0.809017 -2.91261e-14,
+                          -0.809017 0.587785 -4.0153e-14,
+                          -0.654861 0.718761 0.233539,
+                          -0.415415 0.865111 0.281092,
+                          -0.587785 0.809017 -2.91261e-14,
+                          -0.841254 0.51418 0.167067,
+                          -0.809017 0.587785 -4.0153e-14,
+                          -0.951057 0.309017 -4.72495e-14,
+                          -0.841254 0.51418 0.167067,
+                          -0.654861 0.718761 0.233539,
+                          -0.809017 0.587785 -4.0153e-14,
+                          -0.959493 0.267944 0.0870601,
+                          -0.951057 0.309017 -4.72495e-14,
+                          -1 -1.83691e-16 -4.97208e-14,
+                          -0.959493 0.267944 0.0870601,
+                          -0.841254 0.51418 0.167067,
+                          -0.951057 0.309017 -4.72495e-14,
+                          -0.959493 -0.268162 0.0863865,
+                          -1 -1.83691e-16 -4.97208e-14,
+                          -0.951057 -0.309017 -4.72873e-14,
+                          -0.959493 0.227874 0.16567,
+                          -0.959493 0.267944 0.0870601,
+                          -1 -1.83691e-16 -4.97208e-14,
+                          -0.959493 0.165455 0.22803,
+                          -0.959493 0.227874 0.16567,
+                          -1 -1.83691e-16 -4.97208e-14,
+                          -0.959493 0.0868076 0.268026,
+                          -0.959493 0.165455 0.22803,
+                          -1 -1.83691e-16 -4.97208e-14,
+                          -0.959493 -0.000354035 0.281732,
+                          -0.959493 0.0868076 0.268026,
+                          -1 -1.83691e-16 -4.97208e-14,
+                          -0.959493 -0.0874809 0.267807,
+                          -0.959493 -0.000354035 0.281732,
+                          -1 -1.83691e-16 -4.97208e-14,
+                          -0.959493 -0.166028 0.227614,
+                          -0.959493 -0.0874809 0.267807,
+                          -1 -1.83691e-16 -4.97208e-14,
+                          -0.959493 -0.22829 0.165097,
+                          -0.959493 -0.166028 0.227614,
+                          -1 -1.83691e-16 -4.97208e-14,
+                          -0.959493 -0.268162 0.0863865,
+                          -0.959493 -0.22829 0.165097,
+                          -1 -1.83691e-16 -4.97208e-14,
+                          -0.841254 -0.514598 0.165774,
+                          -0.951057 -0.309017 -4.72873e-14,
+                          -0.809017 -0.587785 -4.0225e-14,
+                          -0.959493 -0.268162 0.0863865,
+                          -0.951057 -0.309017 -4.72873e-14,
+                          -0.841254 -0.514598 0.165774,
+                          -0.654861 -0.719345 0.231732,
+                          -0.809017 -0.587785 -4.0225e-14,
+                          -0.587785 -0.809017 -2.92252e-14,
+                          -0.841254 -0.514598 0.165774,
+                          -0.809017 -0.587785 -4.0225e-14,
+                          -0.654861 -0.719345 0.231732,
+                          -0.415415 -0.865815 0.278917,
+                          -0.587785 -0.809017 -2.92252e-14,
+                          -0.309017 -0.951057 -1.53646e-14,
+                          -0.654861 -0.719345 0.231732,
+                          -0.587785 -0.809017 -2.92252e-14,
+                          -0.415415 -0.865815 0.278917,
+                          -0.142315 -0.942142 0.303505,
+                          -0.309017 -0.951057 -1.53646e-14,
+                          -2.44921e-16 -1 -1.21777e-29,
+                          -0.415415 -0.865815 0.278917,
+                          -0.309017 -0.951057 -1.53646e-14,
+                          -0.142315 -0.942142 0.303505,
+                          0.142315 -0.942142 0.303505,
+                          -2.44921e-16 -1 -1.21777e-29,
+                          0.309017 -0.951057 1.53646e-14,
+                          -0.142315 -0.942142 0.303505,
+                          -2.44921e-16 -1 -1.21777e-29,
+                          0.142315 -0.942142 0.303505,
+                          0.415415 -0.865815 0.278917,
+                          0.309017 -0.951057 1.53646e-14,
+                          0.587785 -0.809017 2.92252e-14,
+                          0.142315 -0.942142 0.303505,
+                          0.309017 -0.951057 1.53646e-14,
+                          0.415415 -0.865815 0.278917,
+                          0.654861 -0.719345 0.231732,
+                          0.587785 -0.809017 2.92252e-14,
+                          0.809017 -0.587785 4.0225e-14,
+                          0.415415 -0.865815 0.278917,
+                          0.587785 -0.809017 2.92252e-14,
+                          0.654861 -0.719345 0.231732,
+                          0.841254 -0.514598 0.165774,
+                          0.809017 -0.587785 4.0225e-14,
+                          0.951057 -0.309017 4.72873e-14,
+                          0.654861 -0.719345 0.231732,
+                          0.809017 -0.587785 4.0225e-14,
+                          0.841254 -0.514598 0.165774,
+                          0.841254 -0.514598 0.165774,
+                          0.951057 -0.309017 4.72873e-14,
+                          0.959493 -0.268162 0.0863865,
+                          0.959493 -0.227874 -0.16567,
+                          0.959493 -0.267944 -0.0870601,
+                          0.841254 -0.51418 -0.167067,
+                          0.841254 -0.437288 -0.317918,
+                          0.841254 -0.51418 -0.167067,
+                          0.654861 -0.718761 -0.233539,
+                          0.841254 -0.437288 -0.317918,
+                          0.959493 -0.227874 -0.16567,
+                          0.841254 -0.51418 -0.167067,
+                          0.654861 -0.611275 -0.444411,
+                          0.654861 -0.718761 -0.233539,
+                          0.415415 -0.865111 -0.281092,
+                          0.654861 -0.611275 -0.444411,
+                          0.841254 -0.437288 -0.317918,
+                          0.654861 -0.718761 -0.233539,
+                          0.415415 -0.73574 -0.534899,
+                          0.415415 -0.865111 -0.281092,
+                          0.142315 -0.941376 -0.305872,
+                          0.415415 -0.73574 -0.534899,
+                          0.654861 -0.611275 -0.444411,
+                          0.415415 -0.865111 -0.281092,
+                          0.142315 -0.8006 -0.582054,
+                          0.142315 -0.941376 -0.305872,
+                          -0.142315 -0.941376 -0.305872,
+                          0.142315 -0.8006 -0.582054,
+                          0.415415 -0.73574 -0.534899,
+                          0.142315 -0.941376 -0.305872,
+                          -0.142315 -0.8006 -0.582054,
+                          -0.142315 -0.941376 -0.305872,
+                          -0.415415 -0.865111 -0.281092,
+                          -0.142315 -0.8006 -0.582054,
+                          0.142315 -0.8006 -0.582054,
+                          -0.142315 -0.941376 -0.305872,
+                          -0.415415 -0.73574 -0.534899,
+                          -0.415415 -0.865111 -0.281092,
+                          -0.654861 -0.718761 -0.233539,
+                          -0.415415 -0.73574 -0.534899,
+                          -0.142315 -0.8006 -0.582054,
+                          -0.415415 -0.865111 -0.281092,
+                          -0.654861 -0.611275 -0.444411,
+                          -0.654861 -0.718761 -0.233539,
+                          -0.841254 -0.51418 -0.167067,
+                          -0.654861 -0.611275 -0.444411,
+                          -0.415415 -0.73574 -0.534899,
+                          -0.654861 -0.718761 -0.233539,
+                          -0.841254 -0.437288 -0.317918,
+                          -0.841254 -0.51418 -0.167067,
+                          -0.959493 -0.267944 -0.0870601,
+                          -0.841254 -0.437288 -0.317918,
+                          -0.654861 -0.611275 -0.444411,
+                          -0.841254 -0.51418 -0.167067,
+                          -0.959493 -0.227874 -0.16567,
+                          -0.841254 -0.437288 -0.317918,
+                          -0.959493 -0.267944 -0.0870601,
+                          0.959493 -0.165455 -0.22803,
+                          0.959493 -0.227874 -0.16567,
+                          0.841254 -0.437288 -0.317918,
+                          0.841254 -0.317506 -0.437587,
+                          0.841254 -0.437288 -0.317918,
+                          0.654861 -0.611275 -0.444411,
+                          0.841254 -0.317506 -0.437587,
+                          0.959493 -0.165455 -0.22803,
+                          0.841254 -0.437288 -0.317918,
+                          0.654861 -0.443834 -0.611693,
+                          0.654861 -0.611275 -0.444411,
+                          0.415415 -0.73574 -0.534899,
+                          0.654861 -0.443834 -0.611693,
+                          0.841254 -0.317506 -0.437587,
+                          0.654861 -0.611275 -0.444411,
+                          0.415415 -0.534206 -0.736244,
+                          0.415415 -0.73574 -0.534899,
+                          0.142315 -0.8006 -0.582054,
+                          0.415415 -0.534206 -0.736244,
+                          0.654861 -0.443834 -0.611693,
+                          0.415415 -0.73574 -0.534899,
+                          0.142315 -0.581299 -0.801148,
+                          0.142315 -0.8006 -0.582054,
+                          -0.142315 -0.8006 -0.582054,
+                          0.142315 -0.581299 -0.801148,
+                          0.415415 -0.534206 -0.736244,
+                          0.142315 -0.8006 -0.582054,
+                          -0.142315 -0.581299 -0.801148,
+                          -0.142315 -0.8006 -0.582054,
+                          -0.415415 -0.73574 -0.534899,
+                          -0.142315 -0.581299 -0.801148,
+                          0.142315 -0.581299 -0.801148,
+                          -0.142315 -0.8006 -0.582054,
+                          -0.415415 -0.534206 -0.736244,
+                          -0.415415 -0.73574 -0.534899,
+                          -0.654861 -0.611275 -0.444411,
+                          -0.415415 -0.534206 -0.736244,
+                          -0.142315 -0.581299 -0.801148,
+                          -0.415415 -0.73574 -0.534899,
+                          -0.654861 -0.443834 -0.611693,
+                          -0.654861 -0.611275 -0.444411,
+                          -0.841254 -0.437288 -0.317918,
+                          -0.654861 -0.443834 -0.611693,
+                          -0.415415 -0.534206 -0.736244,
+                          -0.654861 -0.611275 -0.444411,
+                          -0.841254 -0.317506 -0.437587,
+                          -0.841254 -0.437288 -0.317918,
+                          -0.959493 -0.227874 -0.16567,
+                          -0.841254 -0.317506 -0.437587,
+                          -0.654861 -0.443834 -0.611693,
+                          -0.841254 -0.437288 -0.317918,
+                          -0.959493 -0.165455 -0.22803,
+                          -0.841254 -0.317506 -0.437587,
+                          -0.959493 -0.227874 -0.16567,
+                          0.959493 -0.0868076 -0.268026,
+                          0.959493 -0.165455 -0.22803,
+                          0.841254 -0.317506 -0.437587,
+                          0.841254 -0.166583 -0.514337,
+                          0.841254 -0.317506 -0.437587,
+                          0.654861 -0.443834 -0.611693,
+                          0.841254 -0.166583 -0.514337,
+                          0.959493 -0.0868076 -0.268026,
+                          0.841254 -0.317506 -0.437587,
+                          0.654861 -0.232862 -0.71898,
+                          0.654861 -0.443834 -0.611693,
+                          0.415415 -0.534206 -0.736244,
+                          0.654861 -0.232862 -0.71898,
+                          0.841254 -0.166583 -0.514337,
+                          0.654861 -0.443834 -0.611693,
+                          0.415415 -0.280276 -0.865376,
+                          0.415415 -0.534206 -0.736244,
+                          0.142315 -0.581299 -0.801148,
+                          0.415415 -0.280276 -0.865376,
+                          0.654861 -0.232862 -0.71898,
+                          0.415415 -0.534206 -0.736244,
+                          0.142315 -0.304984 -0.941664,
+                          0.142315 -0.581299 -0.801148,
+                          -0.142315 -0.581299 -0.801148,
+                          0.142315 -0.304984 -0.941664,
+                          0.415415 -0.280276 -0.865376,
+                          0.142315 -0.581299 -0.801148,
+                          -0.142315 -0.304984 -0.941664,
+                          -0.142315 -0.581299 -0.801148,
+                          -0.415415 -0.534206 -0.736244,
+                          -0.142315 -0.304984 -0.941664,
+                          0.142315 -0.304984 -0.941664,
+                          -0.142315 -0.581299 -0.801148,
+                          -0.415415 -0.280276 -0.865376,
+                          -0.415415 -0.534206 -0.736244,
+                          -0.654861 -0.443834 -0.611693,
+                          -0.415415 -0.280276 -0.865376,
+                          -0.142315 -0.304984 -0.941664,
+                          -0.415415 -0.534206 -0.736244,
+                          -0.654861 -0.232862 -0.71898,
+                          -0.654861 -0.443834 -0.611693,
+                          -0.841254 -0.317506 -0.437587,
+                          -0.654861 -0.232862 -0.71898,
+                          -0.415415 -0.280276 -0.865376,
+                          -0.654861 -0.443834 -0.611693,
+                          -0.841254 -0.166583 -0.514337,
+                          -0.841254 -0.317506 -0.437587,
+                          -0.959493 -0.165455 -0.22803,
+                          -0.841254 -0.166583 -0.514337,
+                          -0.654861 -0.232862 -0.71898,
+                          -0.841254 -0.317506 -0.437587,
+                          -0.959493 -0.0868076 -0.268026,
+                          -0.841254 -0.166583 -0.514337,
+                          -0.959493 -0.165455 -0.22803,
+                          0.959493 0.000354035 -0.281732,
+                          0.959493 -0.0868076 -0.268026,
+                          0.841254 -0.166583 -0.514337,
+                          0.841254 0.000679389 -0.54064,
+                          0.841254 -0.166583 -0.514337,
+                          0.654861 -0.232862 -0.71898,
+                          0.841254 0.000679389 -0.54064,
+                          0.959493 0.000354035 -0.281732,
+                          0.841254 -0.166583 -0.514337,
+                          0.654861 0.000949703 -0.755749,
+                          0.654861 -0.232862 -0.71898,
+                          0.415415 -0.280276 -0.865376,
+                          0.654861 0.000949703 -0.755749,
+                          0.841254 0.000679389 -0.54064,
+                          0.654861 -0.232862 -0.71898,
+                          0.415415 0.00114308 -0.909631,
+                          0.415415 -0.280276 -0.865376,
+                          0.142315 -0.304984 -0.941664,
+                          0.415415 0.00114308 -0.909631,
+                          0.654861 0.000949703 -0.755749,
+                          0.415415 -0.280276 -0.865376,
+                          0.142315 0.00124385 -0.989821,
+                          0.142315 -0.304984 -0.941664,
+                          -0.142315 -0.304984 -0.941664,
+                          0.142315 0.00124385 -0.989821,
+                          0.415415 0.00114308 -0.909631,
+                          0.142315 -0.304984 -0.941664,
+                          -0.142315 0.00124385 -0.989821,
+                          -0.142315 -0.304984 -0.941664,
+                          -0.415415 -0.280276 -0.865376,
+                          -0.142315 0.00124385 -0.989821,
+                          0.142315 0.00124385 -0.989821,
+                          -0.142315 -0.304984 -0.941664,
+                          -0.415415 0.00114308 -0.909631,
+                          -0.415415 -0.280276 -0.865376,
+                          -0.654861 -0.232862 -0.71898,
+                          -0.415415 0.00114308 -0.909631,
+                          -0.142315 0.00124385 -0.989821,
+                          -0.415415 -0.280276 -0.865376,
+                          -0.654861 0.000949703 -0.755749,
+                          -0.654861 -0.232862 -0.71898,
+                          -0.841254 -0.166583 -0.514337,
+                          -0.654861 0.000949703 -0.755749,
+                          -0.415415 0.00114308 -0.909631,
+                          -0.654861 -0.232862 -0.71898,
+                          -0.841254 0.000679389 -0.54064,
+                          -0.841254 -0.166583 -0.514337,
+                          -0.959493 -0.0868076 -0.268026,
+                          -0.841254 0.000679389 -0.54064,
+                          -0.654861 0.000949703 -0.755749,
+                          -0.841254 -0.166583 -0.514337,
+                          -0.959493 0.000354035 -0.281732,
+                          -0.841254 0.000679389 -0.54064,
+                          -0.959493 -0.0868076 -0.268026,
+                          0.959493 0.0874809 -0.267807,
+                          0.959493 0.000354035 -0.281732,
+                          0.841254 0.000679389 -0.54064,
+                          0.841254 0.167875 -0.513917,
+                          0.841254 0.000679389 -0.54064,
+                          0.654861 0.000949703 -0.755749,
+                          0.841254 0.167875 -0.513917,
+                          0.959493 0.0874809 -0.267807,
+                          0.841254 0.000679389 -0.54064,
+                          0.654861 0.234668 -0.718393,
+                          0.654861 0.000949703 -0.755749,
+                          0.415415 0.00114308 -0.909631,
+                          0.654861 0.234668 -0.718393,
+                          0.841254 0.167875 -0.513917,
+                          0.654861 0.000949703 -0.755749,
+                          0.415415 0.28245 -0.864669,
+                          0.415415 0.00114308 -0.909631,
+                          0.142315 0.00124385 -0.989821,
+                          0.415415 0.28245 -0.864669,
+                          0.654861 0.234668 -0.718393,
+                          0.415415 0.00114308 -0.909631,
+                          0.142315 0.30735 -0.940894,
+                          0.142315 0.00124385 -0.989821,
+                          -0.142315 0.00124385 -0.989821,
+                          0.142315 0.30735 -0.940894,
+                          0.415415 0.28245 -0.864669,
+                          0.142315 0.00124385 -0.989821,
+                          -0.142315 0.30735 -0.940894,
+                          -0.142315 0.00124385 -0.989821,
+                          -0.415415 0.00114308 -0.909631,
+                          -0.142315 0.30735 -0.940894,
+                          0.142315 0.30735 -0.940894,
+                          -0.142315 0.00124385 -0.989821,
+                          -0.415415 0.28245 -0.864669,
+                          -0.415415 0.00114308 -0.909631,
+                          -0.654861 0.000949703 -0.755749,
+                          -0.415415 0.28245 -0.864669,
+                          -0.142315 0.30735 -0.940894,
+                          -0.415415 0.00114308 -0.909631,
+                          -0.654861 0.234668 -0.718393,
+                          -0.654861 0.000949703 -0.755749,
+                          -0.841254 0.000679389 -0.54064,
+                          -0.654861 0.234668 -0.718393,
+                          -0.415415 0.28245 -0.864669,
+                          -0.654861 0.000949703 -0.755749,
+                          -0.841254 0.167875 -0.513917,
+                          -0.841254 0.000679389 -0.54064,
+                          -0.959493 0.000354035 -0.281732,
+                          -0.841254 0.167875 -0.513917,
+                          -0.654861 0.234668 -0.718393,
+                          -0.841254 0.000679389 -0.54064,
+                          -0.959493 0.0874809 -0.267807,
+                          -0.841254 0.167875 -0.513917,
+                          -0.959493 0.000354035 -0.281732,
+                          0.959493 0.166028 -0.227614,
+                          0.959493 0.0874809 -0.267807,
+                          0.841254 0.167875 -0.513917,
+                          0.841254 0.318605 -0.436788,
+                          0.841254 0.167875 -0.513917,
+                          0.654861 0.234668 -0.718393,
+                          0.841254 0.318605 -0.436788,
+                          0.959493 0.166028 -0.227614,
+                          0.841254 0.167875 -0.513917,
+                          0.654861 0.44537 -0.610576,
+                          0.654861 0.234668 -0.718393,
+                          0.415415 0.28245 -0.864669,
+                          0.654861 0.44537 -0.610576,
+                          0.841254 0.318605 -0.436788,
+                          0.654861 0.234668 -0.718393,
+                          0.415415 0.536054 -0.734899,
+                          0.415415 0.28245 -0.864669,
+                          0.142315 0.30735 -0.940894,
+                          0.415415 0.536054 -0.734899,
+                          0.654861 0.44537 -0.610576,
+                          0.415415 0.28245 -0.864669,
+                          0.142315 0.583311 -0.799684,
+                          0.142315 0.30735 -0.940894,
+                          -0.142315 0.30735 -0.940894,
+                          0.142315 0.583311 -0.799684,
+                          0.415415 0.536054 -0.734899,
+                          0.142315 0.30735 -0.940894,
+                          -0.142315 0.583311 -0.799684,
+                          -0.142315 0.30735 -0.940894,
+                          -0.415415 0.28245 -0.864669,
+                          -0.142315 0.583311 -0.799684,
+                          0.142315 0.583311 -0.799684,
+                          -0.142315 0.30735 -0.940894,
+                          -0.415415 0.536054 -0.734899,
+                          -0.415415 0.28245 -0.864669,
+                          -0.654861 0.234668 -0.718393,
+                          -0.415415 0.536054 -0.734899,
+                          -0.142315 0.583311 -0.799684,
+                          -0.415415 0.28245 -0.864669,
+                          -0.654861 0.44537 -0.610576,
+                          -0.654861 0.234668 -0.718393,
+                          -0.841254 0.167875 -0.513917,
+                          -0.654861 0.44537 -0.610576,
+                          -0.415415 0.536054 -0.734899,
+                          -0.654861 0.234668 -0.718393,
+                          -0.841254 0.318605 -0.436788,
+                          -0.841254 0.167875 -0.513917,
+                          -0.959493 0.0874809 -0.267807,
+                          -0.841254 0.318605 -0.436788,
+                          -0.654861 0.44537 -0.610576,
+                          -0.841254 0.167875 -0.513917,
+                          -0.959493 0.166028 -0.227614,
+                          -0.841254 0.318605 -0.436788,
+                          -0.959493 0.0874809 -0.267807,
+                          0.959493 0.22829 -0.165097,
+                          0.959493 0.166028 -0.227614,
+                          0.841254 0.318605 -0.436788,
+                          0.841254 0.438085 -0.316818,
+                          0.841254 0.318605 -0.436788,
+                          0.654861 0.44537 -0.610576,
+                          0.841254 0.438085 -0.316818,
+                          0.959493 0.22829 -0.165097,
+                          0.841254 0.318605 -0.436788,
+                          0.654861 0.61239 -0.442873,
+                          0.654861 0.44537 -0.610576,
+                          0.415415 0.536054 -0.734899,
+                          0.654861 0.61239 -0.442873,
+                          0.841254 0.438085 -0.316818,
+                          0.654861 0.44537 -0.610576,
+                          0.415415 0.737082 -0.533049,
+                          0.415415 0.536054 -0.734899,
+                          0.142315 0.583311 -0.799684,
+                          0.415415 0.737082 -0.533049,
+                          0.654861 0.61239 -0.442873,
+                          0.415415 0.536054 -0.734899,
+                          0.142315 0.80206 -0.58004,
+                          0.142315 0.583311 -0.799684,
+                          -0.142315 0.583311 -0.799684,
+                          0.142315 0.80206 -0.58004,
+                          0.415415 0.737082 -0.533049,
+                          0.142315 0.583311 -0.799684,
+                          -0.142315 0.80206 -0.58004,
+                          -0.142315 0.583311 -0.799684,
+                          -0.415415 0.536054 -0.734899,
+                          -0.142315 0.80206 -0.58004,
+                          0.142315 0.80206 -0.58004,
+                          -0.142315 0.583311 -0.799684,
+                          -0.415415 0.737082 -0.533049,
+                          -0.415415 0.536054 -0.734899,
+                          -0.654861 0.44537 -0.610576,
+                          -0.415415 0.737082 -0.533049,
+                          -0.142315 0.80206 -0.58004,
+                          -0.415415 0.536054 -0.734899,
+                          -0.654861 0.61239 -0.442873,
+                          -0.654861 0.44537 -0.610576,
+                          -0.841254 0.318605 -0.436788,
+                          -0.654861 0.61239 -0.442873,
+                          -0.415415 0.737082 -0.533049,
+                          -0.654861 0.44537 -0.610576,
+                          -0.841254 0.438085 -0.316818,
+                          -0.841254 0.318605 -0.436788,
+                          -0.959493 0.166028 -0.227614,
+                          -0.841254 0.438085 -0.316818,
+                          -0.654861 0.61239 -0.442873,
+                          -0.841254 0.318605 -0.436788,
+                          -0.959493 0.22829 -0.165097,
+                          -0.841254 0.438085 -0.316818,
+                          -0.959493 0.166028 -0.227614,
+                          0.959493 0.268162 -0.0863865,
+                          0.959493 0.22829 -0.165097,
+                          0.841254 0.438085 -0.316818,
+                          0.841254 0.514598 -0.165774,
+                          0.841254 0.438085 -0.316818,
+                          0.654861 0.61239 -0.442873,
+                          0.841254 0.514598 -0.165774,
+                          0.959493 0.268162 -0.0863865,
+                          0.841254 0.438085 -0.316818,
+                          0.654861 0.719345 -0.231732,
+                          0.654861 0.61239 -0.442873,
+                          0.415415 0.737082 -0.533049,
+                          0.654861 0.719345 -0.231732,
+                          0.841254 0.514598 -0.165774,
+                          0.654861 0.61239 -0.442873,
+                          0.415415 0.865815 -0.278917,
+                          0.415415 0.737082 -0.533049,
+                          0.142315 0.80206 -0.58004,
+                          0.415415 0.865815 -0.278917,
+                          0.654861 0.719345 -0.231732,
+                          0.415415 0.737082 -0.533049,
+                          0.142315 0.942142 -0.303505,
+                          0.142315 0.80206 -0.58004,
+                          -0.142315 0.80206 -0.58004,
+                          0.142315 0.942142 -0.303505,
+                          0.415415 0.865815 -0.278917,
+                          0.142315 0.80206 -0.58004,
+                          -0.142315 0.942142 -0.303505,
+                          -0.142315 0.80206 -0.58004,
+                          -0.415415 0.737082 -0.533049,
+                          -0.142315 0.942142 -0.303505,
+                          0.142315 0.942142 -0.303505,
+                          -0.142315 0.80206 -0.58004,
+                          -0.415415 0.865815 -0.278917,
+                          -0.415415 0.737082 -0.533049,
+                          -0.654861 0.61239 -0.442873,
+                          -0.415415 0.865815 -0.278917,
+                          -0.142315 0.942142 -0.303505,
+                          -0.415415 0.737082 -0.533049,
+                          -0.654861 0.719345 -0.231732,
+                          -0.654861 0.61239 -0.442873,
+                          -0.841254 0.438085 -0.316818,
+                          -0.654861 0.719345 -0.231732,
+                          -0.415415 0.865815 -0.278917,
+                          -0.654861 0.61239 -0.442873,
+                          -0.841254 0.514598 -0.165774,
+                          -0.841254 0.438085 -0.316818,
+                          -0.959493 0.22829 -0.165097,
+                          -0.841254 0.514598 -0.165774,
+                          -0.654861 0.719345 -0.231732,
+                          -0.841254 0.438085 -0.316818,
+                          -0.959493 0.268162 -0.0863865,
+                          -0.841254 0.514598 -0.165774,
+                          -0.959493 0.22829 -0.165097,
+                          0.959493 0.227874 0.16567,
+                          0.959493 0.267944 0.0870601,
+                          0.841254 0.51418 0.167067,
+                          0.841254 0.437288 0.317918,
+                          0.841254 0.51418 0.167067,
+                          0.654861 0.718761 0.233539,
+                          0.841254 0.437288 0.317918,
+                          0.959493 0.227874 0.16567,
+                          0.841254 0.51418 0.167067,
+                          0.654861 0.611275 0.444411,
+                          0.654861 0.718761 0.233539,
+                          0.415415 0.865111 0.281092,
+                          0.654861 0.611275 0.444411,
+                          0.841254 0.437288 0.317918,
+                          0.654861 0.718761 0.233539,
+                          0.415415 0.73574 0.534899,
+                          0.415415 0.865111 0.281092,
+                          0.142315 0.941376 0.305872,
+                          0.415415 0.73574 0.534899,
+                          0.654861 0.611275 0.444411,
+                          0.415415 0.865111 0.281092,
+                          0.142315 0.8006 0.582054,
+                          0.142315 0.941376 0.305872,
+                          -0.142315 0.941376 0.305872,
+                          0.142315 0.8006 0.582054,
+                          0.415415 0.73574 0.534899,
+                          0.142315 0.941376 0.305872,
+                          -0.142315 0.8006 0.582054,
+                          -0.142315 0.941376 0.305872,
+                          -0.415415 0.865111 0.281092,
+                          -0.142315 0.8006 0.582054,
+                          0.142315 0.8006 0.582054,
+                          -0.142315 0.941376 0.305872,
+                          -0.415415 0.73574 0.534899,
+                          -0.415415 0.865111 0.281092,
+                          -0.654861 0.718761 0.233539,
+                          -0.415415 0.73574 0.534899,
+                          -0.142315 0.8006 0.582054,
+                          -0.415415 0.865111 0.281092,
+                          -0.654861 0.611275 0.444411,
+                          -0.654861 0.718761 0.233539,
+                          -0.841254 0.51418 0.167067,
+                          -0.654861 0.611275 0.444411,
+                          -0.415415 0.73574 0.534899,
+                          -0.654861 0.718761 0.233539,
+                          -0.841254 0.437288 0.317918,
+                          -0.841254 0.51418 0.167067,
+                          -0.959493 0.267944 0.0870601,
+                          -0.841254 0.437288 0.317918,
+                          -0.654861 0.611275 0.444411,
+                          -0.841254 0.51418 0.167067,
+                          -0.959493 0.227874 0.16567,
+                          -0.841254 0.437288 0.317918,
+                          -0.959493 0.267944 0.0870601,
+                          0.959493 0.165455 0.22803,
+                          0.959493 0.227874 0.16567,
+                          0.841254 0.437288 0.317918,
+                          0.841254 0.317506 0.437587,
+                          0.841254 0.437288 0.317918,
+                          0.654861 0.611275 0.444411,
+                          0.841254 0.317506 0.437587,
+                          0.959493 0.165455 0.22803,
+                          0.841254 0.437288 0.317918,
+                          0.654861 0.443834 0.611693,
+                          0.654861 0.611275 0.444411,
+                          0.415415 0.73574 0.534899,
+                          0.654861 0.443834 0.611693,
+                          0.841254 0.317506 0.437587,
+                          0.654861 0.611275 0.444411,
+                          0.415415 0.534206 0.736244,
+                          0.415415 0.73574 0.534899,
+                          0.142315 0.8006 0.582054,
+                          0.415415 0.534206 0.736244,
+                          0.654861 0.443834 0.611693,
+                          0.415415 0.73574 0.534899,
+                          0.142315 0.581299 0.801148,
+                          0.142315 0.8006 0.582054,
+                          -0.142315 0.8006 0.582054,
+                          0.142315 0.581299 0.801148,
+                          0.415415 0.534206 0.736244,
+                          0.142315 0.8006 0.582054,
+                          -0.142315 0.581299 0.801148,
+                          -0.142315 0.8006 0.582054,
+                          -0.415415 0.73574 0.534899,
+                          -0.142315 0.581299 0.801148,
+                          0.142315 0.581299 0.801148,
+                          -0.142315 0.8006 0.582054,
+                          -0.415415 0.534206 0.736244,
+                          -0.415415 0.73574 0.534899,
+                          -0.654861 0.611275 0.444411,
+                          -0.415415 0.534206 0.736244,
+                          -0.142315 0.581299 0.801148,
+                          -0.415415 0.73574 0.534899,
+                          -0.654861 0.443834 0.611693,
+                          -0.654861 0.611275 0.444411,
+                          -0.841254 0.437288 0.317918,
+                          -0.654861 0.443834 0.611693,
+                          -0.415415 0.534206 0.736244,
+                          -0.654861 0.611275 0.444411,
+                          -0.841254 0.317506 0.437587,
+                          -0.841254 0.437288 0.317918,
+                          -0.959493 0.227874 0.16567,
+                          -0.841254 0.317506 0.437587,
+                          -0.654861 0.443834 0.611693,
+                          -0.841254 0.437288 0.317918,
+                          -0.959493 0.165455 0.22803,
+                          -0.841254 0.317506 0.437587,
+                          -0.959493 0.227874 0.16567,
+                          0.959493 0.0868076 0.268026,
+                          0.959493 0.165455 0.22803,
+                          0.841254 0.317506 0.437587,
+                          0.841254 0.166583 0.514337,
+                          0.841254 0.317506 0.437587,
+                          0.654861 0.443834 0.611693,
+                          0.841254 0.166583 0.514337,
+                          0.959493 0.0868076 0.268026,
+                          0.841254 0.317506 0.437587,
+                          0.654861 0.232862 0.71898,
+                          0.654861 0.443834 0.611693,
+                          0.415415 0.534206 0.736244,
+                          0.654861 0.232862 0.71898,
+                          0.841254 0.166583 0.514337,
+                          0.654861 0.443834 0.611693,
+                          0.415415 0.280276 0.865376,
+                          0.415415 0.534206 0.736244,
+                          0.142315 0.581299 0.801148,
+                          0.415415 0.280276 0.865376,
+                          0.654861 0.232862 0.71898,
+                          0.415415 0.534206 0.736244,
+                          0.142315 0.304984 0.941664,
+                          0.142315 0.581299 0.801148,
+                          -0.142315 0.581299 0.801148,
+                          0.142315 0.304984 0.941664,
+                          0.415415 0.280276 0.865376,
+                          0.142315 0.581299 0.801148,
+                          -0.142315 0.304984 0.941664,
+                          -0.142315 0.581299 0.801148,
+                          -0.415415 0.534206 0.736244,
+                          -0.142315 0.304984 0.941664,
+                          0.142315 0.304984 0.941664,
+                          -0.142315 0.581299 0.801148,
+                          -0.415415 0.280276 0.865376,
+                          -0.415415 0.534206 0.736244,
+                          -0.654861 0.443834 0.611693,
+                          -0.415415 0.280276 0.865376,
+                          -0.142315 0.304984 0.941664,
+                          -0.415415 0.534206 0.736244,
+                          -0.654861 0.232862 0.71898,
+                          -0.654861 0.443834 0.611693,
+                          -0.841254 0.317506 0.437587,
+                          -0.654861 0.232862 0.71898,
+                          -0.415415 0.280276 0.865376,
+                          -0.654861 0.443834 0.611693,
+                          -0.841254 0.166583 0.514337,
+                          -0.841254 0.317506 0.437587,
+                          -0.959493 0.165455 0.22803,
+                          -0.841254 0.166583 0.514337,
+                          -0.654861 0.232862 0.71898,
+                          -0.841254 0.317506 0.437587,
+                          -0.959493 0.0868076 0.268026,
+                          -0.841254 0.166583 0.514337,
+                          -0.959493 0.165455 0.22803,
+                          0.959493 -0.000354035 0.281732,
+                          0.959493 0.0868076 0.268026,
+                          0.841254 0.166583 0.514337,
+                          0.841254 -0.000679389 0.54064,
+                          0.841254 0.166583 0.514337,
+                          0.654861 0.232862 0.71898,
+                          0.841254 -0.000679389 0.54064,
+                          0.959493 -0.000354035 0.281732,
+                          0.841254 0.166583 0.514337,
+                          0.654861 -0.000949703 0.755749,
+                          0.654861 0.232862 0.71898,
+                          0.415415 0.280276 0.865376,
+                          0.654861 -0.000949703 0.755749,
+                          0.841254 -0.000679389 0.54064,
+                          0.654861 0.232862 0.71898,
+                          0.415415 -0.00114308 0.909631,
+                          0.415415 0.280276 0.865376,
+                          0.142315 0.304984 0.941664,
+                          0.415415 -0.00114308 0.909631,
+                          0.654861 -0.000949703 0.755749,
+                          0.415415 0.280276 0.865376,
+                          0.142315 -0.00124385 0.989821,
+                          0.142315 0.304984 0.941664,
+                          -0.142315 0.304984 0.941664,
+                          0.142315 -0.00124385 0.989821,
+                          0.415415 -0.00114308 0.909631,
+                          0.142315 0.304984 0.941664,
+                          -0.142315 -0.00124385 0.989821,
+                          -0.142315 0.304984 0.941664,
+                          -0.415415 0.280276 0.865376,
+                          -0.142315 -0.00124385 0.989821,
+                          0.142315 -0.00124385 0.989821,
+                          -0.142315 0.304984 0.941664,
+                          -0.415415 -0.00114308 0.909631,
+                          -0.415415 0.280276 0.865376,
+                          -0.654861 0.232862 0.71898,
+                          -0.415415 -0.00114308 0.909631,
+                          -0.142315 -0.00124385 0.989821,
+                          -0.415415 0.280276 0.865376,
+                          -0.654861 -0.000949703 0.755749,
+                          -0.654861 0.232862 0.71898,
+                          -0.841254 0.166583 0.514337,
+                          -0.654861 -0.000949703 0.755749,
+                          -0.415415 -0.00114308 0.909631,
+                          -0.654861 0.232862 0.71898,
+                          -0.841254 -0.000679389 0.54064,
+                          -0.841254 0.166583 0.514337,
+                          -0.959493 0.0868076 0.268026,
+                          -0.841254 -0.000679389 0.54064,
+                          -0.654861 -0.000949703 0.755749,
+                          -0.841254 0.166583 0.514337,
+                          -0.959493 -0.000354035 0.281732,
+                          -0.841254 -0.000679389 0.54064,
+                          -0.959493 0.0868076 0.268026,
+                          0.959493 -0.0874809 0.267807,
+                          0.959493 -0.000354035 0.281732,
+                          0.841254 -0.000679389 0.54064,
+                          0.841254 -0.167875 0.513917,
+                          0.841254 -0.000679389 0.54064,
+                          0.654861 -0.000949703 0.755749,
+                          0.841254 -0.167875 0.513917,
+                          0.959493 -0.0874809 0.267807,
+                          0.841254 -0.000679389 0.54064,
+                          0.654861 -0.234668 0.718393,
+                          0.654861 -0.000949703 0.755749,
+                          0.415415 -0.00114308 0.909631,
+                          0.654861 -0.234668 0.718393,
+                          0.841254 -0.167875 0.513917,
+                          0.654861 -0.000949703 0.755749,
+                          0.415415 -0.28245 0.864669,
+                          0.415415 -0.00114308 0.909631,
+                          0.142315 -0.00124385 0.989821,
+                          0.415415 -0.28245 0.864669,
+                          0.654861 -0.234668 0.718393,
+                          0.415415 -0.00114308 0.909631,
+                          0.142315 -0.30735 0.940894,
+                          0.142315 -0.00124385 0.989821,
+                          -0.142315 -0.00124385 0.989821,
+                          0.142315 -0.30735 0.940894,
+                          0.415415 -0.28245 0.864669,
+                          0.142315 -0.00124385 0.989821,
+                          -0.142315 -0.30735 0.940894,
+                          -0.142315 -0.00124385 0.989821,
+                          -0.415415 -0.00114308 0.909631,
+                          -0.142315 -0.30735 0.940894,
+                          0.142315 -0.30735 0.940894,
+                          -0.142315 -0.00124385 0.989821,
+                          -0.415415 -0.28245 0.864669,
+                          -0.415415 -0.00114308 0.909631,
+                          -0.654861 -0.000949703 0.755749,
+                          -0.415415 -0.28245 0.864669,
+                          -0.142315 -0.30735 0.940894,
+                          -0.415415 -0.00114308 0.909631,
+                          -0.654861 -0.234668 0.718393,
+                          -0.654861 -0.000949703 0.755749,
+                          -0.841254 -0.000679389 0.54064,
+                          -0.654861 -0.234668 0.718393,
+                          -0.415415 -0.28245 0.864669,
+                          -0.654861 -0.000949703 0.755749,
+                          -0.841254 -0.167875 0.513917,
+                          -0.841254 -0.000679389 0.54064,
+                          -0.959493 -0.000354035 0.281732,
+                          -0.841254 -0.167875 0.513917,
+                          -0.654861 -0.234668 0.718393,
+                          -0.841254 -0.000679389 0.54064,
+                          -0.959493 -0.0874809 0.267807,
+                          -0.841254 -0.167875 0.513917,
+                          -0.959493 -0.000354035 0.281732,
+                          0.959493 -0.166028 0.227614,
+                          0.959493 -0.0874809 0.267807,
+                          0.841254 -0.167875 0.513917,
+                          0.841254 -0.318605 0.436788,
+                          0.841254 -0.167875 0.513917,
+                          0.654861 -0.234668 0.718393,
+                          0.841254 -0.318605 0.436788,
+                          0.959493 -0.166028 0.227614,
+                          0.841254 -0.167875 0.513917,
+                          0.654861 -0.44537 0.610576,
+                          0.654861 -0.234668 0.718393,
+                          0.415415 -0.28245 0.864669,
+                          0.654861 -0.44537 0.610576,
+                          0.841254 -0.318605 0.436788,
+                          0.654861 -0.234668 0.718393,
+                          0.415415 -0.536054 0.734899,
+                          0.415415 -0.28245 0.864669,
+                          0.142315 -0.30735 0.940894,
+                          0.415415 -0.536054 0.734899,
+                          0.654861 -0.44537 0.610576,
+                          0.415415 -0.28245 0.864669,
+                          0.142315 -0.583311 0.799684,
+                          0.142315 -0.30735 0.940894,
+                          -0.142315 -0.30735 0.940894,
+                          0.142315 -0.583311 0.799684,
+                          0.415415 -0.536054 0.734899,
+                          0.142315 -0.30735 0.940894,
+                          -0.142315 -0.583311 0.799684,
+                          -0.142315 -0.30735 0.940894,
+                          -0.415415 -0.28245 0.864669,
+                          -0.142315 -0.583311 0.799684,
+                          0.142315 -0.583311 0.799684,
+                          -0.142315 -0.30735 0.940894,
+                          -0.415415 -0.536054 0.734899,
+                          -0.415415 -0.28245 0.864669,
+                          -0.654861 -0.234668 0.718393,
+                          -0.415415 -0.536054 0.734899,
+                          -0.142315 -0.583311 0.799684,
+                          -0.415415 -0.28245 0.864669,
+                          -0.654861 -0.44537 0.610576,
+                          -0.654861 -0.234668 0.718393,
+                          -0.841254 -0.167875 0.513917,
+                          -0.654861 -0.44537 0.610576,
+                          -0.415415 -0.536054 0.734899,
+                          -0.654861 -0.234668 0.718393,
+                          -0.841254 -0.318605 0.436788,
+                          -0.841254 -0.167875 0.513917,
+                          -0.959493 -0.0874809 0.267807,
+                          -0.841254 -0.318605 0.436788,
+                          -0.654861 -0.44537 0.610576,
+                          -0.841254 -0.167875 0.513917,
+                          -0.959493 -0.166028 0.227614,
+                          -0.841254 -0.318605 0.436788,
+                          -0.959493 -0.0874809 0.267807,
+                          0.959493 -0.22829 0.165097,
+                          0.959493 -0.166028 0.227614,
+                          0.841254 -0.318605 0.436788,
+                          0.841254 -0.438085 0.316818,
+                          0.841254 -0.318605 0.436788,
+                          0.654861 -0.44537 0.610576,
+                          0.841254 -0.438085 0.316818,
+                          0.959493 -0.22829 0.165097,
+                          0.841254 -0.318605 0.436788,
+                          0.654861 -0.61239 0.442873,
+                          0.654861 -0.44537 0.610576,
+                          0.415415 -0.536054 0.734899,
+                          0.654861 -0.61239 0.442873,
+                          0.841254 -0.438085 0.316818,
+                          0.654861 -0.44537 0.610576,
+                          0.415415 -0.737082 0.533049,
+                          0.415415 -0.536054 0.734899,
+                          0.142315 -0.583311 0.799684,
+                          0.415415 -0.737082 0.533049,
+                          0.654861 -0.61239 0.442873,
+                          0.415415 -0.536054 0.734899,
+                          0.142315 -0.80206 0.58004,
+                          0.142315 -0.583311 0.799684,
+                          -0.142315 -0.583311 0.799684,
+                          0.142315 -0.80206 0.58004,
+                          0.415415 -0.737082 0.533049,
+                          0.142315 -0.583311 0.799684,
+                          -0.142315 -0.80206 0.58004,
+                          -0.142315 -0.583311 0.799684,
+                          -0.415415 -0.536054 0.734899,
+                          -0.142315 -0.80206 0.58004,
+                          0.142315 -0.80206 0.58004,
+                          -0.142315 -0.583311 0.799684,
+                          -0.415415 -0.737082 0.533049,
+                          -0.415415 -0.536054 0.734899,
+                          -0.654861 -0.44537 0.610576,
+                          -0.415415 -0.737082 0.533049,
+                          -0.142315 -0.80206 0.58004,
+                          -0.415415 -0.536054 0.734899,
+                          -0.654861 -0.61239 0.442873,
+                          -0.654861 -0.44537 0.610576,
+                          -0.841254 -0.318605 0.436788,
+                          -0.654861 -0.61239 0.442873,
+                          -0.415415 -0.737082 0.533049,
+                          -0.654861 -0.44537 0.610576,
+                          -0.841254 -0.438085 0.316818,
+                          -0.841254 -0.318605 0.436788,
+                          -0.959493 -0.166028 0.227614,
+                          -0.841254 -0.438085 0.316818,
+                          -0.654861 -0.61239 0.442873,
+                          -0.841254 -0.318605 0.436788,
+                          -0.959493 -0.22829 0.165097,
+                          -0.841254 -0.438085 0.316818,
+                          -0.959493 -0.166028 0.227614,
+                          0.959493 -0.268162 0.0863865,
+                          0.959493 -0.22829 0.165097,
+                          0.841254 -0.438085 0.316818,
+                          0.841254 -0.514598 0.165774,
+                          0.841254 -0.438085 0.316818,
+                          0.654861 -0.61239 0.442873,
+                          0.841254 -0.514598 0.165774,
+                          0.959493 -0.268162 0.0863865,
+                          0.841254 -0.438085 0.316818,
+                          0.654861 -0.719345 0.231732,
+                          0.654861 -0.61239 0.442873,
+                          0.415415 -0.737082 0.533049,
+                          0.654861 -0.719345 0.231732,
+                          0.841254 -0.514598 0.165774,
+                          0.654861 -0.61239 0.442873,
+                          0.415415 -0.865815 0.278917,
+                          0.415415 -0.737082 0.533049,
+                          0.142315 -0.80206 0.58004,
+                          0.415415 -0.865815 0.278917,
+                          0.654861 -0.719345 0.231732,
+                          0.415415 -0.737082 0.533049,
+                          0.142315 -0.942142 0.303505,
+                          0.142315 -0.80206 0.58004,
+                          -0.142315 -0.80206 0.58004,
+                          0.142315 -0.942142 0.303505,
+                          0.415415 -0.865815 0.278917,
+                          0.142315 -0.80206 0.58004,
+                          -0.142315 -0.942142 0.303505,
+                          -0.142315 -0.80206 0.58004,
+                          -0.415415 -0.737082 0.533049,
+                          -0.142315 -0.942142 0.303505,
+                          0.142315 -0.942142 0.303505,
+                          -0.142315 -0.80206 0.58004,
+                          -0.415415 -0.865815 0.278917,
+                          -0.415415 -0.737082 0.533049,
+                          -0.654861 -0.61239 0.442873,
+                          -0.415415 -0.865815 0.278917,
+                          -0.142315 -0.942142 0.303505,
+                          -0.415415 -0.737082 0.533049,
+                          -0.654861 -0.719345 0.231732,
+                          -0.654861 -0.61239 0.442873,
+                          -0.841254 -0.438085 0.316818,
+                          -0.654861 -0.719345 0.231732,
+                          -0.415415 -0.865815 0.278917,
+                          -0.654861 -0.61239 0.442873,
+                          -0.841254 -0.514598 0.165774,
+                          -0.841254 -0.438085 0.316818,
+                          -0.959493 -0.22829 0.165097,
+                          -0.841254 -0.514598 0.165774,
+                          -0.654861 -0.719345 0.231732,
+                          -0.841254 -0.438085 0.316818,
+                          -0.959493 -0.268162 0.0863865,
+                          -0.841254 -0.514598 0.165774,
+                          -0.959493 -0.22829 0.165097 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -25.6787 8.34249 -1.27676e-12,
+                          -25.2031 8.188 -1.25312e-12,
+                          -26.5 2.27374e-13 -1.3176e-12,
+                          -25.4266 7.1005 2.30709,
+                          -26.5 2.27374e-13 -1.3176e-12,
+                          -25.2031 8.188 -1.25312e-12,
+                          -27 2.27374e-13 -1.34246e-12,
+                          -26.5 2.27374e-13 -1.3176e-12,
+                          -25.2031 -8.188 -1.25312e-12,
+                          -25.4266 -7.10628 2.28924,
+                          -25.2031 -8.188 -1.25312e-12,
+                          -26.5 2.27374e-13 -1.3176e-12,
+                          -27 2.27374e-13 -1.34246e-12,
+                          -25.6787 8.34249 -1.27676e-12,
+                          -26.5 2.27374e-13 -1.3176e-12,
+                          -25.4266 6.03867 4.39025,
+                          -26.5 2.27374e-13 -1.3176e-12,
+                          -25.4266 7.1005 2.30709,
+                          -25.4266 4.38456 6.04281,
+                          -26.5 2.27374e-13 -1.3176e-12,
+                          -25.4266 6.03867 4.39025,
+                          -25.4266 2.3004 7.10268,
+                          -26.5 2.27374e-13 -1.3176e-12,
+                          -25.4266 4.38456 6.04281,
+                          -25.4266 -0.00938194 7.46591,
+                          -26.5 2.27374e-13 -1.3176e-12,
+                          -25.4266 2.3004 7.10268,
+                          -25.4266 -2.31824 7.09687,
+                          -26.5 2.27374e-13 -1.3176e-12,
+                          -25.4266 -0.00938194 7.46591,
+                          -25.4266 -4.39973 6.03177,
+                          -26.5 2.27374e-13 -1.3176e-12,
+                          -25.4266 -2.31824 7.09687,
+                          -25.4266 -6.04969 4.37506,
+                          -26.5 2.27374e-13 -1.3176e-12,
+                          -25.4266 -4.39973 6.03177,
+                          -25.4266 -7.10628 2.28924,
+                          -26.5 2.27374e-13 -1.3176e-12,
+                          -25.4266 -6.04969 4.37506,
+                          -25.6787 8.34249 -1.27676e-12,
+                          -21.4385 15.5766 -1.06594e-12,
+                          -25.2031 8.188 -1.25312e-12,
+                          -22.2932 13.6258 4.42728,
+                          -25.2031 8.188 -1.25312e-12,
+                          -21.4385 15.5766 -1.06594e-12,
+                          -22.2932 13.6258 4.42728,
+                          -25.4266 7.1005 2.30709,
+                          -25.2031 8.188 -1.25312e-12,
+                          -21.843 15.8705 -1.08605e-12,
+                          -15.5756 21.4394 -7.74433e-13,
+                          -21.4385 15.5766 -1.06594e-12,
+                          -17.3538 19.0472 6.1888,
+                          -21.4385 15.5766 -1.06594e-12,
+                          -15.5756 21.4394 -7.74433e-13,
+                          -25.6787 8.34249 -1.27676e-12,
+                          -21.843 15.8705 -1.08605e-12,
+                          -21.4385 15.5766 -1.06594e-12,
+                          -17.3538 19.0472 6.1888,
+                          -22.2932 13.6258 4.42728,
+                          -21.4385 15.5766 -1.06594e-12,
+                          -15.8695 21.8439 -7.89045e-13,
+                          -8.18995 25.2026 -4.07211e-13,
+                          -15.5756 21.4394 -7.74433e-13,
+                          -11.0085 22.9255 7.44893,
+                          -15.5756 21.4394 -7.74433e-13,
+                          -8.18995 25.2026 -4.07211e-13,
+                          -21.843 15.8705 -1.08605e-12,
+                          -15.8695 21.8439 -7.89045e-13,
+                          -15.5756 21.4394 -7.74433e-13,
+                          -11.0085 22.9255 7.44893,
+                          -17.3538 19.0472 6.1888,
+                          -15.5756 21.4394 -7.74433e-13,
+                          -8.34448 25.6781 -4.14894e-13,
+                          9.76996e-15 26.4998 -2.20805e-28,
+                          -8.18995 25.2026 -4.07211e-13,
+                          -3.77134 24.9465 8.1056,
+                          -8.18995 25.2026 -4.07211e-13,
+                          9.76996e-15 26.4998 -2.20805e-28,
+                          -15.8695 21.8439 -7.89045e-13,
+                          -8.34448 25.6781 -4.14894e-13,
+                          -8.18995 25.2026 -4.07211e-13,
+                          -3.77134 24.9465 8.1056,
+                          -11.0085 22.9255 7.44893,
+                          -8.18995 25.2026 -4.07211e-13,
+                          8.34448 25.6781 4.14894e-13,
+                          8.18995 25.2026 4.07211e-13,
+                          9.76996e-15 26.4998 -2.20805e-28,
+                          3.77134 24.9465 8.1056,
+                          9.76996e-15 26.4998 -2.20805e-28,
+                          8.18995 25.2026 4.07211e-13,
+                          9.76996e-15 26.9998 -2.20805e-28,
+                          8.34448 25.6781 4.14894e-13,
+                          9.76996e-15 26.4998 -2.20805e-28,
+                          -8.34448 25.6781 -4.14894e-13,
+                          9.76996e-15 26.9998 -2.20805e-28,
+                          9.76996e-15 26.4998 -2.20805e-28,
+                          3.77134 24.9465 8.1056,
+                          -3.77134 24.9465 8.1056,
+                          9.76996e-15 26.4998 -2.20805e-28,
+                          15.8695 21.8439 7.89045e-13,
+                          15.5756 21.4394 7.74433e-13,
+                          8.18995 25.2026 4.07211e-13,
+                          11.0085 22.9255 7.44893,
+                          8.18995 25.2026 4.07211e-13,
+                          15.5756 21.4394 7.74433e-13,
+                          8.34448 25.6781 4.14894e-13,
+                          15.8695 21.8439 7.89045e-13,
+                          8.18995 25.2026 4.07211e-13,
+                          11.0085 22.9255 7.44893,
+                          3.77134 24.9465 8.1056,
+                          8.18995 25.2026 4.07211e-13,
+                          21.843 15.8705 1.08605e-12,
+                          21.4385 15.5766 1.06594e-12,
+                          15.5756 21.4394 7.74433e-13,
+                          17.3538 19.0472 6.1888,
+                          15.5756 21.4394 7.74433e-13,
+                          21.4385 15.5766 1.06594e-12,
+                          15.8695 21.8439 7.89045e-13,
+                          21.843 15.8705 1.08605e-12,
+                          15.5756 21.4394 7.74433e-13,
+                          17.3538 19.0472 6.1888,
+                          11.0085 22.9255 7.44893,
+                          15.5756 21.4394 7.74433e-13,
+                          25.6787 8.34249 1.27676e-12,
+                          25.2031 8.188 1.25312e-12,
+                          21.4385 15.5766 1.06594e-12,
+                          22.2932 13.6258 4.42728,
+                          21.4385 15.5766 1.06594e-12,
+                          25.2031 8.188 1.25312e-12,
+                          21.843 15.8705 1.08605e-12,
+                          25.6787 8.34249 1.27676e-12,
+                          21.4385 15.5766 1.06594e-12,
+                          22.2932 13.6258 4.42728,
+                          17.3538 19.0472 6.1888,
+                          21.4385 15.5766 1.06594e-12,
+                          27 2.27374e-13 1.34246e-12,
+                          26.5 2.27374e-13 1.3176e-12,
+                          25.2031 8.188 1.25312e-12,
+                          25.4266 7.1005 2.30709,
+                          25.2031 8.188 1.25312e-12,
+                          26.5 2.27374e-13 1.3176e-12,
+                          25.6787 8.34249 1.27676e-12,
+                          27 2.27374e-13 1.34246e-12,
+                          25.2031 8.188 1.25312e-12,
+                          25.4266 7.1005 2.30709,
+                          22.2932 13.6258 4.42728,
+                          25.2031 8.188 1.25312e-12,
+                          25.6787 -8.34249 1.27676e-12,
+                          25.2031 -8.188 1.25312e-12,
+                          26.5 2.27374e-13 1.3176e-12,
+                          25.4266 -7.10628 2.28924,
+                          26.5 2.27374e-13 1.3176e-12,
+                          25.2031 -8.188 1.25312e-12,
+                          25.6787 -8.34249 1.27676e-12,
+                          26.5 2.27374e-13 1.3176e-12,
+                          27 2.27374e-13 1.34246e-12,
+                          25.4266 6.03867 4.39025,
+                          25.4266 7.1005 2.30709,
+                          26.5 2.27374e-13 1.3176e-12,
+                          25.4266 4.38456 6.04281,
+                          25.4266 6.03867 4.39025,
+                          26.5 2.27374e-13 1.3176e-12,
+                          25.4266 2.3004 7.10268,
+                          25.4266 4.38456 6.04281,
+                          26.5 2.27374e-13 1.3176e-12,
+                          25.4266 -0.00938194 7.46591,
+                          25.4266 2.3004 7.10268,
+                          26.5 2.27374e-13 1.3176e-12,
+                          25.4266 -2.31824 7.09687,
+                          25.4266 -0.00938194 7.46591,
+                          26.5 2.27374e-13 1.3176e-12,
+                          25.4266 -4.39973 6.03177,
+                          25.4266 -2.31824 7.09687,
+                          26.5 2.27374e-13 1.3176e-12,
+                          25.4266 -6.04969 4.37506,
+                          25.4266 -4.39973 6.03177,
+                          26.5 2.27374e-13 1.3176e-12,
+                          25.4266 -7.10628 2.28924,
+                          25.4266 -6.04969 4.37506,
+                          26.5 2.27374e-13 1.3176e-12,
+                          25.6787 -8.34249 1.27676e-12,
+                          21.4385 -15.5766 1.06594e-12,
+                          25.2031 -8.188 1.25312e-12,
+                          22.2932 -13.6369 4.39302,
+                          25.2031 -8.188 1.25312e-12,
+                          21.4385 -15.5766 1.06594e-12,
+                          25.4266 -7.10628 2.28924,
+                          25.2031 -8.188 1.25312e-12,
+                          22.2932 -13.6369 4.39302,
+                          21.843 -15.8705 1.08605e-12,
+                          15.5756 -21.4394 7.74433e-13,
+                          21.4385 -15.5766 1.06594e-12,
+                          17.3538 -19.0626 6.14091,
+                          21.4385 -15.5766 1.06594e-12,
+                          15.5756 -21.4394 7.74433e-13,
+                          25.6787 -8.34249 1.27676e-12,
+                          21.843 -15.8705 1.08605e-12,
+                          21.4385 -15.5766 1.06594e-12,
+                          22.2932 -13.6369 4.39302,
+                          21.4385 -15.5766 1.06594e-12,
+                          17.3538 -19.0626 6.14091,
+                          15.8695 -21.8439 7.89045e-13,
+                          8.18995 -25.2026 4.07211e-13,
+                          15.5756 -21.4394 7.74433e-13,
+                          11.0085 -22.9441 7.39129,
+                          15.5756 -21.4394 7.74433e-13,
+                          8.18995 -25.2026 4.07211e-13,
+                          21.843 -15.8705 1.08605e-12,
+                          15.8695 -21.8439 7.89045e-13,
+                          15.5756 -21.4394 7.74433e-13,
+                          17.3538 -19.0626 6.14091,
+                          15.5756 -21.4394 7.74433e-13,
+                          11.0085 -22.9441 7.39129,
+                          8.34448 -25.6781 4.14894e-13,
+                          9.76996e-15 -26.4998 -2.20805e-28,
+                          8.18995 -25.2026 4.07211e-13,
+                          3.77134 -24.9668 8.04288,
+                          8.18995 -25.2026 4.07211e-13,
+                          9.76996e-15 -26.4998 -2.20805e-28,
+                          15.8695 -21.8439 7.89045e-13,
+                          8.34448 -25.6781 4.14894e-13,
+                          8.18995 -25.2026 4.07211e-13,
+                          11.0085 -22.9441 7.39129,
+                          8.18995 -25.2026 4.07211e-13,
+                          3.77134 -24.9668 8.04288,
+                          -8.34448 -25.6781 -4.14894e-13,
+                          -8.18995 -25.2026 -4.07211e-13,
+                          9.76996e-15 -26.4998 -2.20805e-28,
+                          -3.77134 -24.9668 8.04288,
+                          9.76996e-15 -26.4998 -2.20805e-28,
+                          -8.18995 -25.2026 -4.07211e-13,
+                          9.76996e-15 -26.9998 -2.20805e-28,
+                          -8.34448 -25.6781 -4.14894e-13,
+                          9.76996e-15 -26.4998 -2.20805e-28,
+                          8.34448 -25.6781 4.14894e-13,
+                          9.76996e-15 -26.9998 -2.20805e-28,
+                          9.76996e-15 -26.4998 -2.20805e-28,
+                          3.77134 -24.9668 8.04288,
+                          9.76996e-15 -26.4998 -2.20805e-28,
+                          -3.77134 -24.9668 8.04288,
+                          -15.8695 -21.8439 -7.89045e-13,
+                          -15.5756 -21.4394 -7.74433e-13,
+                          -8.18995 -25.2026 -4.07211e-13,
+                          -11.0085 -22.9441 7.39129,
+                          -8.18995 -25.2026 -4.07211e-13,
+                          -15.5756 -21.4394 -7.74433e-13,
+                          -8.34448 -25.6781 -4.14894e-13,
+                          -15.8695 -21.8439 -7.89045e-13,
+                          -8.18995 -25.2026 -4.07211e-13,
+                          -3.77134 -24.9668 8.04288,
+                          -8.18995 -25.2026 -4.07211e-13,
+                          -11.0085 -22.9441 7.39129,
+                          -21.843 -15.8705 -1.08605e-12,
+                          -21.4385 -15.5766 -1.06594e-12,
+                          -15.5756 -21.4394 -7.74433e-13,
+                          -17.3538 -19.0626 6.14091,
+                          -15.5756 -21.4394 -7.74433e-13,
+                          -21.4385 -15.5766 -1.06594e-12,
+                          -15.8695 -21.8439 -7.89045e-13,
+                          -21.843 -15.8705 -1.08605e-12,
+                          -15.5756 -21.4394 -7.74433e-13,
+                          -11.0085 -22.9441 7.39129,
+                          -15.5756 -21.4394 -7.74433e-13,
+                          -17.3538 -19.0626 6.14091,
+                          -25.6787 -8.34249 -1.27676e-12,
+                          -25.2031 -8.188 -1.25312e-12,
+                          -21.4385 -15.5766 -1.06594e-12,
+                          -22.2932 -13.6369 4.39302,
+                          -21.4385 -15.5766 -1.06594e-12,
+                          -25.2031 -8.188 -1.25312e-12,
+                          -21.843 -15.8705 -1.08605e-12,
+                          -25.6787 -8.34249 -1.27676e-12,
+                          -21.4385 -15.5766 -1.06594e-12,
+                          -17.3538 -19.0626 6.14091,
+                          -21.4385 -15.5766 -1.06594e-12,
+                          -22.2932 -13.6369 4.39302,
+                          -25.6787 -8.34249 -1.27676e-12,
+                          -27 2.27374e-13 -1.34246e-12,
+                          -25.2031 -8.188 -1.25312e-12,
+                          -22.2932 -13.6369 4.39302,
+                          -25.2031 -8.188 -1.25312e-12,
+                          -25.4266 -7.10628 2.28924,
+                          25.9063 7.23448 2.35062,
+                          27 2.27374e-13 1.34246e-12,
+                          25.6787 8.34249 1.27676e-12,
+                          25.9063 -7.24036 2.33243,
+                          25.6787 -8.34249 1.27676e-12,
+                          27 2.27374e-13 1.34246e-12,
+                          25.9063 6.15261 4.47309,
+                          27 2.27374e-13 1.34246e-12,
+                          25.9063 7.23448 2.35062,
+                          25.9063 4.46729 6.15682,
+                          27 2.27374e-13 1.34246e-12,
+                          25.9063 6.15261 4.47309,
+                          25.9063 2.3438 7.23669,
+                          27 2.27374e-13 1.34246e-12,
+                          25.9063 4.46729 6.15682,
+                          25.9063 -0.00955896 7.60677,
+                          27 2.27374e-13 1.34246e-12,
+                          25.9063 2.3438 7.23669,
+                          25.9063 -2.36198 7.23078,
+                          27 2.27374e-13 1.34246e-12,
+                          25.9063 -0.00955896 7.60677,
+                          25.9063 -4.48274 6.14557,
+                          27 2.27374e-13 1.34246e-12,
+                          25.9063 -2.36198 7.23078,
+                          25.9063 -6.16383 4.45761,
+                          27 2.27374e-13 1.34246e-12,
+                          25.9063 -4.48274 6.14557,
+                          25.9063 -7.24036 2.33243,
+                          27 2.27374e-13 1.34246e-12,
+                          25.9063 -6.16383 4.45761,
+                          22.7138 13.8829 4.51081,
+                          25.6787 8.34249 1.27676e-12,
+                          21.843 15.8705 1.08605e-12,
+                          22.7138 13.8829 4.51081,
+                          25.9063 7.23448 2.35062,
+                          25.6787 8.34249 1.27676e-12,
+                          17.6812 19.4065 6.30557,
+                          21.843 15.8705 1.08605e-12,
+                          15.8695 21.8439 7.89045e-13,
+                          17.6812 19.4065 6.30557,
+                          22.7138 13.8829 4.51081,
+                          21.843 15.8705 1.08605e-12,
+                          11.2162 23.358 7.58948,
+                          15.8695 21.8439 7.89045e-13,
+                          8.34448 25.6781 4.14894e-13,
+                          11.2162 23.358 7.58948,
+                          17.6812 19.4065 6.30557,
+                          15.8695 21.8439 7.89045e-13,
+                          3.8425 25.4172 8.25853,
+                          8.34448 25.6781 4.14894e-13,
+                          9.76996e-15 26.9998 -2.20805e-28,
+                          3.8425 25.4172 8.25853,
+                          11.2162 23.358 7.58948,
+                          8.34448 25.6781 4.14894e-13,
+                          -3.8425 25.4172 8.25853,
+                          9.76996e-15 26.9998 -2.20805e-28,
+                          -8.34448 25.6781 -4.14894e-13,
+                          -3.8425 25.4172 8.25853,
+                          3.8425 25.4172 8.25853,
+                          9.76996e-15 26.9998 -2.20805e-28,
+                          -11.2162 23.358 7.58948,
+                          -8.34448 25.6781 -4.14894e-13,
+                          -15.8695 21.8439 -7.89045e-13,
+                          -11.2162 23.358 7.58948,
+                          -3.8425 25.4172 8.25853,
+                          -8.34448 25.6781 -4.14894e-13,
+                          -17.6812 19.4065 6.30557,
+                          -15.8695 21.8439 -7.89045e-13,
+                          -21.843 15.8705 -1.08605e-12,
+                          -17.6812 19.4065 6.30557,
+                          -11.2162 23.358 7.58948,
+                          -15.8695 21.8439 -7.89045e-13,
+                          -22.7138 13.8829 4.51081,
+                          -21.843 15.8705 -1.08605e-12,
+                          -25.6787 8.34249 -1.27676e-12,
+                          -22.7138 13.8829 4.51081,
+                          -17.6812 19.4065 6.30557,
+                          -21.843 15.8705 -1.08605e-12,
+                          -25.9063 7.23448 2.35062,
+                          -25.6787 8.34249 -1.27676e-12,
+                          -27 2.27374e-13 -1.34246e-12,
+                          -25.9063 7.23448 2.35062,
+                          -22.7138 13.8829 4.51081,
+                          -25.6787 8.34249 -1.27676e-12,
+                          -25.9063 -7.24036 2.33243,
+                          -27 2.27374e-13 -1.34246e-12,
+                          -25.6787 -8.34249 -1.27676e-12,
+                          -25.9063 6.15261 4.47309,
+                          -25.9063 7.23448 2.35062,
+                          -27 2.27374e-13 -1.34246e-12,
+                          -25.9063 4.46729 6.15682,
+                          -25.9063 6.15261 4.47309,
+                          -27 2.27374e-13 -1.34246e-12,
+                          -25.9063 2.3438 7.23669,
+                          -25.9063 4.46729 6.15682,
+                          -27 2.27374e-13 -1.34246e-12,
+                          -25.9063 -0.00955896 7.60677,
+                          -25.9063 2.3438 7.23669,
+                          -27 2.27374e-13 -1.34246e-12,
+                          -25.9063 -2.36198 7.23078,
+                          -25.9063 -0.00955896 7.60677,
+                          -27 2.27374e-13 -1.34246e-12,
+                          -25.9063 -4.48274 6.14557,
+                          -25.9063 -2.36198 7.23078,
+                          -27 2.27374e-13 -1.34246e-12,
+                          -25.9063 -6.16383 4.45761,
+                          -25.9063 -4.48274 6.14557,
+                          -27 2.27374e-13 -1.34246e-12,
+                          -25.9063 -7.24036 2.33243,
+                          -25.9063 -6.16383 4.45761,
+                          -27 2.27374e-13 -1.34246e-12,
+                          -22.7138 -13.8942 4.47591,
+                          -25.6787 -8.34249 -1.27676e-12,
+                          -21.843 -15.8705 -1.08605e-12,
+                          -25.9063 -7.24036 2.33243,
+                          -25.6787 -8.34249 -1.27676e-12,
+                          -22.7138 -13.8942 4.47591,
+                          -17.6812 -19.4223 6.25677,
+                          -21.843 -15.8705 -1.08605e-12,
+                          -15.8695 -21.8439 -7.89045e-13,
+                          -22.7138 -13.8942 4.47591,
+                          -21.843 -15.8705 -1.08605e-12,
+                          -17.6812 -19.4223 6.25677,
+                          -11.2162 -23.377 7.53075,
+                          -15.8695 -21.8439 -7.89045e-13,
+                          -8.34448 -25.6781 -4.14894e-13,
+                          -17.6812 -19.4223 6.25677,
+                          -15.8695 -21.8439 -7.89045e-13,
+                          -11.2162 -23.377 7.53075,
+                          -3.8425 -25.4378 8.19463,
+                          -8.34448 -25.6781 -4.14894e-13,
+                          9.76996e-15 -26.9998 -2.20805e-28,
+                          -11.2162 -23.377 7.53075,
+                          -8.34448 -25.6781 -4.14894e-13,
+                          -3.8425 -25.4378 8.19463,
+                          3.8425 -25.4378 8.19463,
+                          9.76996e-15 -26.9998 -2.20805e-28,
+                          8.34448 -25.6781 4.14894e-13,
+                          -3.8425 -25.4378 8.19463,
+                          9.76996e-15 -26.9998 -2.20805e-28,
+                          3.8425 -25.4378 8.19463,
+                          11.2162 -23.377 7.53075,
+                          8.34448 -25.6781 4.14894e-13,
+                          15.8695 -21.8439 7.89045e-13,
+                          3.8425 -25.4378 8.19463,
+                          8.34448 -25.6781 4.14894e-13,
+                          11.2162 -23.377 7.53075,
+                          17.6812 -19.4223 6.25677,
+                          15.8695 -21.8439 7.89045e-13,
+                          21.843 -15.8705 1.08605e-12,
+                          11.2162 -23.377 7.53075,
+                          15.8695 -21.8439 7.89045e-13,
+                          17.6812 -19.4223 6.25677,
+                          22.7138 -13.8942 4.47591,
+                          21.843 -15.8705 1.08605e-12,
+                          25.6787 -8.34249 1.27676e-12,
+                          17.6812 -19.4223 6.25677,
+                          21.843 -15.8705 1.08605e-12,
+                          22.7138 -13.8942 4.47591,
+                          22.7138 -13.8942 4.47591,
+                          25.6787 -8.34249 1.27676e-12,
+                          25.9063 -7.24036 2.33243,
+                          -25.4266 6.03867 4.39025,
+                          -25.4266 7.1005 2.30709,
+                          -22.2932 13.6258 4.42728,
+                          -22.2932 11.5881 8.42483,
+                          -22.2932 13.6258 4.42728,
+                          -17.3538 19.0472 6.1888,
+                          -22.2932 11.5881 8.42483,
+                          -25.4266 6.03867 4.39025,
+                          -22.2932 13.6258 4.42728,
+                          -17.3538 16.1988 11.7769,
+                          -17.3538 19.0472 6.1888,
+                          -11.0085 22.9255 7.44893,
+                          -17.3538 16.1988 11.7769,
+                          -22.2932 11.5881 8.42483,
+                          -17.3538 19.0472 6.1888,
+                          -11.0085 19.4971 14.1748,
+                          -11.0085 22.9255 7.44893,
+                          -3.77134 24.9465 8.1056,
+                          -11.0085 19.4971 14.1748,
+                          -17.3538 16.1988 11.7769,
+                          -11.0085 22.9255 7.44893,
+                          -3.77134 21.2159 15.4244,
+                          -3.77134 24.9465 8.1056,
+                          3.77134 24.9465 8.1056,
+                          -3.77134 21.2159 15.4244,
+                          -11.0085 19.4971 14.1748,
+                          -3.77134 24.9465 8.1056,
+                          3.77134 21.2159 15.4244,
+                          3.77134 24.9465 8.1056,
+                          11.0085 22.9255 7.44893,
+                          3.77134 21.2159 15.4244,
+                          -3.77134 21.2159 15.4244,
+                          3.77134 24.9465 8.1056,
+                          11.0085 19.4971 14.1748,
+                          11.0085 22.9255 7.44893,
+                          17.3538 19.0472 6.1888,
+                          11.0085 19.4971 14.1748,
+                          3.77134 21.2159 15.4244,
+                          11.0085 22.9255 7.44893,
+                          17.3538 16.1988 11.7769,
+                          17.3538 19.0472 6.1888,
+                          22.2932 13.6258 4.42728,
+                          17.3538 16.1988 11.7769,
+                          11.0085 19.4971 14.1748,
+                          17.3538 19.0472 6.1888,
+                          22.2932 11.5881 8.42483,
+                          22.2932 13.6258 4.42728,
+                          25.4266 7.1005 2.30709,
+                          22.2932 11.5881 8.42483,
+                          17.3538 16.1988 11.7769,
+                          22.2932 13.6258 4.42728,
+                          25.4266 6.03867 4.39025,
+                          22.2932 11.5881 8.42483,
+                          25.4266 7.1005 2.30709,
+                          -25.4266 4.38456 6.04281,
+                          -25.4266 6.03867 4.39025,
+                          -22.2932 11.5881 8.42483,
+                          -22.2932 8.4139 11.5961,
+                          -22.2932 11.5881 8.42483,
+                          -17.3538 16.1988 11.7769,
+                          -22.2932 8.4139 11.5961,
+                          -25.4266 4.38456 6.04281,
+                          -22.2932 11.5881 8.42483,
+                          -17.3538 11.7616 16.2099,
+                          -17.3538 16.1988 11.7769,
+                          -11.0085 19.4971 14.1748,
+                          -17.3538 11.7616 16.2099,
+                          -22.2932 8.4139 11.5961,
+                          -17.3538 16.1988 11.7769,
+                          -11.0085 14.1565 19.5105,
+                          -11.0085 19.4971 14.1748,
+                          -3.77134 21.2159 15.4244,
+                          -11.0085 14.1565 19.5105,
+                          -17.3538 11.7616 16.2099,
+                          -11.0085 19.4971 14.1748,
+                          -3.77134 15.4044 21.2304,
+                          -3.77134 21.2159 15.4244,
+                          3.77134 21.2159 15.4244,
+                          -3.77134 15.4044 21.2304,
+                          -11.0085 14.1565 19.5105,
+                          -3.77134 21.2159 15.4244,
+                          3.77134 15.4044 21.2304,
+                          3.77134 21.2159 15.4244,
+                          11.0085 19.4971 14.1748,
+                          3.77134 15.4044 21.2304,
+                          -3.77134 15.4044 21.2304,
+                          3.77134 21.2159 15.4244,
+                          11.0085 14.1565 19.5105,
+                          11.0085 19.4971 14.1748,
+                          17.3538 16.1988 11.7769,
+                          11.0085 14.1565 19.5105,
+                          3.77134 15.4044 21.2304,
+                          11.0085 19.4971 14.1748,
+                          17.3538 11.7616 16.2099,
+                          17.3538 16.1988 11.7769,
+                          22.2932 11.5881 8.42483,
+                          17.3538 11.7616 16.2099,
+                          11.0085 14.1565 19.5105,
+                          17.3538 16.1988 11.7769,
+                          22.2932 8.4139 11.5961,
+                          22.2932 11.5881 8.42483,
+                          25.4266 6.03867 4.39025,
+                          22.2932 8.4139 11.5961,
+                          17.3538 11.7616 16.2099,
+                          22.2932 11.5881 8.42483,
+                          25.4266 4.38456 6.04281,
+                          22.2932 8.4139 11.5961,
+                          25.4266 6.03867 4.39025,
+                          -25.4266 2.3004 7.10268,
+                          -25.4266 4.38456 6.04281,
+                          -22.2932 8.4139 11.5961,
+                          -22.2932 4.41444 13.6299,
+                          -22.2932 8.4139 11.5961,
+                          -17.3538 11.7616 16.2099,
+                          -22.2932 4.41444 13.6299,
+                          -25.4266 2.3004 7.10268,
+                          -22.2932 8.4139 11.5961,
+                          -17.3538 6.17084 19.053,
+                          -17.3538 11.7616 16.2099,
+                          -11.0085 14.1565 19.5105,
+                          -17.3538 6.17084 19.053,
+                          -22.2932 4.41444 13.6299,
+                          -17.3538 11.7616 16.2099,
+                          -11.0085 7.42732 22.9325,
+                          -11.0085 14.1565 19.5105,
+                          -3.77134 15.4044 21.2304,
+                          -11.0085 7.42732 22.9325,
+                          -17.3538 6.17084 19.053,
+                          -11.0085 14.1565 19.5105,
+                          -3.77134 8.08208 24.9541,
+                          -3.77134 15.4044 21.2304,
+                          3.77134 15.4044 21.2304,
+                          -3.77134 8.08208 24.9541,
+                          -11.0085 7.42732 22.9325,
+                          -3.77134 15.4044 21.2304,
+                          3.77134 8.08208 24.9541,
+                          3.77134 15.4044 21.2304,
+                          11.0085 14.1565 19.5105,
+                          3.77134 8.08208 24.9541,
+                          -3.77134 8.08208 24.9541,
+                          3.77134 15.4044 21.2304,
+                          11.0085 7.42732 22.9325,
+                          11.0085 14.1565 19.5105,
+                          17.3538 11.7616 16.2099,
+                          11.0085 7.42732 22.9325,
+                          3.77134 8.08208 24.9541,
+                          11.0085 14.1565 19.5105,
+                          17.3538 6.17084 19.053,
+                          17.3538 11.7616 16.2099,
+                          22.2932 8.4139 11.5961,
+                          17.3538 6.17084 19.053,
+                          11.0085 7.42732 22.9325,
+                          17.3538 11.7616 16.2099,
+                          22.2932 4.41444 13.6299,
+                          22.2932 8.4139 11.5961,
+                          25.4266 4.38456 6.04281,
+                          22.2932 4.41444 13.6299,
+                          17.3538 6.17084 19.053,
+                          22.2932 8.4139 11.5961,
+                          25.4266 2.3004 7.10268,
+                          22.2932 4.41444 13.6299,
+                          25.4266 4.38456 6.04281,
+                          -25.4266 -0.00938194 7.46591,
+                          -25.4266 2.3004 7.10268,
+                          -22.2932 4.41444 13.6299,
+                          -22.2932 -0.0180038 14.327,
+                          -22.2932 4.41444 13.6299,
+                          -17.3538 6.17084 19.053,
+                          -22.2932 -0.0180038 14.327,
+                          -25.4266 -0.00938194 7.46591,
+                          -22.2932 4.41444 13.6299,
+                          -17.3538 -0.0251671 20.0273,
+                          -17.3538 6.17084 19.053,
+                          -11.0085 7.42732 22.9325,
+                          -17.3538 -0.0251671 20.0273,
+                          -22.2932 -0.0180038 14.327,
+                          -17.3538 6.17084 19.053,
+                          -11.0085 -0.0302915 24.1052,
+                          -11.0085 7.42732 22.9325,
+                          -3.77134 8.08208 24.9541,
+                          -11.0085 -0.0302915 24.1052,
+                          -17.3538 -0.0251671 20.0273,
+                          -11.0085 7.42732 22.9325,
+                          -3.77134 -0.0329619 26.2302,
+                          -3.77134 8.08208 24.9541,
+                          3.77134 8.08208 24.9541,
+                          -3.77134 -0.0329619 26.2302,
+                          -11.0085 -0.0302915 24.1052,
+                          -3.77134 8.08208 24.9541,
+                          3.77134 -0.0329619 26.2302,
+                          3.77134 8.08208 24.9541,
+                          11.0085 7.42732 22.9325,
+                          3.77134 -0.0329619 26.2302,
+                          -3.77134 -0.0329619 26.2302,
+                          3.77134 8.08208 24.9541,
+                          11.0085 -0.0302915 24.1052,
+                          11.0085 7.42732 22.9325,
+                          17.3538 6.17084 19.053,
+                          11.0085 -0.0302915 24.1052,
+                          3.77134 -0.0329619 26.2302,
+                          11.0085 7.42732 22.9325,
+                          17.3538 -0.0251671 20.0273,
+                          17.3538 6.17084 19.053,
+                          22.2932 4.41444 13.6299,
+                          17.3538 -0.0251671 20.0273,
+                          11.0085 -0.0302915 24.1052,
+                          17.3538 6.17084 19.053,
+                          22.2932 -0.0180038 14.327,
+                          22.2932 4.41444 13.6299,
+                          25.4266 2.3004 7.10268,
+                          22.2932 -0.0180038 14.327,
+                          17.3538 -0.0251671 20.0273,
+                          22.2932 4.41444 13.6299,
+                          25.4266 -0.00938194 7.46591,
+                          22.2932 -0.0180038 14.327,
+                          25.4266 2.3004 7.10268,
+                          -25.4266 -2.31824 7.09687,
+                          -25.4266 -0.00938194 7.46591,
+                          -22.2932 -0.0180038 14.327,
+                          -22.2932 -4.44868 13.6188,
+                          -22.2932 -0.0180038 14.327,
+                          -17.3538 -0.0251671 20.0273,
+                          -22.2932 -4.44868 13.6188,
+                          -25.4266 -2.31824 7.09687,
+                          -22.2932 -0.0180038 14.327,
+                          -17.3538 -6.21871 19.0374,
+                          -17.3538 -0.0251671 20.0273,
+                          -11.0085 -0.0302915 24.1052,
+                          -17.3538 -6.21871 19.0374,
+                          -22.2932 -4.44868 13.6188,
+                          -17.3538 -0.0251671 20.0273,
+                          -11.0085 -7.48493 22.9137,
+                          -11.0085 -0.0302915 24.1052,
+                          -3.77134 -0.0329619 26.2302,
+                          -11.0085 -7.48493 22.9137,
+                          -17.3538 -6.21871 19.0374,
+                          -11.0085 -0.0302915 24.1052,
+                          -3.77134 -8.14477 24.9337,
+                          -3.77134 -0.0329619 26.2302,
+                          3.77134 -0.0329619 26.2302,
+                          -3.77134 -8.14477 24.9337,
+                          -11.0085 -7.48493 22.9137,
+                          -3.77134 -0.0329619 26.2302,
+                          3.77134 -8.14477 24.9337,
+                          3.77134 -0.0329619 26.2302,
+                          11.0085 -0.0302915 24.1052,
+                          3.77134 -8.14477 24.9337,
+                          -3.77134 -8.14477 24.9337,
+                          3.77134 -0.0329619 26.2302,
+                          11.0085 -7.48493 22.9137,
+                          11.0085 -0.0302915 24.1052,
+                          17.3538 -0.0251671 20.0273,
+                          11.0085 -7.48493 22.9137,
+                          3.77134 -8.14477 24.9337,
+                          11.0085 -0.0302915 24.1052,
+                          17.3538 -6.21871 19.0374,
+                          17.3538 -0.0251671 20.0273,
+                          22.2932 -0.0180038 14.327,
+                          17.3538 -6.21871 19.0374,
+                          11.0085 -7.48493 22.9137,
+                          17.3538 -0.0251671 20.0273,
+                          22.2932 -4.44868 13.6188,
+                          22.2932 -0.0180038 14.327,
+                          25.4266 -0.00938194 7.46591,
+                          22.2932 -4.44868 13.6188,
+                          17.3538 -6.21871 19.0374,
+                          22.2932 -0.0180038 14.327,
+                          25.4266 -2.31824 7.09687,
+                          22.2932 -4.44868 13.6188,
+                          25.4266 -0.00938194 7.46591,
+                          -25.4266 -4.39973 6.03177,
+                          -25.4266 -2.31824 7.09687,
+                          -22.2932 -4.44868 13.6188,
+                          -22.2932 -8.44302 11.5749,
+                          -22.2932 -4.44868 13.6188,
+                          -17.3538 -6.21871 19.0374,
+                          -22.2932 -8.44302 11.5749,
+                          -25.4266 -4.39973 6.03177,
+                          -22.2932 -4.44868 13.6188,
+                          -17.3538 -11.8023 16.1803,
+                          -17.3538 -6.21871 19.0374,
+                          -11.0085 -7.48493 22.9137,
+                          -17.3538 -11.8023 16.1803,
+                          -22.2932 -8.44302 11.5749,
+                          -17.3538 -6.21871 19.0374,
+                          -11.0085 -14.2054 19.4748,
+                          -11.0085 -7.48493 22.9137,
+                          -3.77134 -8.14477 24.9337,
+                          -11.0085 -14.2054 19.4748,
+                          -17.3538 -11.8023 16.1803,
+                          -11.0085 -7.48493 22.9137,
+                          -3.77134 -15.4577 21.1916,
+                          -3.77134 -8.14477 24.9337,
+                          3.77134 -8.14477 24.9337,
+                          -3.77134 -15.4577 21.1916,
+                          -11.0085 -14.2054 19.4748,
+                          -3.77134 -8.14477 24.9337,
+                          3.77134 -15.4577 21.1916,
+                          3.77134 -8.14477 24.9337,
+                          11.0085 -7.48493 22.9137,
+                          3.77134 -15.4577 21.1916,
+                          -3.77134 -15.4577 21.1916,
+                          3.77134 -8.14477 24.9337,
+                          11.0085 -14.2054 19.4748,
+                          11.0085 -7.48493 22.9137,
+                          17.3538 -6.21871 19.0374,
+                          11.0085 -14.2054 19.4748,
+                          3.77134 -15.4577 21.1916,
+                          11.0085 -7.48493 22.9137,
+                          17.3538 -11.8023 16.1803,
+                          17.3538 -6.21871 19.0374,
+                          22.2932 -4.44868 13.6188,
+                          17.3538 -11.8023 16.1803,
+                          11.0085 -14.2054 19.4748,
+                          17.3538 -6.21871 19.0374,
+                          22.2932 -8.44302 11.5749,
+                          22.2932 -4.44868 13.6188,
+                          25.4266 -2.31824 7.09687,
+                          22.2932 -8.44302 11.5749,
+                          17.3538 -11.8023 16.1803,
+                          22.2932 -4.44868 13.6188,
+                          25.4266 -4.39973 6.03177,
+                          22.2932 -8.44302 11.5749,
+                          25.4266 -2.31824 7.09687,
+                          -25.4266 -6.04969 4.37506,
+                          -25.4266 -4.39973 6.03177,
+                          -22.2932 -8.44302 11.5749,
+                          -22.2932 -11.6093 8.39568,
+                          -22.2932 -8.44302 11.5749,
+                          -17.3538 -11.8023 16.1803,
+                          -22.2932 -11.6093 8.39568,
+                          -25.4266 -6.04969 4.37506,
+                          -22.2932 -8.44302 11.5749,
+                          -17.3538 -16.2283 11.7361,
+                          -17.3538 -11.8023 16.1803,
+                          -11.0085 -14.2054 19.4748,
+                          -17.3538 -16.2283 11.7361,
+                          -22.2932 -11.6093 8.39568,
+                          -17.3538 -11.8023 16.1803,
+                          -11.0085 -19.5327 14.1258,
+                          -11.0085 -14.2054 19.4748,
+                          -3.77134 -15.4577 21.1916,
+                          -11.0085 -19.5327 14.1258,
+                          -17.3538 -16.2283 11.7361,
+                          -11.0085 -14.2054 19.4748,
+                          -3.77134 -21.2546 15.3711,
+                          -3.77134 -15.4577 21.1916,
+                          3.77134 -15.4577 21.1916,
+                          -3.77134 -21.2546 15.3711,
+                          -11.0085 -19.5327 14.1258,
+                          -3.77134 -15.4577 21.1916,
+                          3.77134 -21.2546 15.3711,
+                          3.77134 -15.4577 21.1916,
+                          11.0085 -14.2054 19.4748,
+                          3.77134 -21.2546 15.3711,
+                          -3.77134 -21.2546 15.3711,
+                          3.77134 -15.4577 21.1916,
+                          11.0085 -19.5327 14.1258,
+                          11.0085 -14.2054 19.4748,
+                          17.3538 -11.8023 16.1803,
+                          11.0085 -19.5327 14.1258,
+                          3.77134 -21.2546 15.3711,
+                          11.0085 -14.2054 19.4748,
+                          17.3538 -16.2283 11.7361,
+                          17.3538 -11.8023 16.1803,
+                          22.2932 -8.44302 11.5749,
+                          17.3538 -16.2283 11.7361,
+                          11.0085 -19.5327 14.1258,
+                          17.3538 -11.8023 16.1803,
+                          22.2932 -11.6093 8.39568,
+                          22.2932 -8.44302 11.5749,
+                          25.4266 -4.39973 6.03177,
+                          22.2932 -11.6093 8.39568,
+                          17.3538 -16.2283 11.7361,
+                          22.2932 -8.44302 11.5749,
+                          25.4266 -6.04969 4.37506,
+                          22.2932 -11.6093 8.39568,
+                          25.4266 -4.39973 6.03177,
+                          -25.4266 -7.10628 2.28924,
+                          -25.4266 -6.04969 4.37506,
+                          -22.2932 -11.6093 8.39568,
+                          -22.2932 -13.6369 4.39302,
+                          -22.2932 -11.6093 8.39568,
+                          -17.3538 -16.2283 11.7361,
+                          -22.2932 -13.6369 4.39302,
+                          -25.4266 -7.10628 2.28924,
+                          -22.2932 -11.6093 8.39568,
+                          -17.3538 -19.0626 6.14091,
+                          -17.3538 -16.2283 11.7361,
+                          -11.0085 -19.5327 14.1258,
+                          -17.3538 -19.0626 6.14091,
+                          -22.2932 -13.6369 4.39302,
+                          -17.3538 -16.2283 11.7361,
+                          -11.0085 -22.9441 7.39129,
+                          -11.0085 -19.5327 14.1258,
+                          -3.77134 -21.2546 15.3711,
+                          -11.0085 -22.9441 7.39129,
+                          -17.3538 -19.0626 6.14091,
+                          -11.0085 -19.5327 14.1258,
+                          -3.77134 -24.9668 8.04288,
+                          -3.77134 -21.2546 15.3711,
+                          3.77134 -21.2546 15.3711,
+                          -3.77134 -24.9668 8.04288,
+                          -11.0085 -22.9441 7.39129,
+                          -3.77134 -21.2546 15.3711,
+                          3.77134 -24.9668 8.04288,
+                          3.77134 -21.2546 15.3711,
+                          11.0085 -19.5327 14.1258,
+                          3.77134 -24.9668 8.04288,
+                          -3.77134 -24.9668 8.04288,
+                          3.77134 -21.2546 15.3711,
+                          11.0085 -22.9441 7.39129,
+                          11.0085 -19.5327 14.1258,
+                          17.3538 -16.2283 11.7361,
+                          11.0085 -22.9441 7.39129,
+                          3.77134 -24.9668 8.04288,
+                          11.0085 -19.5327 14.1258,
+                          17.3538 -19.0626 6.14091,
+                          17.3538 -16.2283 11.7361,
+                          22.2932 -11.6093 8.39568,
+                          17.3538 -19.0626 6.14091,
+                          11.0085 -22.9441 7.39129,
+                          17.3538 -16.2283 11.7361,
+                          22.2932 -13.6369 4.39302,
+                          22.2932 -11.6093 8.39568,
+                          25.4266 -6.04969 4.37506,
+                          22.2932 -13.6369 4.39302,
+                          17.3538 -19.0626 6.14091,
+                          22.2932 -11.6093 8.39568,
+                          25.4266 -7.10628 2.28924,
+                          22.2932 -13.6369 4.39302,
+                          25.4266 -6.04969 4.37506,
+                          25.9063 6.15261 4.47309,
+                          25.9063 7.23448 2.35062,
+                          22.7138 13.8829 4.51081,
+                          22.7138 11.8068 8.58379,
+                          22.7138 13.8829 4.51081,
+                          17.6812 19.4065 6.30557,
+                          22.7138 11.8068 8.58379,
+                          25.9063 6.15261 4.47309,
+                          22.7138 13.8829 4.51081,
+                          17.6812 16.5044 11.9991,
+                          17.6812 19.4065 6.30557,
+                          11.2162 23.358 7.58948,
+                          17.6812 16.5044 11.9991,
+                          22.7138 11.8068 8.58379,
+                          17.6812 19.4065 6.30557,
+                          11.2162 19.865 14.4423,
+                          11.2162 23.358 7.58948,
+                          3.8425 25.4172 8.25853,
+                          11.2162 19.865 14.4423,
+                          17.6812 16.5044 11.9991,
+                          11.2162 23.358 7.58948,
+                          3.8425 21.6162 15.7155,
+                          3.8425 25.4172 8.25853,
+                          -3.8425 25.4172 8.25853,
+                          3.8425 21.6162 15.7155,
+                          11.2162 19.865 14.4423,
+                          3.8425 25.4172 8.25853,
+                          -3.8425 21.6162 15.7155,
+                          -3.8425 25.4172 8.25853,
+                          -11.2162 23.358 7.58948,
+                          -3.8425 21.6162 15.7155,
+                          3.8425 21.6162 15.7155,
+                          -3.8425 25.4172 8.25853,
+                          -11.2162 19.865 14.4423,
+                          -11.2162 23.358 7.58948,
+                          -17.6812 19.4065 6.30557,
+                          -11.2162 19.865 14.4423,
+                          -3.8425 21.6162 15.7155,
+                          -11.2162 23.358 7.58948,
+                          -17.6812 16.5044 11.9991,
+                          -17.6812 19.4065 6.30557,
+                          -22.7138 13.8829 4.51081,
+                          -17.6812 16.5044 11.9991,
+                          -11.2162 19.865 14.4423,
+                          -17.6812 19.4065 6.30557,
+                          -22.7138 11.8068 8.58379,
+                          -22.7138 13.8829 4.51081,
+                          -25.9063 7.23448 2.35062,
+                          -22.7138 11.8068 8.58379,
+                          -17.6812 16.5044 11.9991,
+                          -22.7138 13.8829 4.51081,
+                          -25.9063 6.15261 4.47309,
+                          -22.7138 11.8068 8.58379,
+                          -25.9063 7.23448 2.35062,
+                          25.9063 4.46729 6.15682,
+                          25.9063 6.15261 4.47309,
+                          22.7138 11.8068 8.58379,
+                          22.7138 8.57266 11.8149,
+                          22.7138 11.8068 8.58379,
+                          17.6812 16.5044 11.9991,
+                          22.7138 8.57266 11.8149,
+                          25.9063 4.46729 6.15682,
+                          22.7138 11.8068 8.58379,
+                          17.6812 11.9835 16.5157,
+                          17.6812 16.5044 11.9991,
+                          11.2162 19.865 14.4423,
+                          17.6812 11.9835 16.5157,
+                          22.7138 8.57266 11.8149,
+                          17.6812 16.5044 11.9991,
+                          11.2162 14.4236 19.8786,
+                          11.2162 19.865 14.4423,
+                          3.8425 21.6162 15.7155,
+                          11.2162 14.4236 19.8786,
+                          17.6812 11.9835 16.5157,
+                          11.2162 19.865 14.4423,
+                          3.8425 15.6951 21.631,
+                          3.8425 21.6162 15.7155,
+                          -3.8425 21.6162 15.7155,
+                          3.8425 15.6951 21.631,
+                          11.2162 14.4236 19.8786,
+                          3.8425 21.6162 15.7155,
+                          -3.8425 15.6951 21.631,
+                          -3.8425 21.6162 15.7155,
+                          -11.2162 19.865 14.4423,
+                          -3.8425 15.6951 21.631,
+                          3.8425 15.6951 21.631,
+                          -3.8425 21.6162 15.7155,
+                          -11.2162 14.4236 19.8786,
+                          -11.2162 19.865 14.4423,
+                          -17.6812 16.5044 11.9991,
+                          -11.2162 14.4236 19.8786,
+                          -3.8425 15.6951 21.631,
+                          -11.2162 19.865 14.4423,
+                          -17.6812 11.9835 16.5157,
+                          -17.6812 16.5044 11.9991,
+                          -22.7138 11.8068 8.58379,
+                          -17.6812 11.9835 16.5157,
+                          -11.2162 14.4236 19.8786,
+                          -17.6812 16.5044 11.9991,
+                          -22.7138 8.57266 11.8149,
+                          -22.7138 11.8068 8.58379,
+                          -25.9063 6.15261 4.47309,
+                          -22.7138 8.57266 11.8149,
+                          -17.6812 11.9835 16.5157,
+                          -22.7138 11.8068 8.58379,
+                          -25.9063 4.46729 6.15682,
+                          -22.7138 8.57266 11.8149,
+                          -25.9063 6.15261 4.47309,
+                          25.9063 2.3438 7.23669,
+                          25.9063 4.46729 6.15682,
+                          22.7138 8.57266 11.8149,
+                          22.7138 4.49773 13.8871,
+                          22.7138 8.57266 11.8149,
+                          17.6812 11.9835 16.5157,
+                          22.7138 4.49773 13.8871,
+                          25.9063 2.3438 7.23669,
+                          22.7138 8.57266 11.8149,
+                          17.6812 6.28727 19.4125,
+                          17.6812 11.9835 16.5157,
+                          11.2162 14.4236 19.8786,
+                          17.6812 6.28727 19.4125,
+                          22.7138 4.49773 13.8871,
+                          17.6812 11.9835 16.5157,
+                          11.2162 7.56746 23.3652,
+                          11.2162 14.4236 19.8786,
+                          3.8425 15.6951 21.631,
+                          11.2162 7.56746 23.3652,
+                          17.6812 6.28727 19.4125,
+                          11.2162 14.4236 19.8786,
+                          3.8425 8.23458 25.4249,
+                          3.8425 15.6951 21.631,
+                          -3.8425 15.6951 21.631,
+                          3.8425 8.23458 25.4249,
+                          11.2162 7.56746 23.3652,
+                          3.8425 15.6951 21.631,
+                          -3.8425 8.23458 25.4249,
+                          -3.8425 15.6951 21.631,
+                          -11.2162 14.4236 19.8786,
+                          -3.8425 8.23458 25.4249,
+                          3.8425 8.23458 25.4249,
+                          -3.8425 15.6951 21.631,
+                          -11.2162 7.56746 23.3652,
+                          -11.2162 14.4236 19.8786,
+                          -17.6812 11.9835 16.5157,
+                          -11.2162 7.56746 23.3652,
+                          -3.8425 8.23458 25.4249,
+                          -11.2162 14.4236 19.8786,
+                          -17.6812 6.28727 19.4125,
+                          -17.6812 11.9835 16.5157,
+                          -22.7138 8.57266 11.8149,
+                          -17.6812 6.28727 19.4125,
+                          -11.2162 7.56746 23.3652,
+                          -17.6812 11.9835 16.5157,
+                          -22.7138 4.49773 13.8871,
+                          -22.7138 8.57266 11.8149,
+                          -25.9063 4.46729 6.15682,
+                          -22.7138 4.49773 13.8871,
+                          -17.6812 6.28727 19.4125,
+                          -22.7138 8.57266 11.8149,
+                          -25.9063 2.3438 7.23669,
+                          -22.7138 4.49773 13.8871,
+                          -25.9063 4.46729 6.15682,
+                          25.9063 -0.00955896 7.60677,
+                          25.9063 2.3438 7.23669,
+                          22.7138 4.49773 13.8871,
+                          22.7138 -0.0183435 14.5973,
+                          22.7138 4.49773 13.8871,
+                          17.6812 6.28727 19.4125,
+                          22.7138 -0.0183435 14.5973,
+                          25.9063 -0.00955896 7.60677,
+                          22.7138 4.49773 13.8871,
+                          17.6812 -0.025642 20.4052,
+                          17.6812 6.28727 19.4125,
+                          11.2162 7.56746 23.3652,
+                          17.6812 -0.025642 20.4052,
+                          22.7138 -0.0183435 14.5973,
+                          17.6812 6.28727 19.4125,
+                          11.2162 -0.0308631 24.56,
+                          11.2162 7.56746 23.3652,
+                          3.8425 8.23458 25.4249,
+                          11.2162 -0.0308631 24.56,
+                          17.6812 -0.025642 20.4052,
+                          11.2162 7.56746 23.3652,
+                          3.8425 -0.0335838 26.7252,
+                          3.8425 8.23458 25.4249,
+                          -3.8425 8.23458 25.4249,
+                          3.8425 -0.0335838 26.7252,
+                          11.2162 -0.0308631 24.56,
+                          3.8425 8.23458 25.4249,
+                          -3.8425 -0.0335838 26.7252,
+                          -3.8425 8.23458 25.4249,
+                          -11.2162 7.56746 23.3652,
+                          -3.8425 -0.0335838 26.7252,
+                          3.8425 -0.0335838 26.7252,
+                          -3.8425 8.23458 25.4249,
+                          -11.2162 -0.0308631 24.56,
+                          -11.2162 7.56746 23.3652,
+                          -17.6812 6.28727 19.4125,
+                          -11.2162 -0.0308631 24.56,
+                          -3.8425 -0.0335838 26.7252,
+                          -11.2162 7.56746 23.3652,
+                          -17.6812 -0.025642 20.4052,
+                          -17.6812 6.28727 19.4125,
+                          -22.7138 4.49773 13.8871,
+                          -17.6812 -0.025642 20.4052,
+                          -11.2162 -0.0308631 24.56,
+                          -17.6812 6.28727 19.4125,
+                          -22.7138 -0.0183435 14.5973,
+                          -22.7138 4.49773 13.8871,
+                          -25.9063 2.3438 7.23669,
+                          -22.7138 -0.0183435 14.5973,
+                          -17.6812 -0.025642 20.4052,
+                          -22.7138 4.49773 13.8871,
+                          -25.9063 -0.00955896 7.60677,
+                          -22.7138 -0.0183435 14.5973,
+                          -25.9063 2.3438 7.23669,
+                          25.9063 -2.36198 7.23078,
+                          25.9063 -0.00955896 7.60677,
+                          22.7138 -0.0183435 14.5973,
+                          22.7138 -4.53262 13.8758,
+                          22.7138 -0.0183435 14.5973,
+                          17.6812 -0.025642 20.4052,
+                          22.7138 -4.53262 13.8758,
+                          25.9063 -2.36198 7.23078,
+                          22.7138 -0.0183435 14.5973,
+                          17.6812 -6.33604 19.3966,
+                          17.6812 -0.025642 20.4052,
+                          11.2162 -0.0308631 24.56,
+                          17.6812 -6.33604 19.3966,
+                          22.7138 -4.53262 13.8758,
+                          17.6812 -0.025642 20.4052,
+                          11.2162 -7.62616 23.3461,
+                          11.2162 -0.0308631 24.56,
+                          3.8425 -0.0335838 26.7252,
+                          11.2162 -7.62616 23.3461,
+                          17.6812 -6.33604 19.3966,
+                          11.2162 -0.0308631 24.56,
+                          3.8425 -8.29845 25.4042,
+                          3.8425 -0.0335838 26.7252,
+                          -3.8425 -0.0335838 26.7252,
+                          3.8425 -8.29845 25.4042,
+                          11.2162 -7.62616 23.3461,
+                          3.8425 -0.0335838 26.7252,
+                          -3.8425 -8.29845 25.4042,
+                          -3.8425 -0.0335838 26.7252,
+                          -11.2162 -0.0308631 24.56,
+                          -3.8425 -8.29845 25.4042,
+                          3.8425 -8.29845 25.4042,
+                          -3.8425 -0.0335838 26.7252,
+                          -11.2162 -7.62616 23.3461,
+                          -11.2162 -0.0308631 24.56,
+                          -17.6812 -0.025642 20.4052,
+                          -11.2162 -7.62616 23.3461,
+                          -3.8425 -8.29845 25.4042,
+                          -11.2162 -0.0308631 24.56,
+                          -17.6812 -6.33604 19.3966,
+                          -17.6812 -0.025642 20.4052,
+                          -22.7138 -0.0183435 14.5973,
+                          -17.6812 -6.33604 19.3966,
+                          -11.2162 -7.62616 23.3461,
+                          -17.6812 -0.025642 20.4052,
+                          -22.7138 -4.53262 13.8758,
+                          -22.7138 -0.0183435 14.5973,
+                          -25.9063 -0.00955896 7.60677,
+                          -22.7138 -4.53262 13.8758,
+                          -17.6812 -6.33604 19.3966,
+                          -22.7138 -0.0183435 14.5973,
+                          -25.9063 -2.36198 7.23078,
+                          -22.7138 -4.53262 13.8758,
+                          -25.9063 -0.00955896 7.60677,
+                          25.9063 -4.48274 6.14557,
+                          25.9063 -2.36198 7.23078,
+                          22.7138 -4.53262 13.8758,
+                          22.7138 -8.60232 11.7933,
+                          22.7138 -4.53262 13.8758,
+                          17.6812 -6.33604 19.3966,
+                          22.7138 -8.60232 11.7933,
+                          25.9063 -4.48274 6.14557,
+                          22.7138 -4.53262 13.8758,
+                          17.6812 -12.025 16.4855,
+                          17.6812 -6.33604 19.3966,
+                          11.2162 -7.62616 23.3461,
+                          17.6812 -12.025 16.4855,
+                          22.7138 -8.60232 11.7933,
+                          17.6812 -6.33604 19.3966,
+                          11.2162 -14.4735 19.8423,
+                          11.2162 -7.62616 23.3461,
+                          3.8425 -8.29845 25.4042,
+                          11.2162 -14.4735 19.8423,
+                          17.6812 -12.025 16.4855,
+                          11.2162 -7.62616 23.3461,
+                          3.8425 -15.7494 21.5915,
+                          3.8425 -8.29845 25.4042,
+                          -3.8425 -8.29845 25.4042,
+                          3.8425 -15.7494 21.5915,
+                          11.2162 -14.4735 19.8423,
+                          3.8425 -8.29845 25.4042,
+                          -3.8425 -15.7494 21.5915,
+                          -3.8425 -8.29845 25.4042,
+                          -11.2162 -7.62616 23.3461,
+                          -3.8425 -15.7494 21.5915,
+                          3.8425 -15.7494 21.5915,
+                          -3.8425 -8.29845 25.4042,
+                          -11.2162 -14.4735 19.8423,
+                          -11.2162 -7.62616 23.3461,
+                          -17.6812 -6.33604 19.3966,
+                          -11.2162 -14.4735 19.8423,
+                          -3.8425 -15.7494 21.5915,
+                          -11.2162 -7.62616 23.3461,
+                          -17.6812 -12.025 16.4855,
+                          -17.6812 -6.33604 19.3966,
+                          -22.7138 -4.53262 13.8758,
+                          -17.6812 -12.025 16.4855,
+                          -11.2162 -14.4735 19.8423,
+                          -17.6812 -6.33604 19.3966,
+                          -22.7138 -8.60232 11.7933,
+                          -22.7138 -4.53262 13.8758,
+                          -25.9063 -2.36198 7.23078,
+                          -22.7138 -8.60232 11.7933,
+                          -17.6812 -12.025 16.4855,
+                          -22.7138 -4.53262 13.8758,
+                          -25.9063 -4.48274 6.14557,
+                          -22.7138 -8.60232 11.7933,
+                          -25.9063 -2.36198 7.23078,
+                          25.9063 -6.16383 4.45761,
+                          25.9063 -4.48274 6.14557,
+                          22.7138 -8.60232 11.7933,
+                          22.7138 -11.8283 8.55409,
+                          22.7138 -8.60232 11.7933,
+                          17.6812 -12.025 16.4855,
+                          22.7138 -11.8283 8.55409,
+                          25.9063 -6.16383 4.45761,
+                          22.7138 -8.60232 11.7933,
+                          17.6812 -16.5345 11.9576,
+                          17.6812 -12.025 16.4855,
+                          11.2162 -14.4735 19.8423,
+                          17.6812 -16.5345 11.9576,
+                          22.7138 -11.8283 8.55409,
+                          17.6812 -12.025 16.4855,
+                          11.2162 -19.9012 14.3923,
+                          11.2162 -14.4735 19.8423,
+                          3.8425 -15.7494 21.5915,
+                          11.2162 -19.9012 14.3923,
+                          17.6812 -16.5345 11.9576,
+                          11.2162 -14.4735 19.8423,
+                          3.8425 -21.6556 15.6611,
+                          3.8425 -15.7494 21.5915,
+                          -3.8425 -15.7494 21.5915,
+                          3.8425 -21.6556 15.6611,
+                          11.2162 -19.9012 14.3923,
+                          3.8425 -15.7494 21.5915,
+                          -3.8425 -21.6556 15.6611,
+                          -3.8425 -15.7494 21.5915,
+                          -11.2162 -14.4735 19.8423,
+                          -3.8425 -21.6556 15.6611,
+                          3.8425 -21.6556 15.6611,
+                          -3.8425 -15.7494 21.5915,
+                          -11.2162 -19.9012 14.3923,
+                          -11.2162 -14.4735 19.8423,
+                          -17.6812 -12.025 16.4855,
+                          -11.2162 -19.9012 14.3923,
+                          -3.8425 -21.6556 15.6611,
+                          -11.2162 -14.4735 19.8423,
+                          -17.6812 -16.5345 11.9576,
+                          -17.6812 -12.025 16.4855,
+                          -22.7138 -8.60232 11.7933,
+                          -17.6812 -16.5345 11.9576,
+                          -11.2162 -19.9012 14.3923,
+                          -17.6812 -12.025 16.4855,
+                          -22.7138 -11.8283 8.55409,
+                          -22.7138 -8.60232 11.7933,
+                          -25.9063 -4.48274 6.14557,
+                          -22.7138 -11.8283 8.55409,
+                          -17.6812 -16.5345 11.9576,
+                          -22.7138 -8.60232 11.7933,
+                          -25.9063 -6.16383 4.45761,
+                          -22.7138 -11.8283 8.55409,
+                          -25.9063 -4.48274 6.14557,
+                          25.9063 -7.24036 2.33243,
+                          25.9063 -6.16383 4.45761,
+                          22.7138 -11.8283 8.55409,
+                          22.7138 -13.8942 4.47591,
+                          22.7138 -11.8283 8.55409,
+                          17.6812 -16.5345 11.9576,
+                          22.7138 -13.8942 4.47591,
+                          25.9063 -7.24036 2.33243,
+                          22.7138 -11.8283 8.55409,
+                          17.6812 -19.4223 6.25677,
+                          17.6812 -16.5345 11.9576,
+                          11.2162 -19.9012 14.3923,
+                          17.6812 -19.4223 6.25677,
+                          22.7138 -13.8942 4.47591,
+                          17.6812 -16.5345 11.9576,
+                          11.2162 -23.377 7.53075,
+                          11.2162 -19.9012 14.3923,
+                          3.8425 -21.6556 15.6611,
+                          11.2162 -23.377 7.53075,
+                          17.6812 -19.4223 6.25677,
+                          11.2162 -19.9012 14.3923,
+                          3.8425 -25.4378 8.19463,
+                          3.8425 -21.6556 15.6611,
+                          -3.8425 -21.6556 15.6611,
+                          3.8425 -25.4378 8.19463,
+                          11.2162 -23.377 7.53075,
+                          3.8425 -21.6556 15.6611,
+                          -3.8425 -25.4378 8.19463,
+                          -3.8425 -21.6556 15.6611,
+                          -11.2162 -19.9012 14.3923,
+                          -3.8425 -25.4378 8.19463,
+                          3.8425 -25.4378 8.19463,
+                          -3.8425 -21.6556 15.6611,
+                          -11.2162 -23.377 7.53075,
+                          -11.2162 -19.9012 14.3923,
+                          -17.6812 -16.5345 11.9576,
+                          -11.2162 -23.377 7.53075,
+                          -3.8425 -25.4378 8.19463,
+                          -11.2162 -19.9012 14.3923,
+                          -17.6812 -19.4223 6.25677,
+                          -17.6812 -16.5345 11.9576,
+                          -22.7138 -11.8283 8.55409,
+                          -17.6812 -19.4223 6.25677,
+                          -11.2162 -23.377 7.53075,
+                          -17.6812 -16.5345 11.9576,
+                          -22.7138 -13.8942 4.47591,
+                          -22.7138 -11.8283 8.55409,
+                          -25.9063 -6.16383 4.45761,
+                          -22.7138 -13.8942 4.47591,
+                          -17.6812 -19.4223 6.25677,
+                          -22.7138 -11.8283 8.55409,
+                          -25.9063 -7.24036 2.33243,
+                          -22.7138 -13.8942 4.47591,
+                          -25.9063 -6.16383 4.45761 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/handlink_green.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/handlink_green.iv
new file mode 100644
index 0000000000000000000000000000000000000000..8331696d2519a470d5a9c6555fdc8fc7c9e0c14b
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/handlink_green.iv
@@ -0,0 +1,1203 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+
+    Material {
+        diffuseColor    0 0 1
+    }
+    Separator {
+        Normal {
+            vector      [ -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          0.177778 0.984071 1.97367e-17,
+                          0.177778 0.984071 1.97367e-17,
+                          0.998959 0.0456073 1.34135e-16,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          1 1.70569e-16 1.34468e-16,
+                          0.998959 0.0456073 1.34135e-16,
+                          0.266667 -0.963789 3.9941e-17,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          0.177778 0.984071 1.97367e-17,
+                          0.998959 0.0456073 1.34135e-16,
+                          1 1.70569e-16 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 1.70569e-16 1.34468e-16,
+                          0.266667 -0.963789 3.9941e-17,
+                          0.177778 -0.984071 2.80742e-17,
+                          0.177778 -0.984071 2.80742e-17,
+                          0.177778 -0.984071 2.80742e-17,
+                          0.266667 -0.963789 3.9941e-17,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          0.22253 -0.974926 3.40532e-17,
+                          0.266667 -0.963789 3.9941e-17,
+                          0.266667 -0.963789 3.9941e-17,
+                          0.177778 -0.984071 2.80742e-17,
+                          0.266667 -0.963789 3.9941e-17,
+                          0.22253 -0.974926 3.40532e-17,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -1 1.73936e-16 -1.34468e-16,
+                          -0.266667 -0.963789 -3.17754e-17,
+                          -0.998959 0.0456073 -1.34521e-16,
+                          -0.177778 -0.984071 -1.97367e-17,
+                          -0.266667 -0.963789 -3.17754e-17,
+                          -1 1.73936e-16 -1.34468e-16,
+                          -0.266667 -0.963789 -3.17754e-17,
+                          -0.266667 -0.963789 -3.17754e-17,
+                          -0.177778 -0.984071 -1.97367e-17,
+                          -1 1.73936e-16 -1.34468e-16,
+                          -0.998959 0.0456073 -1.34521e-16,
+                          -0.177778 0.984071 -2.80742e-17,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.73936e-16 -1.34468e-16,
+                          -0.177778 0.984071 -2.80742e-17,
+                          -0.177778 0.984071 -2.80742e-17,
+                          1 2.318e-16 1.34468e-16,
+                          1 2.318e-16 1.34468e-16,
+                          -1.77407e-16 1 -4.23622e-18,
+                          5.49466e-17 -1 4.23622e-18,
+                          5.49466e-17 -1 4.23622e-18,
+                          1 1.09339e-16 1.34468e-16,
+                          5.49466e-17 -1 4.23622e-18,
+                          1 1.09339e-16 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          -1.77407e-16 1 -4.23622e-18,
+                          -1.77407e-16 1 -4.23622e-18,
+                          -1 -1.09339e-16 -1.34468e-16,
+                          -1.77407e-16 1 -4.23622e-18,
+                          1 2.318e-16 1.34468e-16,
+                          -1.77407e-16 1 -4.23622e-18,
+                          -1 -1.09339e-16 -1.34468e-16,
+                          -1 -1.09339e-16 -1.34468e-16,
+                          5.49466e-17 -1 4.23622e-18,
+                          -1.77407e-16 1 -4.23622e-18,
+                          -1 -1.09339e-16 -1.34468e-16,
+                          -1 -1.09339e-16 -1.34468e-16,
+                          -1 -1.09339e-16 -1.34468e-16,
+                          5.49466e-17 -1 4.23622e-18,
+                          5.49466e-17 -1 4.23622e-18,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -0.22253 -0.974926 -2.57932e-17,
+                          -0.177778 -0.984071 -1.97367e-17,
+                          -0.177778 -0.984071 -1.97367e-17,
+                          -0.266667 -0.963789 -3.17754e-17,
+                          -0.177778 -0.984071 -1.97367e-17,
+                          -0.22253 -0.974926 -2.57932e-17,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 4 19 -25,
+                          4 23 -25,
+                          -4 23 -25,
+                          4 23 -35,
+                          -4 23 -25,
+                          4 23 -25,
+                          -4 19 -25,
+                          4 19 -25,
+                          -4 23 -25,
+                          -4 22.1416 -32,
+                          -4 19 -25,
+                          -4 23 -25,
+                          -4 23 -35,
+                          -4 22.1416 -32,
+                          -4 23 -25,
+                          4 23 -35,
+                          -4 23 -35,
+                          -4 23 -25,
+                          4 19 -32,
+                          4 23 -25,
+                          4 19 -25,
+                          4 22.1416 -32,
+                          4 23 -25,
+                          4 19 -32,
+                          4 22.1416 -35,
+                          4 23 -25,
+                          4 22.1416 -32,
+                          4 23 -35,
+                          4 23 -25,
+                          4 22.1416 -35,
+                          4 19 -32,
+                          4 19 -25,
+                          -4 19 -25,
+                          -4 19 -32,
+                          4 19 -32,
+                          -4 19 -25,
+                          -4 22.1416 -32,
+                          -4 19 -32,
+                          -4 19 -25,
+                          7.64696e-14 14.9998 -32,
+                          4 19 -32,
+                          -4 19 -32,
+                          15 8.49018e-14 -32,
+                          4 22.1416 -32,
+                          4 19 -32,
+                          7.64696e-14 14.9998 -32,
+                          15 8.49018e-14 -32,
+                          4 19 -32,
+                          -4 22.1416 -32,
+                          -22.4766 1.02616 -32,
+                          -4 19 -32,
+                          -15 8.17427e-14 -32,
+                          -4 19 -32,
+                          -22.4766 1.02616 -32,
+                          7.64696e-14 14.9998 -32,
+                          -4 19 -32,
+                          -15 8.17427e-14 -32,
+                          15 8.49018e-14 -32,
+                          22.4766 1.02616 -32,
+                          4 22.1416 -32,
+                          4 22.1416 -35,
+                          4 22.1416 -32,
+                          22.4766 1.02616 -32,
+                          6 -16 -32,
+                          6 -21.6852 -32,
+                          22.4766 1.02616 -32,
+                          22.4998 8.14172e-14 -35,
+                          22.4766 1.02616 -32,
+                          6 -21.6852 -32,
+                          15 8.49018e-14 -32,
+                          6 -16 -32,
+                          22.4766 1.02616 -32,
+                          4 22.1416 -35,
+                          22.4766 1.02616 -32,
+                          22.4998 8.14172e-14 -35,
+                          6 -16 -25,
+                          6 -21.6852 -32,
+                          6 -16 -32,
+                          22.4998 8.14172e-14 -35,
+                          6 -21.6852 -32,
+                          4 -22.1416 -35,
+                          4 -22.1416 -25,
+                          4 -22.1416 -35,
+                          6 -21.6852 -32,
+                          6 -21.6852 -25,
+                          6 -21.6852 -32,
+                          6 -16 -25,
+                          5.00693 -21.9358 -25,
+                          6 -21.6852 -32,
+                          6 -21.6852 -25,
+                          4 -22.1416 -25,
+                          6 -21.6852 -32,
+                          5.00693 -21.9358 -25,
+                          7.98338e-14 -14.9998 -32,
+                          -6 -16 -32,
+                          6 -16 -32,
+                          6 -16 -25,
+                          6 -16 -32,
+                          -6 -16 -32,
+                          15 8.49018e-14 -32,
+                          7.98338e-14 -14.9998 -32,
+                          6 -16 -32,
+                          -15 8.17427e-14 -32,
+                          -6 -21.6852 -32,
+                          -6 -16 -32,
+                          -6 -21.6852 -25,
+                          -6 -16 -32,
+                          -6 -21.6852 -32,
+                          7.98338e-14 -14.9998 -32,
+                          -15 8.17427e-14 -32,
+                          -6 -16 -32,
+                          -6 -16 -25,
+                          6 -16 -25,
+                          -6 -16 -32,
+                          -6 -21.6852 -25,
+                          -6 -16 -25,
+                          -6 -16 -32,
+                          -15 8.17427e-14 -32,
+                          -22.4766 1.02616 -32,
+                          -6 -21.6852 -32,
+                          -22.4998 8.55604e-14 -35,
+                          -6 -21.6852 -32,
+                          -22.4766 1.02616 -32,
+                          -4 -22.1416 -35,
+                          -6 -21.6852 -32,
+                          -22.4998 8.55604e-14 -35,
+                          -6 -21.6852 -25,
+                          -6 -21.6852 -32,
+                          -4 -22.1416 -35,
+                          -22.4998 8.55604e-14 -35,
+                          -22.4766 1.02616 -32,
+                          -4 22.1416 -32,
+                          -4 22.1416 -35,
+                          -4 22.1416 -32,
+                          -4 23 -35,
+                          -22.4998 8.55604e-14 -35,
+                          -4 22.1416 -32,
+                          -4 22.1416 -35,
+                          -15 7.83565e-14 -35,
+                          -15 8.17427e-14 -32,
+                          7.98338e-14 -14.9998 -32,
+                          7.66525e-14 14.9998 -35,
+                          7.64696e-14 14.9998 -32,
+                          -15 8.17427e-14 -32,
+                          7.66525e-14 14.9998 -35,
+                          -15 8.17427e-14 -32,
+                          -15 7.83565e-14 -35,
+                          8.00167e-14 -14.9998 -35,
+                          7.98338e-14 -14.9998 -32,
+                          15 8.49018e-14 -32,
+                          8.00167e-14 -14.9998 -35,
+                          -15 7.83565e-14 -35,
+                          7.98338e-14 -14.9998 -32,
+                          15 8.15156e-14 -35,
+                          15 8.49018e-14 -32,
+                          7.64696e-14 14.9998 -32,
+                          8.00167e-14 -14.9998 -35,
+                          15 8.49018e-14 -32,
+                          15 8.15156e-14 -35,
+                          15 8.15156e-14 -35,
+                          7.64696e-14 14.9998 -32,
+                          7.66525e-14 14.9998 -35,
+                          4 22.1416 -35,
+                          -4 22.1416 -35,
+                          -4 23 -35,
+                          4 23 -35,
+                          4 22.1416 -35,
+                          -4 23 -35,
+                          -15 7.83565e-14 -35,
+                          -22.4998 8.55604e-14 -35,
+                          -4 22.1416 -35,
+                          4 22.1416 -35,
+                          22.4998 8.14172e-14 -35,
+                          -4 22.1416 -35,
+                          7.66525e-14 14.9998 -35,
+                          -4 22.1416 -35,
+                          22.4998 8.14172e-14 -35,
+                          7.66525e-14 14.9998 -35,
+                          -15 7.83565e-14 -35,
+                          -4 22.1416 -35,
+                          4 -22.1416 -35,
+                          -4 -22.1416 -35,
+                          -22.4998 8.55604e-14 -35,
+                          8.00167e-14 -14.9998 -35,
+                          4 -22.1416 -35,
+                          -22.4998 8.55604e-14 -35,
+                          8.00167e-14 -14.9998 -35,
+                          -22.4998 8.55604e-14 -35,
+                          -15 7.83565e-14 -35,
+                          4 -23 -35,
+                          -4 -23 -35,
+                          -4 -22.1416 -35,
+                          -4 -23 -25,
+                          -4 -22.1416 -35,
+                          -4 -23 -35,
+                          4 -22.1416 -35,
+                          4 -23 -35,
+                          -4 -22.1416 -35,
+                          -4 -22.1416 -25,
+                          -4 -22.1416 -35,
+                          -4 -23 -25,
+                          -5.00693 -21.9358 -25,
+                          -4 -22.1416 -35,
+                          -4 -22.1416 -25,
+                          -6 -21.6852 -25,
+                          -4 -22.1416 -35,
+                          -5.00693 -21.9358 -25,
+                          4 -23 -25,
+                          -4 -23 -35,
+                          4 -23 -35,
+                          4 -23 -25,
+                          -4 -23 -25,
+                          -4 -23 -35,
+                          4 -22.1416 -25,
+                          4 -23 -35,
+                          4 -22.1416 -35,
+                          4 -22.1416 -25,
+                          4 -23 -25,
+                          4 -23 -35,
+                          15 8.15156e-14 -35,
+                          22.4998 8.14172e-14 -35,
+                          4 -22.1416 -35,
+                          8.00167e-14 -14.9998 -35,
+                          15 8.15156e-14 -35,
+                          4 -22.1416 -35,
+                          15 8.15156e-14 -35,
+                          7.66525e-14 14.9998 -35,
+                          22.4998 8.14172e-14 -35,
+                          -4 -22.1416 -25,
+                          -4 -23 -25,
+                          4 -23 -25,
+                          4 -22.1416 -25,
+                          -6 -16 -25,
+                          4 -23 -25,
+                          -4 -22.1416 -25,
+                          4 -23 -25,
+                          -6 -16 -25,
+                          6 -21.6852 -25,
+                          6 -16 -25,
+                          -6 -16 -25,
+                          5.00693 -21.9358 -25,
+                          6 -21.6852 -25,
+                          -6 -16 -25,
+                          4 -22.1416 -25,
+                          5.00693 -21.9358 -25,
+                          -6 -16 -25,
+                          -5.00693 -21.9358 -25,
+                          -4 -22.1416 -25,
+                          -6 -16 -25,
+                          -6 -21.6852 -25,
+                          -5.00693 -21.9358 -25,
+                          -6 -16 -25 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.403873 0.7 0.420213
+    }
+    Separator {
+        Normal {
+            vector      [ -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -0.347826 5.6609e-17 -0.937559,
+                          -0.347826 5.6609e-17 -0.937559,
+                          -0.959164 2.8287e-17 -0.28285,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -0.959164 2.8287e-17 -0.28285,
+                          -0.959164 2.8287e-17 -0.28285,
+                          -0.80089 -2.27318e-17 0.598811,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -0.347826 5.6609e-17 -0.937559,
+                          -0.959164 2.8287e-17 -0.28285,
+                          -0.959164 2.8287e-17 -0.28285,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -0.80089 -2.27318e-17 0.598811,
+                          -0.80089 -2.27318e-17 0.598811,
+                          -2.44648e-16 -5.55112e-17 1,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -0.959164 2.8287e-17 -0.28285,
+                          -0.80089 -2.27318e-17 0.598811,
+                          -0.80089 -2.27318e-17 0.598811,
+                          -2.44648e-16 -5.55112e-17 1,
+                          -2.44648e-16 -5.55112e-17 1,
+                          0.80089 -4.37496e-17 0.598811,
+                          -0.80089 -2.27318e-17 0.598811,
+                          -2.44648e-16 -5.55112e-17 1,
+                          -2.44648e-16 -5.55112e-17 1,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          0.80089 -4.37496e-17 0.598811,
+                          0.80089 -4.37496e-17 0.598811,
+                          0.959164 3.11568e-18 -0.28285,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -2.44648e-16 -5.55112e-17 1,
+                          0.80089 -4.37496e-17 0.598811,
+                          0.80089 -4.37496e-17 0.598811,
+                          0.959164 3.11568e-18 -0.28285,
+                          0.959164 3.11568e-18 -0.28285,
+                          0.347826 4.7481e-17 -0.937559,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          0.80089 -4.37496e-17 0.598811,
+                          0.959164 3.11568e-18 -0.28285,
+                          0.959164 3.11568e-18 -0.28285,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          0.959164 3.11568e-18 -0.28285,
+                          0.347826 4.7481e-17 -0.937559,
+                          0.347826 4.7481e-17 -0.937559,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          -1 1.31215e-17 -3.79389e-16,
+                          -1 1.31215e-17 -3.79389e-16,
+                          2.44648e-16 5.55112e-17 -1,
+                          -1.22187e-16 -5.55112e-17 1,
+                          -1.22187e-16 -5.55112e-17 1,
+                          -1 1.31215e-17 1.8716e-16,
+                          -1.22187e-16 -5.55112e-17 1,
+                          -1 1.31215e-17 1.8716e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          2.44648e-16 5.55112e-17 -1,
+                          2.44648e-16 5.55112e-17 -1,
+                          1 -1.31215e-17 2.56929e-16,
+                          2.44648e-16 5.55112e-17 -1,
+                          -1 1.31215e-17 -3.79389e-16,
+                          2.44648e-16 5.55112e-17 -1,
+                          1 -1.31215e-17 2.56929e-16,
+                          1 -1.31215e-17 2.56929e-16,
+                          -1.22187e-16 -5.55112e-17 1,
+                          2.44648e-16 5.55112e-17 -1,
+                          1 -1.31215e-17 2.56929e-16,
+                          1 -1.31215e-17 2.56929e-16,
+                          1 -1.31215e-17 2.56929e-16,
+                          -1.22187e-16 -5.55112e-17 1,
+                          -1.22187e-16 -5.55112e-17 1,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 4 -29 -10.7819,
+                          -4 -29 -10.7819,
+                          -4 -29 -36,
+                          -4 -23 -36,
+                          -4 -29 -36,
+                          -4 -29 -10.7819,
+                          4 -29 -36,
+                          4 -29 -10.7819,
+                          -4 -29 -36,
+                          4 -23 -36,
+                          4 -29 -36,
+                          -4 -29 -36,
+                          4 -23 -36,
+                          -4 -29 -36,
+                          -4 -23 -36,
+                          7.47007e-14 -29 -3.75,
+                          -11.0305 -29 -3.25208,
+                          -4 -29 -10.7819,
+                          -4 -23 -10.7819,
+                          -4 -29 -10.7819,
+                          -11.0305 -29 -3.25208,
+                          4 -29 -10.7819,
+                          11.0305 -29 -3.25208,
+                          -4 -29 -10.7819,
+                          7.47007e-14 -29 -3.75,
+                          -4 -29 -10.7819,
+                          11.0305 -29 -3.25208,
+                          -4 -23 -10.7819,
+                          -4 -23 -36,
+                          -4 -29 -10.7819,
+                          7.39749e-14 -29 3.75,
+                          -9.20978 -29 6.88671,
+                          -11.0305 -29 -3.25208,
+                          -11.0305 -23 -3.25208,
+                          -11.0305 -29 -3.25208,
+                          -9.20978 -29 6.88671,
+                          -3.75 -29 -1.98004e-13,
+                          7.39749e-14 -29 3.75,
+                          -11.0305 -29 -3.25208,
+                          7.47007e-14 -29 -3.75,
+                          -3.75 -29 -1.98004e-13,
+                          -11.0305 -29 -3.25208,
+                          -4 -23 -10.7819,
+                          -11.0305 -29 -3.25208,
+                          -11.0305 -23 -3.25208,
+                          9.20978 -29 6.88671,
+                          7.65391e-14 -29 11.4998,
+                          -9.20978 -29 6.88671,
+                          -9.20978 -23 6.88671,
+                          -9.20978 -29 6.88671,
+                          7.65391e-14 -29 11.4998,
+                          7.39749e-14 -29 3.75,
+                          9.20978 -29 6.88671,
+                          -9.20978 -29 6.88671,
+                          -11.0305 -23 -3.25208,
+                          -9.20978 -29 6.88671,
+                          -9.20978 -23 6.88671,
+                          7.65768e-14 -23 11.4998,
+                          7.65391e-14 -29 11.4998,
+                          9.20978 -29 6.88671,
+                          -9.20978 -23 6.88671,
+                          7.65391e-14 -29 11.4998,
+                          7.65768e-14 -23 11.4998,
+                          3.75 -29 -1.99408e-13,
+                          11.0305 -29 -3.25208,
+                          9.20978 -29 6.88671,
+                          9.20978 -23 6.88671,
+                          9.20978 -29 6.88671,
+                          11.0305 -29 -3.25208,
+                          7.39749e-14 -29 3.75,
+                          3.75 -29 -1.99408e-13,
+                          9.20978 -29 6.88671,
+                          7.65768e-14 -23 11.4998,
+                          9.20978 -29 6.88671,
+                          9.20978 -23 6.88671,
+                          11.0305 -23 -3.25208,
+                          11.0305 -29 -3.25208,
+                          4 -29 -10.7819,
+                          7.47007e-14 -29 -3.75,
+                          11.0305 -29 -3.25208,
+                          3.75 -29 -1.99408e-13,
+                          9.20978 -23 6.88671,
+                          11.0305 -29 -3.25208,
+                          11.0305 -23 -3.25208,
+                          4 -23 -10.7819,
+                          4 -29 -10.7819,
+                          4 -29 -36,
+                          11.0305 -23 -3.25208,
+                          4 -29 -10.7819,
+                          4 -23 -10.7819,
+                          4 -23 -10.7819,
+                          4 -29 -36,
+                          4 -23 -36,
+                          3.75 -23 -1.97768e-13,
+                          3.75 -29 -1.99408e-13,
+                          7.39749e-14 -29 3.75,
+                          7.47384e-14 -23 -3.75,
+                          7.47007e-14 -29 -3.75,
+                          3.75 -29 -1.99408e-13,
+                          7.47384e-14 -23 -3.75,
+                          3.75 -29 -1.99408e-13,
+                          3.75 -23 -1.97768e-13,
+                          7.33628e-14 -23 3.75,
+                          7.39749e-14 -29 3.75,
+                          -3.75 -29 -1.98004e-13,
+                          7.33628e-14 -23 3.75,
+                          3.75 -23 -1.97768e-13,
+                          7.39749e-14 -29 3.75,
+                          -3.75 -23 -1.99695e-13,
+                          -3.75 -29 -1.98004e-13,
+                          7.47007e-14 -29 -3.75,
+                          7.33628e-14 -23 3.75,
+                          -3.75 -29 -1.98004e-13,
+                          -3.75 -23 -1.99695e-13,
+                          -3.75 -23 -1.99695e-13,
+                          7.47007e-14 -29 -3.75,
+                          7.47384e-14 -23 -3.75,
+                          -4 -23 -10.7819,
+                          4 -23 -36,
+                          -4 -23 -36,
+                          -4 -23 -10.7819,
+                          4 -23 -10.7819,
+                          4 -23 -36,
+                          7.47384e-14 -23 -3.75,
+                          11.0305 -23 -3.25208,
+                          4 -23 -10.7819,
+                          -4 -23 -10.7819,
+                          -11.0305 -23 -3.25208,
+                          4 -23 -10.7819,
+                          7.47384e-14 -23 -3.75,
+                          4 -23 -10.7819,
+                          -11.0305 -23 -3.25208,
+                          7.33628e-14 -23 3.75,
+                          9.20978 -23 6.88671,
+                          11.0305 -23 -3.25208,
+                          7.47384e-14 -23 -3.75,
+                          3.75 -23 -1.97768e-13,
+                          11.0305 -23 -3.25208,
+                          7.33628e-14 -23 3.75,
+                          11.0305 -23 -3.25208,
+                          3.75 -23 -1.97768e-13,
+                          -9.20978 -23 6.88671,
+                          7.65768e-14 -23 11.4998,
+                          9.20978 -23 6.88671,
+                          7.33628e-14 -23 3.75,
+                          -9.20978 -23 6.88671,
+                          9.20978 -23 6.88671,
+                          -3.75 -23 -1.99695e-13,
+                          -11.0305 -23 -3.25208,
+                          -9.20978 -23 6.88671,
+                          7.33628e-14 -23 3.75,
+                          -3.75 -23 -1.99695e-13,
+                          -9.20978 -23 6.88671,
+                          -3.75 -23 -1.99695e-13,
+                          7.47384e-14 -23 -3.75,
+                          -11.0305 -23 -3.25208 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          0.347826 4.7481e-17 -0.937559,
+                          0.347826 4.7481e-17 -0.937559,
+                          0.959164 3.11568e-18 -0.28285,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          0.959164 3.11568e-18 -0.28285,
+                          0.959164 3.11568e-18 -0.28285,
+                          0.80089 -4.37496e-17 0.598811,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          0.347826 4.7481e-17 -0.937559,
+                          0.959164 3.11568e-18 -0.28285,
+                          0.959164 3.11568e-18 -0.28285,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          0.80089 -4.37496e-17 0.598811,
+                          0.80089 -4.37496e-17 0.598811,
+                          1.22734e-16 -5.55112e-17 1,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          0.959164 3.11568e-18 -0.28285,
+                          0.80089 -4.37496e-17 0.598811,
+                          0.80089 -4.37496e-17 0.598811,
+                          1.22734e-16 -5.55112e-17 1,
+                          1.22734e-16 -5.55112e-17 1,
+                          -0.80089 -2.27318e-17 0.598811,
+                          0.80089 -4.37496e-17 0.598811,
+                          1.22734e-16 -5.55112e-17 1,
+                          1.22734e-16 -5.55112e-17 1,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          -0.80089 -2.27318e-17 0.598811,
+                          -0.80089 -2.27318e-17 0.598811,
+                          -0.959164 2.8287e-17 -0.28285,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          1.22734e-16 -5.55112e-17 1,
+                          -0.80089 -2.27318e-17 0.598811,
+                          -0.80089 -2.27318e-17 0.598811,
+                          -0.959164 2.8287e-17 -0.28285,
+                          -0.959164 2.8287e-17 -0.28285,
+                          -0.347826 5.6609e-17 -0.937559,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          -0.80089 -2.27318e-17 0.598811,
+                          -0.959164 2.8287e-17 -0.28285,
+                          -0.959164 2.8287e-17 -0.28285,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -0.959164 2.8287e-17 -0.28285,
+                          -0.347826 5.6609e-17 -0.937559,
+                          -0.347826 5.6609e-17 -0.937559,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          1 -1.31215e-17 -1.10453e-16,
+                          1 -1.31215e-17 -1.10453e-16,
+                          -1.22734e-16 5.55112e-17 -1,
+                          2.73592e-19 -5.55112e-17 1,
+                          2.73592e-19 -5.55112e-17 1,
+                          1 -1.31215e-17 4.56097e-16,
+                          2.73592e-19 -5.55112e-17 1,
+                          1 -1.31215e-17 4.56097e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          -1.22734e-16 5.55112e-17 -1,
+                          -1.22734e-16 5.55112e-17 -1,
+                          -1 1.31215e-17 -1.20075e-17,
+                          -1.22734e-16 5.55112e-17 -1,
+                          1 -1.31215e-17 -1.10453e-16,
+                          -1.22734e-16 5.55112e-17 -1,
+                          -1 1.31215e-17 -1.20075e-17,
+                          -1 1.31215e-17 -1.20075e-17,
+                          2.73592e-19 -5.55112e-17 1,
+                          -1.22734e-16 5.55112e-17 -1,
+                          -1 1.31215e-17 -1.20075e-17,
+                          -1 1.31215e-17 -1.20075e-17,
+                          -1 1.31215e-17 -1.20075e-17,
+                          2.73592e-19 -5.55112e-17 1,
+                          2.73592e-19 -5.55112e-17 1,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -4 29 -10.7819,
+                          4 29 -10.7819,
+                          4 29 -36,
+                          4 23 -36,
+                          4 29 -36,
+                          4 29 -10.7819,
+                          -4 29 -36,
+                          -4 29 -10.7819,
+                          4 29 -36,
+                          -4 23 -36,
+                          -4 29 -36,
+                          4 29 -36,
+                          -4 23 -36,
+                          4 29 -36,
+                          4 23 -36,
+                          7.4606e-14 29 -3.75,
+                          11.0305 29 -3.25208,
+                          4 29 -10.7819,
+                          4 23 -10.7819,
+                          4 29 -10.7819,
+                          11.0305 29 -3.25208,
+                          -4 29 -10.7819,
+                          -11.0305 29 -3.25208,
+                          4 29 -10.7819,
+                          7.4606e-14 29 -3.75,
+                          4 29 -10.7819,
+                          -11.0305 29 -3.25208,
+                          4 23 -10.7819,
+                          4 23 -36,
+                          4 29 -10.7819,
+                          7.44175e-14 29 3.75,
+                          9.20978 29 6.88671,
+                          11.0305 29 -3.25208,
+                          11.0305 23 -3.25208,
+                          11.0305 29 -3.25208,
+                          9.20978 29 6.88671,
+                          3.75 29 -1.97242e-13,
+                          7.44175e-14 29 3.75,
+                          11.0305 29 -3.25208,
+                          7.4606e-14 29 -3.75,
+                          3.75 29 -1.97242e-13,
+                          11.0305 29 -3.25208,
+                          4 23 -10.7819,
+                          11.0305 29 -3.25208,
+                          11.0305 23 -3.25208,
+                          -9.20978 29 6.88671,
+                          7.09084e-14 29 11.4998,
+                          9.20978 29 6.88671,
+                          9.20978 23 6.88671,
+                          9.20978 29 6.88671,
+                          7.09084e-14 29 11.4998,
+                          7.44175e-14 29 3.75,
+                          -9.20978 29 6.88671,
+                          9.20978 29 6.88671,
+                          11.0305 23 -3.25208,
+                          9.20978 29 6.88671,
+                          9.20978 23 6.88671,
+                          7.08707e-14 23 11.4998,
+                          7.09084e-14 29 11.4998,
+                          -9.20978 29 6.88671,
+                          9.20978 23 6.88671,
+                          7.09084e-14 29 11.4998,
+                          7.08707e-14 23 11.4998,
+                          -3.75 29 -2.00662e-13,
+                          -11.0305 29 -3.25208,
+                          -9.20978 29 6.88671,
+                          -9.20978 23 6.88671,
+                          -9.20978 29 6.88671,
+                          -11.0305 29 -3.25208,
+                          7.44175e-14 29 3.75,
+                          -3.75 29 -2.00662e-13,
+                          -9.20978 29 6.88671,
+                          7.08707e-14 23 11.4998,
+                          -9.20978 29 6.88671,
+                          -9.20978 23 6.88671,
+                          -11.0305 23 -3.25208,
+                          -11.0305 29 -3.25208,
+                          -4 29 -10.7819,
+                          7.4606e-14 29 -3.75,
+                          -11.0305 29 -3.25208,
+                          -3.75 29 -2.00662e-13,
+                          -9.20978 23 6.88671,
+                          -11.0305 29 -3.25208,
+                          -11.0305 23 -3.25208,
+                          -4 23 -10.7819,
+                          -4 29 -10.7819,
+                          -4 29 -36,
+                          -11.0305 23 -3.25208,
+                          -4 29 -10.7819,
+                          -4 23 -10.7819,
+                          -4 23 -10.7819,
+                          -4 29 -36,
+                          -4 23 -36,
+                          -3.75 23 -1.98972e-13,
+                          -3.75 29 -2.00662e-13,
+                          7.44175e-14 29 3.75,
+                          7.45683e-14 23 -3.75,
+                          7.4606e-14 29 -3.75,
+                          -3.75 29 -2.00662e-13,
+                          7.45683e-14 23 -3.75,
+                          -3.75 29 -2.00662e-13,
+                          -3.75 23 -1.98972e-13,
+                          7.50295e-14 23 3.75,
+                          7.44175e-14 29 3.75,
+                          3.75 29 -1.97242e-13,
+                          7.50295e-14 23 3.75,
+                          -3.75 23 -1.98972e-13,
+                          7.44175e-14 29 3.75,
+                          3.75 23 -1.98882e-13,
+                          3.75 29 -1.97242e-13,
+                          7.4606e-14 29 -3.75,
+                          7.50295e-14 23 3.75,
+                          3.75 29 -1.97242e-13,
+                          3.75 23 -1.98882e-13,
+                          3.75 23 -1.98882e-13,
+                          7.4606e-14 29 -3.75,
+                          7.45683e-14 23 -3.75,
+                          4 23 -10.7819,
+                          -4 23 -36,
+                          4 23 -36,
+                          4 23 -10.7819,
+                          -4 23 -10.7819,
+                          -4 23 -36,
+                          7.45683e-14 23 -3.75,
+                          -11.0305 23 -3.25208,
+                          -4 23 -10.7819,
+                          4 23 -10.7819,
+                          11.0305 23 -3.25208,
+                          -4 23 -10.7819,
+                          7.45683e-14 23 -3.75,
+                          -4 23 -10.7819,
+                          11.0305 23 -3.25208,
+                          7.50295e-14 23 3.75,
+                          -9.20978 23 6.88671,
+                          -11.0305 23 -3.25208,
+                          7.45683e-14 23 -3.75,
+                          -3.75 23 -1.98972e-13,
+                          -11.0305 23 -3.25208,
+                          7.50295e-14 23 3.75,
+                          -11.0305 23 -3.25208,
+                          -3.75 23 -1.98972e-13,
+                          9.20978 23 6.88671,
+                          7.08707e-14 23 11.4998,
+                          -9.20978 23 6.88671,
+                          7.50295e-14 23 3.75,
+                          9.20978 23 6.88671,
+                          -9.20978 23 6.88671,
+                          3.75 23 -1.98882e-13,
+                          11.0305 23 -3.25208,
+                          9.20978 23 6.88671,
+                          7.50295e-14 23 3.75,
+                          3.75 23 -1.98882e-13,
+                          9.20978 23 6.88671,
+                          3.75 23 -1.98882e-13,
+                          7.45683e-14 23 -3.75,
+                          11.0305 23 -3.25208 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/handlink_red.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/handlink_red.iv
new file mode 100644
index 0000000000000000000000000000000000000000..ba0de0148e8fa77f64e20eb61535f8af79a0ac64
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/handlink_red.iv
@@ -0,0 +1,1436 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+
+    Material {
+        diffuseColor    1 0 0
+    }
+    Separator {
+        Normal {
+            vector      [ 1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          6.09567e-17 3.00432e-16 -1,
+                          6.09567e-17 3.00432e-16 -1,
+                          6.28371e-18 1 1.79455e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          -6.28371e-18 -1 -5.69941e-17,
+                          -6.28371e-18 -1 -5.69941e-17,
+                          6.09567e-17 5.55112e-17 -1,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          -6.28371e-18 -1 -5.69941e-17,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          6.28371e-18 1 1.79455e-16,
+                          6.28371e-18 1 1.79455e-16,
+                          -6.09567e-17 -1.77972e-16 1,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          6.28371e-18 1 1.79455e-16,
+                          6.09567e-17 3.00432e-16 -1,
+                          6.28371e-18 1 1.79455e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          -6.09567e-17 -1.77972e-16 1,
+                          -6.09567e-17 -1.77972e-16 1,
+                          -6.28371e-18 -1 -5.69941e-17,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          6.28371e-18 1 1.79455e-16,
+                          -6.09567e-17 -1.77972e-16 1,
+                          -6.09567e-17 -1.77972e-16 1,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          -6.09567e-17 -1.77972e-16 1,
+                          -6.28371e-18 -1 -5.69941e-17,
+                          -6.28371e-18 -1 -5.69941e-17,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          3.74255e-17 0.850289 -0.526316,
+                          3.74255e-17 0.850289 -0.526316,
+                          6.09567e-17 1.77972e-16 -1,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          6.09567e-17 1.77972e-16 -1,
+                          6.09567e-17 1.77972e-16 -1,
+                          2.67395e-17 -0.850289 -0.526316,
+                          3.74255e-17 0.850289 -0.526316,
+                          6.09567e-17 1.77972e-16 -1,
+                          6.09567e-17 1.77972e-16 -1,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          6.09567e-17 1.77972e-16 -1,
+                          2.67395e-17 -0.850289 -0.526316,
+                          2.67395e-17 -0.850289 -0.526316,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -3.74255e-17 -0.850289 0.526316,
+                          -3.74255e-17 -0.850289 0.526316,
+                          -6.09567e-17 -3.00432e-16 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -3.00432e-16 1,
+                          -6.09567e-17 -3.00432e-16 1,
+                          -2.67395e-17 0.850289 0.526316,
+                          -3.74255e-17 -0.850289 0.526316,
+                          -6.09567e-17 -3.00432e-16 1,
+                          -6.09567e-17 -3.00432e-16 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -3.00432e-16 1,
+                          -2.67395e-17 0.850289 0.526316,
+                          -2.67395e-17 0.850289 0.526316,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -23.5 -8.07775 5,
+                          -23.5 -4.99986 -1.99578e-13,
+                          -23.5 8.4349e-14 5,
+                          -27.5 8.44015e-14 5,
+                          -23.5 8.4349e-14 5,
+                          -23.5 -4.99986 -1.99578e-13,
+                          -23.5 8.23801e-14 9.49987,
+                          -23.5 8.4349e-14 5,
+                          -23.5 4.99986 -1.98399e-13,
+                          -27.5 4.99986 -1.98937e-13,
+                          -23.5 4.99986 -1.98399e-13,
+                          -23.5 8.4349e-14 5,
+                          -23.5 8.23801e-14 9.49987,
+                          -23.5 -8.07775 5,
+                          -23.5 8.4349e-14 5,
+                          -27.5 4.99986 -1.98937e-13,
+                          -23.5 8.4349e-14 5,
+                          -27.5 8.44015e-14 5,
+                          -23.5 8.6932e-14 -9.49987,
+                          -23.5 8.61287e-14 -5,
+                          -23.5 -4.99986 -1.99578e-13,
+                          -27.5 -4.99986 -2.00116e-13,
+                          -23.5 -4.99986 -1.99578e-13,
+                          -23.5 8.61287e-14 -5,
+                          -23.5 -8.07775 5,
+                          -23.5 8.6932e-14 -9.49987,
+                          -23.5 -4.99986 -1.99578e-13,
+                          -27.5 -4.99986 -2.00116e-13,
+                          -27.5 8.44015e-14 5,
+                          -23.5 -4.99986 -1.99578e-13,
+                          -23.5 8.07775 -5,
+                          -23.5 4.99986 -1.98399e-13,
+                          -23.5 8.61287e-14 -5,
+                          -27.5 8.61812e-14 -5,
+                          -23.5 8.61287e-14 -5,
+                          -23.5 4.99986 -1.98399e-13,
+                          -23.5 8.6932e-14 -9.49987,
+                          -23.5 8.07775 -5,
+                          -23.5 8.61287e-14 -5,
+                          -27.5 -4.99986 -2.00116e-13,
+                          -23.5 8.61287e-14 -5,
+                          -27.5 8.61812e-14 -5,
+                          -23.5 8.23801e-14 9.49987,
+                          -23.5 4.99986 -1.98399e-13,
+                          -23.5 8.07775 -5,
+                          -27.5 8.61812e-14 -5,
+                          -23.5 4.99986 -1.98399e-13,
+                          -27.5 4.99986 -1.98937e-13,
+                          -23.5 8.07775 5,
+                          -23.5 8.07775 -5,
+                          -23.5 17 -5,
+                          -27.5 17 -5,
+                          -23.5 17 -5,
+                          -23.5 8.07775 -5,
+                          -23.5 17 5,
+                          -23.5 8.07775 5,
+                          -23.5 17 -5,
+                          -27.5 17 5,
+                          -23.5 17 5,
+                          -23.5 17 -5,
+                          -27.5 17 5,
+                          -23.5 17 -5,
+                          -27.5 17 -5,
+                          -27.5 8.07775 -5,
+                          -23.5 8.07775 -5,
+                          -23.5 8.6932e-14 -9.49987,
+                          -23.5 8.07775 5,
+                          -23.5 8.23801e-14 9.49987,
+                          -23.5 8.07775 -5,
+                          -27.5 8.07775 -5,
+                          -27.5 17 -5,
+                          -23.5 8.07775 -5,
+                          -23.5 -8.07775 5,
+                          -23.5 -8.07775 -5,
+                          -23.5 8.6932e-14 -9.49987,
+                          -27.5 8.69845e-14 -9.49987,
+                          -23.5 8.6932e-14 -9.49987,
+                          -23.5 -8.07775 -5,
+                          -27.5 8.07775 -5,
+                          -23.5 8.6932e-14 -9.49987,
+                          -27.5 8.69845e-14 -9.49987,
+                          -23.5 -17 5,
+                          -23.5 -17 -5,
+                          -23.5 -8.07775 -5,
+                          -27.5 -8.07775 -5,
+                          -23.5 -8.07775 -5,
+                          -23.5 -17 -5,
+                          -23.5 -8.07775 5,
+                          -23.5 -17 5,
+                          -23.5 -8.07775 -5,
+                          -27.5 8.69845e-14 -9.49987,
+                          -23.5 -8.07775 -5,
+                          -27.5 -8.07775 -5,
+                          -27.5 -17 -5,
+                          -23.5 -17 -5,
+                          -23.5 -17 5,
+                          -27.5 -8.07775 -5,
+                          -23.5 -17 -5,
+                          -27.5 -17 -5,
+                          -27.5 -17 5,
+                          -23.5 -17 5,
+                          -23.5 -8.07775 5,
+                          -27.5 -17 -5,
+                          -23.5 -17 5,
+                          -27.5 -17 5,
+                          -27.5 -8.07775 5,
+                          -23.5 -8.07775 5,
+                          -23.5 8.23801e-14 9.49987,
+                          -27.5 -17 5,
+                          -23.5 -8.07775 5,
+                          -27.5 -8.07775 5,
+                          -27.5 8.24326e-14 9.49987,
+                          -23.5 8.23801e-14 9.49987,
+                          -23.5 8.07775 5,
+                          -27.5 -8.07775 5,
+                          -23.5 8.23801e-14 9.49987,
+                          -27.5 8.24326e-14 9.49987,
+                          -27.5 8.07775 5,
+                          -23.5 8.07775 5,
+                          -23.5 17 5,
+                          -27.5 8.24326e-14 9.49987,
+                          -23.5 8.07775 5,
+                          -27.5 8.07775 5,
+                          -27.5 8.07775 5,
+                          -23.5 17 5,
+                          -27.5 17 5,
+                          -27.5 8.07775 5,
+                          -27.5 4.99986 -1.98937e-13,
+                          -27.5 8.44015e-14 5,
+                          -27.5 8.24326e-14 9.49987,
+                          -27.5 8.44015e-14 5,
+                          -27.5 -4.99986 -2.00116e-13,
+                          -27.5 8.24326e-14 9.49987,
+                          -27.5 8.07775 5,
+                          -27.5 8.44015e-14 5,
+                          -27.5 8.69845e-14 -9.49987,
+                          -27.5 8.61812e-14 -5,
+                          -27.5 4.99986 -1.98937e-13,
+                          -27.5 8.69845e-14 -9.49987,
+                          -27.5 4.99986 -1.98937e-13,
+                          -27.5 8.07775 5,
+                          -27.5 -8.07775 -5,
+                          -27.5 -4.99986 -2.00116e-13,
+                          -27.5 8.61812e-14 -5,
+                          -27.5 8.69845e-14 -9.49987,
+                          -27.5 -8.07775 -5,
+                          -27.5 8.61812e-14 -5,
+                          -27.5 -8.07775 -5,
+                          -27.5 8.24326e-14 9.49987,
+                          -27.5 -4.99986 -2.00116e-13,
+                          -27.5 8.07775 -5,
+                          -27.5 17 5,
+                          -27.5 17 -5,
+                          -27.5 8.07775 -5,
+                          -27.5 8.07775 5,
+                          -27.5 17 5,
+                          -27.5 8.07775 -5,
+                          -27.5 8.69845e-14 -9.49987,
+                          -27.5 8.07775 5,
+                          -27.5 -8.07775 -5,
+                          -27.5 -8.07775 5,
+                          -27.5 8.24326e-14 9.49987,
+                          -27.5 -17 -5,
+                          -27.5 -17 5,
+                          -27.5 -8.07775 5,
+                          -27.5 -8.07775 -5,
+                          -27.5 -17 -5,
+                          -27.5 -8.07775 5 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.83 0 0
+    }
+    Separator {
+        Normal {
+            vector      [ -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -6.09567e-17 1.8941e-16 1,
+                          -6.09567e-17 1.8941e-16 1,
+                          6.28371e-18 1 -1.87927e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -6.28371e-18 -1 6.54665e-17,
+                          -6.28371e-18 -1 6.54665e-17,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -6.28371e-18 -1 6.54665e-17,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          6.28371e-18 1 -1.87927e-16,
+                          6.28371e-18 1 -1.87927e-16,
+                          6.09567e-17 -6.69495e-17 -1,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          6.28371e-18 1 -1.87927e-16,
+                          -6.09567e-17 1.8941e-16 1,
+                          6.28371e-18 1 -1.87927e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          6.09567e-17 -6.69495e-17 -1,
+                          6.09567e-17 -6.69495e-17 -1,
+                          -6.28371e-18 -1 6.54665e-17,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          6.28371e-18 1 -1.87927e-16,
+                          6.09567e-17 -6.69495e-17 -1,
+                          6.09567e-17 -6.69495e-17 -1,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          6.09567e-17 -6.69495e-17 -1,
+                          -6.28371e-18 -1 6.54665e-17,
+                          -6.28371e-18 -1 6.54665e-17,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          -2.67395e-17 0.850289 0.526316,
+                          -2.67395e-17 0.850289 0.526316,
+                          -6.09567e-17 6.69495e-17 1,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -6.09567e-17 6.69495e-17 1,
+                          -6.09567e-17 6.69495e-17 1,
+                          -3.74255e-17 -0.850289 0.526316,
+                          -2.67395e-17 0.850289 0.526316,
+                          -6.09567e-17 6.69495e-17 1,
+                          -6.09567e-17 6.69495e-17 1,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -6.09567e-17 6.69495e-17 1,
+                          -3.74255e-17 -0.850289 0.526316,
+                          -3.74255e-17 -0.850289 0.526316,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          2.67395e-17 -0.850289 -0.526316,
+                          2.67395e-17 -0.850289 -0.526316,
+                          6.09567e-17 -1.8941e-16 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 -1.8941e-16 -1,
+                          6.09567e-17 -1.8941e-16 -1,
+                          3.74255e-17 0.850289 -0.526316,
+                          2.67395e-17 -0.850289 -0.526316,
+                          6.09567e-17 -1.8941e-16 -1,
+                          6.09567e-17 -1.8941e-16 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 -1.8941e-16 -1,
+                          3.74255e-17 0.850289 -0.526316,
+                          3.74255e-17 0.850289 -0.526316,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 23.5 -8.07775 -5,
+                          23.5 -4.74987 -1.92742e-13,
+                          23.5 8.55288e-14 -4.75,
+                          27.5 8.54763e-14 -4.75,
+                          23.5 8.55288e-14 -4.75,
+                          23.5 -4.74987 -1.92742e-13,
+                          23.5 8.3461e-14 -9.49987,
+                          23.5 8.55288e-14 -4.75,
+                          23.5 4.74987 -1.93921e-13,
+                          27.5 4.74987 -1.93383e-13,
+                          23.5 4.74987 -1.93921e-13,
+                          23.5 8.55288e-14 -4.75,
+                          23.5 8.3461e-14 -9.49987,
+                          23.5 -8.07775 -5,
+                          23.5 8.55288e-14 -4.75,
+                          27.5 4.74987 -1.93383e-13,
+                          23.5 8.55288e-14 -4.75,
+                          27.5 8.54763e-14 -4.75,
+                          23.5 8.59035e-14 9.49987,
+                          23.5 8.50015e-14 4.75,
+                          23.5 -4.74987 -1.92742e-13,
+                          27.5 -4.74987 -1.92204e-13,
+                          23.5 -4.74987 -1.92742e-13,
+                          23.5 8.50015e-14 4.75,
+                          23.5 -8.07775 -5,
+                          23.5 8.59035e-14 9.49987,
+                          23.5 -4.74987 -1.92742e-13,
+                          27.5 -4.74987 -1.92204e-13,
+                          27.5 8.54763e-14 -4.75,
+                          23.5 -4.74987 -1.92742e-13,
+                          23.5 8.07775 5,
+                          23.5 4.74987 -1.93921e-13,
+                          23.5 8.50015e-14 4.75,
+                          27.5 8.4949e-14 4.75,
+                          23.5 8.50015e-14 4.75,
+                          23.5 4.74987 -1.93921e-13,
+                          23.5 8.59035e-14 9.49987,
+                          23.5 8.07775 5,
+                          23.5 8.50015e-14 4.75,
+                          27.5 -4.74987 -1.92204e-13,
+                          23.5 8.50015e-14 4.75,
+                          27.5 8.4949e-14 4.75,
+                          23.5 8.3461e-14 -9.49987,
+                          23.5 4.74987 -1.93921e-13,
+                          23.5 8.07775 5,
+                          27.5 8.4949e-14 4.75,
+                          23.5 4.74987 -1.93921e-13,
+                          27.5 4.74987 -1.93383e-13,
+                          23.5 8.07775 -5,
+                          23.5 8.07775 5,
+                          23.5 17.5 5,
+                          27.5 17.5 5,
+                          23.5 17.5 5,
+                          23.5 8.07775 5,
+                          23.5 17.5 -5,
+                          23.5 8.07775 -5,
+                          23.5 17.5 5,
+                          27.5 17.5 -5,
+                          23.5 17.5 -5,
+                          23.5 17.5 5,
+                          27.5 17.5 -5,
+                          23.5 17.5 5,
+                          27.5 17.5 5,
+                          27.5 8.07775 5,
+                          23.5 8.07775 5,
+                          23.5 8.59035e-14 9.49987,
+                          23.5 8.07775 -5,
+                          23.5 8.3461e-14 -9.49987,
+                          23.5 8.07775 5,
+                          27.5 8.07775 5,
+                          27.5 17.5 5,
+                          23.5 8.07775 5,
+                          23.5 -8.07775 -5,
+                          23.5 -8.07775 5,
+                          23.5 8.59035e-14 9.49987,
+                          27.5 8.5851e-14 9.49987,
+                          23.5 8.59035e-14 9.49987,
+                          23.5 -8.07775 5,
+                          27.5 8.07775 5,
+                          23.5 8.59035e-14 9.49987,
+                          27.5 8.5851e-14 9.49987,
+                          23.5 -17.5 -5,
+                          23.5 -17.5 5,
+                          23.5 -8.07775 5,
+                          27.5 -8.07775 5,
+                          23.5 -8.07775 5,
+                          23.5 -17.5 5,
+                          23.5 -8.07775 -5,
+                          23.5 -17.5 -5,
+                          23.5 -8.07775 5,
+                          27.5 8.5851e-14 9.49987,
+                          23.5 -8.07775 5,
+                          27.5 -8.07775 5,
+                          27.5 -17.5 5,
+                          23.5 -17.5 5,
+                          23.5 -17.5 -5,
+                          27.5 -8.07775 5,
+                          23.5 -17.5 5,
+                          27.5 -17.5 5,
+                          27.5 -17.5 -5,
+                          23.5 -17.5 -5,
+                          23.5 -8.07775 -5,
+                          27.5 -17.5 5,
+                          23.5 -17.5 -5,
+                          27.5 -17.5 -5,
+                          27.5 -8.07775 -5,
+                          23.5 -8.07775 -5,
+                          23.5 8.3461e-14 -9.49987,
+                          27.5 -17.5 -5,
+                          23.5 -8.07775 -5,
+                          27.5 -8.07775 -5,
+                          27.5 8.34085e-14 -9.49987,
+                          23.5 8.3461e-14 -9.49987,
+                          23.5 8.07775 -5,
+                          27.5 -8.07775 -5,
+                          23.5 8.3461e-14 -9.49987,
+                          27.5 8.34085e-14 -9.49987,
+                          27.5 8.07775 -5,
+                          23.5 8.07775 -5,
+                          23.5 17.5 -5,
+                          27.5 8.34085e-14 -9.49987,
+                          23.5 8.07775 -5,
+                          27.5 8.07775 -5,
+                          27.5 8.07775 -5,
+                          23.5 17.5 -5,
+                          27.5 17.5 -5,
+                          27.5 8.07775 -5,
+                          27.5 4.74987 -1.93383e-13,
+                          27.5 8.54763e-14 -4.75,
+                          27.5 8.34085e-14 -9.49987,
+                          27.5 8.54763e-14 -4.75,
+                          27.5 -4.74987 -1.92204e-13,
+                          27.5 8.34085e-14 -9.49987,
+                          27.5 8.07775 -5,
+                          27.5 8.54763e-14 -4.75,
+                          27.5 8.5851e-14 9.49987,
+                          27.5 8.4949e-14 4.75,
+                          27.5 4.74987 -1.93383e-13,
+                          27.5 8.5851e-14 9.49987,
+                          27.5 4.74987 -1.93383e-13,
+                          27.5 8.07775 -5,
+                          27.5 -8.07775 5,
+                          27.5 -4.74987 -1.92204e-13,
+                          27.5 8.4949e-14 4.75,
+                          27.5 8.5851e-14 9.49987,
+                          27.5 -8.07775 5,
+                          27.5 8.4949e-14 4.75,
+                          27.5 -8.07775 5,
+                          27.5 8.34085e-14 -9.49987,
+                          27.5 -4.74987 -1.92204e-13,
+                          27.5 8.07775 5,
+                          27.5 17.5 -5,
+                          27.5 17.5 5,
+                          27.5 8.07775 5,
+                          27.5 8.07775 -5,
+                          27.5 17.5 -5,
+                          27.5 8.07775 5,
+                          27.5 8.5851e-14 9.49987,
+                          27.5 8.07775 -5,
+                          27.5 -8.07775 5,
+                          27.5 -8.07775 -5,
+                          27.5 8.34085e-14 -9.49987,
+                          27.5 -17.5 5,
+                          27.5 -17.5 -5,
+                          27.5 -8.07775 -5,
+                          27.5 -8.07775 5,
+                          27.5 -17.5 5,
+                          27.5 -8.07775 -5 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    1 0.03 0.03
+    }
+    Separator {
+        Normal {
+            vector      [ 6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          1.83965e-16 -5.55112e-17 1,
+                          1.83965e-16 -5.55112e-17 1,
+                          1 -1.31215e-17 -4.92228e-17,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          -1 1.31215e-17 -7.32379e-17,
+                          -1 1.31215e-17 -7.32379e-17,
+                          -6.09567e-17 -5.55112e-17 1,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          -1 1.31215e-17 -7.32379e-17,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          1 -1.31215e-17 -4.92228e-17,
+                          1 -1.31215e-17 -4.92228e-17,
+                          -6.15039e-17 5.55112e-17 -1,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          1 -1.31215e-17 -4.92228e-17,
+                          1.83965e-16 -5.55112e-17 1,
+                          1 -1.31215e-17 -4.92228e-17,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          -6.15039e-17 5.55112e-17 -1,
+                          -6.15039e-17 5.55112e-17 -1,
+                          -1 1.31215e-17 -7.32379e-17,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          1 -1.31215e-17 -4.92228e-17,
+                          -6.15039e-17 5.55112e-17 -1,
+                          -6.15039e-17 5.55112e-17 -1,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          -6.15039e-17 5.55112e-17 -1,
+                          -1 1.31215e-17 -7.32379e-17,
+                          -1 1.31215e-17 -7.32379e-17,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          0.909059 -3.50579e-17 0.416667,
+                          0.909059 -3.50579e-17 0.416667,
+                          6.15039e-17 -5.55112e-17 1,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.15039e-17 -5.55112e-17 1,
+                          6.15039e-17 -5.55112e-17 1,
+                          -0.909059 -1.12014e-17 0.416667,
+                          0.909059 -3.50579e-17 0.416667,
+                          6.15039e-17 -5.55112e-17 1,
+                          6.15039e-17 -5.55112e-17 1,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.15039e-17 -5.55112e-17 1,
+                          -0.909059 -1.12014e-17 0.416667,
+                          -0.909059 -1.12014e-17 0.416667,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -0.909059 3.50579e-17 -0.416667,
+                          -0.909059 3.50579e-17 -0.416667,
+                          -1.83965e-16 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          -1.83965e-16 5.55112e-17 -1,
+                          -1.83965e-16 5.55112e-17 -1,
+                          0.909059 1.12014e-17 -0.416667,
+                          -0.909059 3.50579e-17 -0.416667,
+                          -1.83965e-16 5.55112e-17 -1,
+                          -1.83965e-16 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          -1.83965e-16 5.55112e-17 -1,
+                          0.909059 1.12014e-17 -0.416667,
+                          0.909059 1.12014e-17 -0.416667,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -10.9087 -17 -5,
+                          -6.5 -17 -1.96856e-13,
+                          7.77599e-14 -17 -6.5,
+                          7.77285e-14 -22 -6.5,
+                          7.77599e-14 -17 -6.5,
+                          -6.5 -17 -1.96856e-13,
+                          7.59521e-14 -17 -12,
+                          7.77599e-14 -17 -6.5,
+                          6.5 -17 -1.967e-13,
+                          6.5 -22 -1.96678e-13,
+                          6.5 -17 -1.967e-13,
+                          7.77599e-14 -17 -6.5,
+                          7.59521e-14 -17 -12,
+                          -10.9087 -17 -5,
+                          7.77599e-14 -17 -6.5,
+                          6.5 -22 -1.96678e-13,
+                          7.77599e-14 -17 -6.5,
+                          7.77285e-14 -22 -6.5,
+                          7.88977e-14 -17 12,
+                          7.85595e-14 -17 6.5,
+                          -6.5 -17 -1.96856e-13,
+                          -6.5 -22 -1.96834e-13,
+                          -6.5 -17 -1.96856e-13,
+                          7.85595e-14 -17 6.5,
+                          -10.9087 -17 -5,
+                          7.88977e-14 -17 12,
+                          -6.5 -17 -1.96856e-13,
+                          -6.5 -22 -1.96834e-13,
+                          7.77285e-14 -22 -6.5,
+                          -6.5 -17 -1.96856e-13,
+                          10.9087 -17 5,
+                          6.5 -17 -1.967e-13,
+                          7.85595e-14 -17 6.5,
+                          7.85281e-14 -22 6.5,
+                          7.85595e-14 -17 6.5,
+                          6.5 -17 -1.967e-13,
+                          7.88977e-14 -17 12,
+                          10.9087 -17 5,
+                          7.85595e-14 -17 6.5,
+                          -6.5 -22 -1.96834e-13,
+                          7.85595e-14 -17 6.5,
+                          7.85281e-14 -22 6.5,
+                          7.59521e-14 -17 -12,
+                          6.5 -17 -1.967e-13,
+                          10.9087 -17 5,
+                          7.85281e-14 -22 6.5,
+                          6.5 -17 -1.967e-13,
+                          6.5 -22 -1.96678e-13,
+                          10.9087 -17 -5,
+                          10.9087 -17 5,
+                          28.5 -17 5,
+                          28.5 -22 5,
+                          28.5 -17 5,
+                          10.9087 -17 5,
+                          28.5 -17 -5,
+                          10.9087 -17 -5,
+                          28.5 -17 5,
+                          28.5 -22 -5,
+                          28.5 -17 -5,
+                          28.5 -17 5,
+                          28.5 -22 -5,
+                          28.5 -17 5,
+                          28.5 -22 5,
+                          10.9087 -22 5,
+                          10.9087 -17 5,
+                          7.88977e-14 -17 12,
+                          10.9087 -17 -5,
+                          7.59521e-14 -17 -12,
+                          10.9087 -17 5,
+                          10.9087 -22 5,
+                          28.5 -22 5,
+                          10.9087 -17 5,
+                          -10.9087 -17 -5,
+                          -10.9087 -17 5,
+                          7.88977e-14 -17 12,
+                          7.88663e-14 -22 12,
+                          7.88977e-14 -17 12,
+                          -10.9087 -17 5,
+                          10.9087 -22 5,
+                          7.88977e-14 -17 12,
+                          7.88663e-14 -22 12,
+                          -27.5 -17 -5,
+                          -27.5 -17 5,
+                          -10.9087 -17 5,
+                          -10.9087 -22 5,
+                          -10.9087 -17 5,
+                          -27.5 -17 5,
+                          -10.9087 -17 -5,
+                          -27.5 -17 -5,
+                          -10.9087 -17 5,
+                          7.88663e-14 -22 12,
+                          -10.9087 -17 5,
+                          -10.9087 -22 5,
+                          -27.5 -22 5,
+                          -27.5 -17 5,
+                          -27.5 -17 -5,
+                          -10.9087 -22 5,
+                          -27.5 -17 5,
+                          -27.5 -22 5,
+                          -27.5 -22 -5,
+                          -27.5 -17 -5,
+                          -10.9087 -17 -5,
+                          -27.5 -22 5,
+                          -27.5 -17 -5,
+                          -27.5 -22 -5,
+                          -10.9087 -22 -5,
+                          -10.9087 -17 -5,
+                          7.59521e-14 -17 -12,
+                          -27.5 -22 -5,
+                          -10.9087 -17 -5,
+                          -10.9087 -22 -5,
+                          7.59207e-14 -22 -12,
+                          7.59521e-14 -17 -12,
+                          10.9087 -17 -5,
+                          -10.9087 -22 -5,
+                          7.59521e-14 -17 -12,
+                          7.59207e-14 -22 -12,
+                          10.9087 -22 -5,
+                          10.9087 -17 -5,
+                          28.5 -17 -5,
+                          7.59207e-14 -22 -12,
+                          10.9087 -17 -5,
+                          10.9087 -22 -5,
+                          10.9087 -22 -5,
+                          28.5 -17 -5,
+                          28.5 -22 -5,
+                          10.9087 -22 -5,
+                          6.5 -22 -1.96678e-13,
+                          7.77285e-14 -22 -6.5,
+                          7.59207e-14 -22 -12,
+                          7.77285e-14 -22 -6.5,
+                          -6.5 -22 -1.96834e-13,
+                          7.59207e-14 -22 -12,
+                          10.9087 -22 -5,
+                          7.77285e-14 -22 -6.5,
+                          7.88663e-14 -22 12,
+                          7.85281e-14 -22 6.5,
+                          6.5 -22 -1.96678e-13,
+                          7.88663e-14 -22 12,
+                          6.5 -22 -1.96678e-13,
+                          10.9087 -22 -5,
+                          -10.9087 -22 5,
+                          -6.5 -22 -1.96834e-13,
+                          7.85281e-14 -22 6.5,
+                          7.88663e-14 -22 12,
+                          -10.9087 -22 5,
+                          7.85281e-14 -22 6.5,
+                          -10.9087 -22 5,
+                          7.59207e-14 -22 -12,
+                          -6.5 -22 -1.96834e-13,
+                          10.9087 -22 5,
+                          28.5 -22 -5,
+                          28.5 -22 5,
+                          10.9087 -22 5,
+                          10.9087 -22 -5,
+                          28.5 -22 -5,
+                          10.9087 -22 5,
+                          7.88663e-14 -22 12,
+                          10.9087 -22 -5,
+                          -10.9087 -22 5,
+                          -10.9087 -22 -5,
+                          7.59207e-14 -22 -12,
+                          -27.5 -22 5,
+                          -27.5 -22 -5,
+                          -10.9087 -22 -5,
+                          -10.9087 -22 5,
+                          -27.5 -22 5,
+                          -10.9087 -22 -5 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          1 -1.31215e-17 1.34468e-16,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          0.909059 1.12014e-17 -0.416667,
+                          0.909059 1.12014e-17 -0.416667,
+                          1.83417e-16 5.55112e-17 -1,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          1.83417e-16 5.55112e-17 -1,
+                          1.83417e-16 5.55112e-17 -1,
+                          -0.909059 3.50579e-17 -0.416667,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          0.909059 1.12014e-17 -0.416667,
+                          1.83417e-16 5.55112e-17 -1,
+                          1.83417e-16 5.55112e-17 -1,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          1.83417e-16 5.55112e-17 -1,
+                          -0.909059 3.50579e-17 -0.416667,
+                          -0.909059 3.50579e-17 -0.416667,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          6.09567e-17 5.55112e-17 -1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -1 1.31215e-17 -1.34468e-16,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -0.909059 -1.12014e-17 0.416667,
+                          -0.909059 -1.12014e-17 0.416667,
+                          -3.05878e-16 -5.55112e-17 1,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -3.05878e-16 -5.55112e-17 1,
+                          -3.05878e-16 -5.55112e-17 1,
+                          0.909059 -3.50579e-17 0.416667,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -6.28371e-18 -1 4.23622e-18,
+                          -0.909059 -1.12014e-17 0.416667,
+                          -3.05878e-16 -5.55112e-17 1,
+                          -3.05878e-16 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -3.05878e-16 -5.55112e-17 1,
+                          0.909059 -3.50579e-17 0.416667,
+                          0.909059 -3.50579e-17 0.416667,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -6.09567e-17 -5.55112e-17 1,
+                          -1 1.96812e-16 -1.34468e-16,
+                          -1 1.96812e-16 -1.34468e-16,
+                          2.21771e-16 5.55112e-17 -1,
+                          -5.66276e-16 -5.55112e-17 1,
+                          -5.66276e-16 -5.55112e-17 1,
+                          -1 1.96812e-16 -1.34468e-16,
+                          -5.66276e-16 -5.55112e-17 1,
+                          -1 1.96812e-16 -1.34468e-16,
+                          -1 1.96812e-16 -1.34468e-16,
+                          2.21771e-16 5.55112e-17 -1,
+                          2.21771e-16 5.55112e-17 -1,
+                          1 -1.96812e-16 1.20075e-17,
+                          2.21771e-16 5.55112e-17 -1,
+                          -1 1.96812e-16 -1.34468e-16,
+                          2.21771e-16 5.55112e-17 -1,
+                          1 -1.96812e-16 2.56929e-16,
+                          1 -1.96812e-16 2.56929e-16,
+                          -5.66276e-16 -5.55112e-17 1,
+                          2.21771e-16 5.55112e-17 -1,
+                          1 -1.96812e-16 1.20075e-17,
+                          1 -1.96812e-16 1.20075e-17,
+                          1 -1.96812e-16 2.56929e-16,
+                          -5.66276e-16 -5.55112e-17 1,
+                          -5.66276e-16 -5.55112e-17 1,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18,
+                          6.28371e-18 1 -4.23622e-18 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 10.9087 17 5,
+                          10.9087 17 -5,
+                          28.5 17 -5,
+                          28.5 22 -5,
+                          28.5 17 -5,
+                          10.9087 17 -5,
+                          28.5 17 5,
+                          10.9087 17 5,
+                          28.5 17 -5,
+                          28.5 22 5,
+                          28.5 17 5,
+                          28.5 17 -5,
+                          28.5 22 5,
+                          28.5 17 -5,
+                          28.5 22 -5,
+                          8.17698e-14 17 -8,
+                          8.03607e-14 17 -12,
+                          10.9087 17 -5,
+                          10.9087 22 -5,
+                          10.9087 17 -5,
+                          8.03607e-14 17 -12,
+                          8 17 -1.961e-13,
+                          10.9087 17 -5,
+                          10.9087 17 5,
+                          8.17698e-14 17 -8,
+                          10.9087 17 -5,
+                          8 17 -1.961e-13,
+                          10.9087 22 -5,
+                          28.5 22 -5,
+                          10.9087 17 -5,
+                          -8 17 -1.98251e-13,
+                          -10.9087 17 -5,
+                          8.03607e-14 17 -12,
+                          8.03921e-14 22 -12,
+                          8.03607e-14 17 -12,
+                          -10.9087 17 -5,
+                          8.17698e-14 17 -8,
+                          -8 17 -1.98251e-13,
+                          8.03607e-14 17 -12,
+                          10.9087 22 -5,
+                          8.03607e-14 17 -12,
+                          8.03921e-14 22 -12,
+                          -27.5 17 5,
+                          -27.5 17 -5,
+                          -10.9087 17 -5,
+                          -10.9087 22 -5,
+                          -10.9087 17 -5,
+                          -27.5 17 -5,
+                          -10.9087 17 5,
+                          -27.5 17 5,
+                          -10.9087 17 -5,
+                          -8 17 -1.98251e-13,
+                          -10.9087 17 5,
+                          -10.9087 17 -5,
+                          8.03921e-14 22 -12,
+                          -10.9087 17 -5,
+                          -10.9087 22 -5,
+                          -27.5 22 -5,
+                          -27.5 17 -5,
+                          -27.5 17 5,
+                          -10.9087 22 -5,
+                          -27.5 17 -5,
+                          -27.5 22 -5,
+                          -27.5 22 5,
+                          -27.5 17 5,
+                          -10.9087 17 5,
+                          -27.5 22 -5,
+                          -27.5 17 5,
+                          -27.5 22 5,
+                          7.54654e-14 17 8,
+                          7.44892e-14 17 12,
+                          -10.9087 17 5,
+                          -10.9087 22 5,
+                          -10.9087 17 5,
+                          7.44892e-14 17 12,
+                          -8 17 -1.98251e-13,
+                          7.54654e-14 17 8,
+                          -10.9087 17 5,
+                          -27.5 22 5,
+                          -10.9087 17 5,
+                          -10.9087 22 5,
+                          8 17 -1.961e-13,
+                          10.9087 17 5,
+                          7.44892e-14 17 12,
+                          7.45206e-14 22 12,
+                          7.44892e-14 17 12,
+                          10.9087 17 5,
+                          7.54654e-14 17 8,
+                          8 17 -1.961e-13,
+                          7.44892e-14 17 12,
+                          -10.9087 22 5,
+                          7.44892e-14 17 12,
+                          7.45206e-14 22 12,
+                          10.9087 22 5,
+                          10.9087 17 5,
+                          28.5 17 5,
+                          7.45206e-14 22 12,
+                          10.9087 17 5,
+                          10.9087 22 5,
+                          10.9087 22 5,
+                          28.5 17 5,
+                          28.5 22 5,
+                          8 22 -1.96121e-13,
+                          8 17 -1.961e-13,
+                          7.54654e-14 17 8,
+                          8.27197e-14 22 -8,
+                          8.17698e-14 17 -8,
+                          8 17 -1.961e-13,
+                          8.27197e-14 22 -8,
+                          8 17 -1.961e-13,
+                          8 22 -1.96121e-13,
+                          7.64153e-14 22 8,
+                          7.54654e-14 17 8,
+                          -8 17 -1.98251e-13,
+                          7.64153e-14 22 8,
+                          8 22 -1.96121e-13,
+                          7.54654e-14 17 8,
+                          -8 22 -1.98273e-13,
+                          -8 17 -1.98251e-13,
+                          8.17698e-14 17 -8,
+                          7.64153e-14 22 8,
+                          -8 17 -1.98251e-13,
+                          -8 22 -1.98273e-13,
+                          -8 22 -1.98273e-13,
+                          8.17698e-14 17 -8,
+                          8.27197e-14 22 -8,
+                          10.9087 22 -5,
+                          28.5 22 5,
+                          28.5 22 -5,
+                          10.9087 22 -5,
+                          10.9087 22 5,
+                          28.5 22 5,
+                          7.64153e-14 22 8,
+                          7.45206e-14 22 12,
+                          10.9087 22 5,
+                          8 22 -1.96121e-13,
+                          10.9087 22 5,
+                          10.9087 22 -5,
+                          7.64153e-14 22 8,
+                          10.9087 22 5,
+                          8 22 -1.96121e-13,
+                          -8 22 -1.98273e-13,
+                          -10.9087 22 5,
+                          7.45206e-14 22 12,
+                          7.64153e-14 22 8,
+                          -8 22 -1.98273e-13,
+                          7.45206e-14 22 12,
+                          -27.5 22 -5,
+                          -27.5 22 5,
+                          -10.9087 22 5,
+                          -10.9087 22 -5,
+                          -27.5 22 -5,
+                          -10.9087 22 5,
+                          -8 22 -1.98273e-13,
+                          -10.9087 22 -5,
+                          -10.9087 22 5,
+                          8.27197e-14 22 -8,
+                          8.03921e-14 22 -12,
+                          -10.9087 22 -5,
+                          -8 22 -1.98273e-13,
+                          8.27197e-14 22 -8,
+                          -10.9087 22 -5,
+                          8 22 -1.96121e-13,
+                          10.9087 22 -5,
+                          8.03921e-14 22 -12,
+                          8.27197e-14 22 -8,
+                          8 22 -1.96121e-13,
+                          8.03921e-14 22 -12 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/metacarpals.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/metacarpals.iv
new file mode 100644
index 0000000000000000000000000000000000000000..4800791651e8ef7bc74969422379b92cf0cc082a
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/metacarpals.iv
@@ -0,0 +1,2108 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+    Separator {
+        Normal {
+            vector      [ -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -1 2.86563e-16 5.63785e-17,
+                          -1 2.86563e-16 5.63785e-17,
+                          -0.809017 0.587785 -1.96461e-17,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -0.809017 -0.587785 1.10868e-16,
+                          -0.809017 -0.587785 1.10868e-16,
+                          -1 4.16334e-17 5.63785e-17,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -0.809017 -0.587785 1.10868e-16,
+                          -1 4.16334e-17 5.63785e-17,
+                          -1 4.16334e-17 5.63785e-17,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -0.809017 0.587785 -1.96461e-17,
+                          -0.809017 0.587785 -1.96461e-17,
+                          -0.309017 0.951057 -8.81666e-17,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -0.809017 0.587785 -1.96461e-17,
+                          -1 2.86563e-16 5.63785e-17,
+                          -0.809017 0.587785 -1.96461e-17,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -0.309017 0.951057 -8.81666e-17,
+                          -0.309017 0.951057 -8.81666e-17,
+                          0.309017 0.951057 -1.2301e-16,
+                          -0.809017 0.587785 -1.96461e-17,
+                          -0.309017 0.951057 -8.81666e-17,
+                          -0.309017 0.951057 -8.81666e-17,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          0.309017 0.951057 -1.2301e-16,
+                          0.309017 0.951057 -1.2301e-16,
+                          0.809017 0.587785 -1.10868e-16,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -0.309017 0.951057 -8.81666e-17,
+                          0.309017 0.951057 -1.2301e-16,
+                          0.309017 0.951057 -1.2301e-16,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          0.809017 0.587785 -1.10868e-16,
+                          0.809017 0.587785 -1.10868e-16,
+                          1 -1.64098e-16 -5.63785e-17,
+                          0.309017 0.951057 -1.2301e-16,
+                          0.809017 0.587785 -1.10868e-16,
+                          0.809017 0.587785 -1.10868e-16,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          1 -1.64098e-16 -5.63785e-17,
+                          1 -1.64098e-16 -5.63785e-17,
+                          0.809017 -0.587785 1.96461e-17,
+                          0.809017 0.587785 -1.10868e-16,
+                          1 -1.64098e-16 -5.63785e-17,
+                          1 -1.64098e-16 -5.63785e-17,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          0.809017 -0.587785 1.96461e-17,
+                          0.809017 -0.587785 1.96461e-17,
+                          0.309017 -0.951057 8.81666e-17,
+                          1 -1.64098e-16 -5.63785e-17,
+                          0.809017 -0.587785 1.96461e-17,
+                          0.809017 -0.587785 1.96461e-17,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          0.309017 -0.951057 8.81666e-17,
+                          0.309017 -0.951057 8.81666e-17,
+                          -0.309017 -0.951057 1.2301e-16,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          0.809017 -0.587785 1.96461e-17,
+                          0.309017 -0.951057 8.81666e-17,
+                          0.309017 -0.951057 8.81666e-17,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -0.309017 -0.951057 1.2301e-16,
+                          -0.309017 -0.951057 1.2301e-16,
+                          -0.809017 -0.587785 1.10868e-16,
+                          0.309017 -0.951057 8.81666e-17,
+                          -0.309017 -0.951057 1.2301e-16,
+                          -0.309017 -0.951057 1.2301e-16,
+                          -0.309017 -0.951057 1.2301e-16,
+                          -0.809017 -0.587785 1.10868e-16,
+                          -0.809017 -0.587785 1.10868e-16,
+                          -2.94903e-17 -1 1.11022e-16,
+                          -2.94903e-17 -1 1.11022e-16,
+                          -2.94903e-17 -1 1.11022e-16,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -1 4.16334e-17 5.63785e-17,
+                          -1 4.16334e-17 5.63785e-17,
+                          -1 4.16334e-17 5.63785e-17,
+                          -1 4.16334e-17 5.63785e-17,
+                          -1 4.16334e-17 5.63785e-17,
+                          -1 4.16334e-17 5.63785e-17,
+                          -2.13187e-16 -1 1.11022e-16,
+                          -2.13187e-16 -1 1.11022e-16,
+                          0.382683 -0.92388 8.09961e-17,
+                          -2.94903e-17 -1 1.11022e-16,
+                          -2.94903e-17 -1 1.11022e-16,
+                          -2.94903e-17 -1 1.11022e-16,
+                          -2.94903e-17 -1 1.11022e-16,
+                          -2.94903e-17 -1 1.11022e-16,
+                          -2.94903e-17 -1 1.11022e-16,
+                          -2.94903e-17 -1 1.11022e-16,
+                          -2.94903e-17 -1 1.11022e-16,
+                          -2.94903e-17 -1 1.11022e-16,
+                          -2.94903e-17 -1 1.11022e-16,
+                          -2.94903e-17 -1 1.11022e-16,
+                          -2.94903e-17 -1 1.11022e-16,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          0.382683 -0.92388 8.09961e-17,
+                          0.382683 -0.92388 8.09961e-17,
+                          0.707107 -0.707107 3.8639e-17,
+                          0.382683 -0.92388 8.09961e-17,
+                          -2.13187e-16 -1 1.11022e-16,
+                          0.382683 -0.92388 8.09961e-17,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          0.707107 -0.707107 3.8639e-17,
+                          0.707107 -0.707107 3.8639e-17,
+                          0.92388 -0.382683 -9.60056e-18,
+                          0.382683 -0.92388 8.09961e-17,
+                          0.707107 -0.707107 3.8639e-17,
+                          0.707107 -0.707107 3.8639e-17,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          0.92388 -0.382683 -9.60056e-18,
+                          0.92388 -0.382683 -9.60056e-18,
+                          1 -2.86563e-16 -5.63785e-17,
+                          0.707107 -0.707107 3.8639e-17,
+                          0.92388 -0.382683 -9.60056e-18,
+                          0.92388 -0.382683 -9.60056e-18,
+                          1 -4.16334e-17 -5.63785e-17,
+                          1 -4.16334e-17 -5.63785e-17,
+                          1 -4.16334e-17 -5.63785e-17,
+                          1 -4.16334e-17 -5.63785e-17,
+                          1 -4.16334e-17 -5.63785e-17,
+                          1 -4.16334e-17 -5.63785e-17,
+                          0.92388 -0.382683 -9.60056e-18,
+                          1 -2.86563e-16 -5.63785e-17,
+                          1 -2.86563e-16 -5.63785e-17,
+                          2.94903e-17 1 -1.11022e-16,
+                          2.94903e-17 1 -1.11022e-16,
+                          2.94903e-17 1 -1.11022e-16,
+                          2.94903e-17 1 -1.11022e-16,
+                          2.94903e-17 1 -1.11022e-16,
+                          2.94903e-17 1 -1.11022e-16,
+                          2.94903e-17 1 -1.11022e-16,
+                          2.94903e-17 1 -1.11022e-16,
+                          2.94903e-17 1 -1.11022e-16,
+                          2.94903e-17 1 -1.11022e-16,
+                          2.94903e-17 1 -1.11022e-16,
+                          2.94903e-17 1 -1.11022e-16,
+                          2.94903e-17 1 -1.11022e-16,
+                          2.94903e-17 1 -1.11022e-16,
+                          2.94903e-17 1 -1.11022e-16,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          1 2.03296e-16 -5.63785e-17,
+                          1 2.03296e-16 -5.63785e-17,
+                          0.809017 0.587785 -1.10868e-16,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          0.809017 -0.587785 1.96461e-17,
+                          0.809017 -0.587785 1.96461e-17,
+                          1 -4.16334e-17 -5.63785e-17,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          0.809017 -0.587785 1.96461e-17,
+                          1 -4.16334e-17 -5.63785e-17,
+                          1 -4.16334e-17 -5.63785e-17,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          0.809017 0.587785 -1.10868e-16,
+                          0.809017 0.587785 -1.10868e-16,
+                          0.309017 0.951057 -1.2301e-16,
+                          0.809017 0.587785 -1.10868e-16,
+                          1 2.03296e-16 -5.63785e-17,
+                          0.809017 0.587785 -1.10868e-16,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          0.309017 0.951057 -1.2301e-16,
+                          0.309017 0.951057 -1.2301e-16,
+                          -0.309017 0.951057 -8.81666e-17,
+                          0.809017 0.587785 -1.10868e-16,
+                          0.309017 0.951057 -1.2301e-16,
+                          0.309017 0.951057 -1.2301e-16,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          -0.309017 0.951057 -8.81666e-17,
+                          -0.309017 0.951057 -8.81666e-17,
+                          -0.809017 0.587785 -1.96461e-17,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          0.309017 0.951057 -1.2301e-16,
+                          -0.309017 0.951057 -8.81666e-17,
+                          -0.309017 0.951057 -8.81666e-17,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          -0.809017 0.587785 -1.96461e-17,
+                          -0.809017 0.587785 -1.96461e-17,
+                          -1 -8.08313e-17 5.63785e-17,
+                          -0.309017 0.951057 -8.81666e-17,
+                          -0.809017 0.587785 -1.96461e-17,
+                          -0.809017 0.587785 -1.96461e-17,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          -1 -8.08313e-17 5.63785e-17,
+                          -1 -8.08313e-17 5.63785e-17,
+                          -0.809017 -0.587785 1.10868e-16,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          -0.809017 0.587785 -1.96461e-17,
+                          -1 -8.08313e-17 5.63785e-17,
+                          -1 -8.08313e-17 5.63785e-17,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          -0.809017 -0.587785 1.10868e-16,
+                          -0.809017 -0.587785 1.10868e-16,
+                          -0.309017 -0.951057 1.2301e-16,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          -1 -8.08313e-17 5.63785e-17,
+                          -0.809017 -0.587785 1.10868e-16,
+                          -0.809017 -0.587785 1.10868e-16,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          -0.309017 -0.951057 1.2301e-16,
+                          -0.309017 -0.951057 1.2301e-16,
+                          0.309017 -0.951057 8.81666e-17,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          -0.809017 -0.587785 1.10868e-16,
+                          -0.309017 -0.951057 1.2301e-16,
+                          -0.309017 -0.951057 1.2301e-16,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          0.309017 -0.951057 8.81666e-17,
+                          0.309017 -0.951057 8.81666e-17,
+                          0.809017 -0.587785 1.96461e-17,
+                          -0.309017 -0.951057 1.2301e-16,
+                          0.309017 -0.951057 8.81666e-17,
+                          0.309017 -0.951057 8.81666e-17,
+                          0.309017 -0.951057 8.81666e-17,
+                          0.809017 -0.587785 1.96461e-17,
+                          0.809017 -0.587785 1.96461e-17,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          -2.94903e-17 -1 1.11022e-16,
+                          -2.94903e-17 -1 1.11022e-16,
+                          -2.94903e-17 -1 1.11022e-16,
+                          0.382683 -0.92388 8.09961e-17,
+                          0.382683 -0.92388 8.09961e-17,
+                          -2.13187e-16 -1 1.11022e-16,
+                          0.382683 -0.92388 8.09961e-17,
+                          -2.13187e-16 -1 1.11022e-16,
+                          -2.13187e-16 -1 1.11022e-16,
+                          -1 4.16334e-17 5.63785e-17,
+                          -1 4.16334e-17 5.63785e-17,
+                          -1 4.16334e-17 5.63785e-17,
+                          -2.94903e-17 -1 1.11022e-16,
+                          -2.94903e-17 -1 1.11022e-16,
+                          -2.94903e-17 -1 1.11022e-16,
+                          -2.94903e-17 -1 1.11022e-16,
+                          -2.94903e-17 -1 1.11022e-16,
+                          -2.94903e-17 -1 1.11022e-16,
+                          2.94903e-17 1 -1.11022e-16,
+                          2.94903e-17 1 -1.11022e-16,
+                          2.94903e-17 1 -1.11022e-16,
+                          -1 4.16334e-17 5.63785e-17,
+                          -1 4.16334e-17 5.63785e-17,
+                          -1 4.16334e-17 5.63785e-17,
+                          1 -4.16334e-17 -5.63785e-17,
+                          1 -4.16334e-17 -5.63785e-17,
+                          1 -4.16334e-17 -5.63785e-17,
+                          1 -4.16334e-17 -5.63785e-17,
+                          1 -4.16334e-17 -5.63785e-17,
+                          1 -4.16334e-17 -5.63785e-17,
+                          2.94903e-17 1 -1.11022e-16,
+                          2.94903e-17 1 -1.11022e-16,
+                          2.94903e-17 1 -1.11022e-16,
+                          2.94903e-17 1 -1.11022e-16,
+                          2.94903e-17 1 -1.11022e-16,
+                          2.94903e-17 1 -1.11022e-16,
+                          1 -2.86563e-16 -5.63785e-17,
+                          1 -2.86563e-16 -5.63785e-17,
+                          0.92388 -0.382683 -9.60056e-18,
+                          0.92388 -0.382683 -9.60056e-18,
+                          0.92388 -0.382683 -9.60056e-18,
+                          0.707107 -0.707107 3.8639e-17,
+                          0.92388 -0.382683 -9.60056e-18,
+                          1 -2.86563e-16 -5.63785e-17,
+                          0.92388 -0.382683 -9.60056e-18,
+                          0.707107 -0.707107 3.8639e-17,
+                          0.707107 -0.707107 3.8639e-17,
+                          0.382683 -0.92388 8.09961e-17,
+                          0.92388 -0.382683 -9.60056e-18,
+                          0.707107 -0.707107 3.8639e-17,
+                          0.707107 -0.707107 3.8639e-17,
+                          0.707107 -0.707107 3.8639e-17,
+                          0.382683 -0.92388 8.09961e-17,
+                          0.382683 -0.92388 8.09961e-17,
+                          -1 4.16334e-17 5.63785e-17,
+                          -1 4.16334e-17 5.63785e-17,
+                          -1 4.16334e-17 5.63785e-17,
+                          2.94903e-17 1 -1.11022e-16,
+                          2.94903e-17 1 -1.11022e-16,
+                          2.94903e-17 1 -1.11022e-16,
+                          -1 4.16334e-17 5.63785e-17,
+                          -1 4.16334e-17 5.63785e-17,
+                          -1 4.16334e-17 5.63785e-17,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          2.94903e-17 1 -1.11022e-16,
+                          2.94903e-17 1 -1.11022e-16,
+                          2.94903e-17 1 -1.11022e-16,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          -2.94903e-17 -1 1.11022e-16,
+                          -2.94903e-17 -1 1.11022e-16,
+                          -2.94903e-17 -1 1.11022e-16,
+                          -2.94903e-17 -1 1.11022e-16,
+                          -2.94903e-17 -1 1.11022e-16,
+                          -2.94903e-17 -1 1.11022e-16,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          1 -4.16334e-17 -5.63785e-17,
+                          1 -4.16334e-17 -5.63785e-17,
+                          1 -4.16334e-17 -5.63785e-17,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          1 -4.16334e-17 -5.63785e-17,
+                          1 -4.16334e-17 -5.63785e-17,
+                          1 -4.16334e-17 -5.63785e-17,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          2.25514e-17 5.55112e-17 1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          -2.25514e-17 -5.55112e-17 -1,
+                          1 -4.16334e-17 -5.63785e-17,
+                          1 -4.16334e-17 -5.63785e-17,
+                          0.866025 -0.5 6.68593e-18,
+                          0.866025 0.5 -1.04336e-16,
+                          0.866025 0.5 -1.04336e-16,
+                          1 2.03296e-16 -5.63785e-17,
+                          0.866025 0.5 -1.04336e-16,
+                          1 2.03296e-16 -5.63785e-17,
+                          1 2.03296e-16 -5.63785e-17,
+                          0.866025 -0.5 6.68593e-18,
+                          0.866025 -0.5 6.68593e-18,
+                          0.5 -0.866025 6.79589e-17,
+                          0.866025 -0.5 6.68593e-18,
+                          1 -4.16334e-17 -5.63785e-17,
+                          0.866025 -0.5 6.68593e-18,
+                          0.5 -0.866025 6.79589e-17,
+                          0.5 -0.866025 6.79589e-17,
+                          -4.85324e-15 -1 1.11022e-16,
+                          0.866025 -0.5 6.68593e-18,
+                          0.5 -0.866025 6.79589e-17,
+                          0.5 -0.866025 6.79589e-17,
+                          -4.85324e-15 -1 1.11022e-16,
+                          -4.85324e-15 -1 1.11022e-16,
+                          -0.5 -0.866025 1.24337e-16,
+                          0.5 -0.866025 6.79589e-17,
+                          -4.85324e-15 -1 1.11022e-16,
+                          -4.85324e-15 -1 1.11022e-16,
+                          -0.5 -0.866025 1.24337e-16,
+                          -0.5 -0.866025 1.24337e-16,
+                          -0.866025 -0.5 1.04336e-16,
+                          -4.85324e-15 -1 1.11022e-16,
+                          -0.5 -0.866025 1.24337e-16,
+                          -0.5 -0.866025 1.24337e-16,
+                          -0.866025 -0.5 1.04336e-16,
+                          -0.866025 -0.5 1.04336e-16,
+                          -1 -8.08313e-17 5.63785e-17,
+                          -0.5 -0.866025 1.24337e-16,
+                          -0.866025 -0.5 1.04336e-16,
+                          -0.866025 -0.5 1.04336e-16,
+                          -1 -8.08313e-17 5.63785e-17,
+                          -1 -8.08313e-17 5.63785e-17,
+                          -0.866025 0.5 -6.68593e-18,
+                          -0.866025 -0.5 1.04336e-16,
+                          -1 -8.08313e-17 5.63785e-17,
+                          -1 -8.08313e-17 5.63785e-17,
+                          -0.866025 0.5 -6.68593e-18,
+                          -0.866025 0.5 -6.68593e-18,
+                          -0.5 0.866025 -6.79589e-17,
+                          -1 -8.08313e-17 5.63785e-17,
+                          -0.866025 0.5 -6.68593e-18,
+                          -0.866025 0.5 -6.68593e-18,
+                          -0.5 0.866025 -6.79589e-17,
+                          -0.5 0.866025 -6.79589e-17,
+                          1.62215e-15 1 -1.11022e-16,
+                          -0.866025 0.5 -6.68593e-18,
+                          -0.5 0.866025 -6.79589e-17,
+                          -0.5 0.866025 -6.79589e-17,
+                          1.62215e-15 1 -1.11022e-16,
+                          1.62215e-15 1 -1.11022e-16,
+                          0.5 0.866025 -1.24337e-16,
+                          -0.5 0.866025 -6.79589e-17,
+                          1.62215e-15 1 -1.11022e-16,
+                          1.62215e-15 1 -1.11022e-16,
+                          0.5 0.866025 -1.24337e-16,
+                          0.5 0.866025 -1.24337e-16,
+                          0.866025 0.5 -1.04336e-16,
+                          1.62215e-15 1 -1.11022e-16,
+                          0.5 0.866025 -1.24337e-16,
+                          0.5 0.866025 -1.24337e-16,
+                          0.5 0.866025 -1.24337e-16,
+                          0.866025 0.5 -1.04336e-16,
+                          0.866025 0.5 -1.04336e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 0.856699 -2.0597 -5,
+                          0.598674 -0.434958 -5,
+                          0.74 0 -5,
+                          0.74 0 -2.8,
+                          0.74 0 -5,
+                          0.598674 -0.434958 -5,
+                          2.4 2.25 -5,
+                          0.74 0 -5,
+                          0.598674 0.434958 -5,
+                          0.598674 0.434958 -2.8,
+                          0.598674 0.434958 -5,
+                          0.74 0 -5,
+                          2.4 2.25 -5,
+                          0.856699 -2.0597 -5,
+                          0.74 0 -5,
+                          0.598674 0.434958 -2.8,
+                          0.74 0 -5,
+                          0.74 0 -2.8,
+                          -0.1 -2.25 -5,
+                          0.228666 -0.703784 -5,
+                          0.598674 -0.434958 -5,
+                          0.598674 -0.434958 -2.8,
+                          0.598674 -0.434958 -5,
+                          0.228666 -0.703784 -5,
+                          0.856699 -2.0597 -5,
+                          -0.1 -2.25 -5,
+                          0.598674 -0.434958 -5,
+                          0.598674 -0.434958 -2.8,
+                          0.74 0 -2.8,
+                          0.598674 -0.434958 -5,
+                          -0.1 -2.25 -5,
+                          -0.228666 -0.703784 -5,
+                          0.228666 -0.703784 -5,
+                          0.228666 -0.703784 -2.8,
+                          0.228666 -0.703784 -5,
+                          -0.228666 -0.703784 -5,
+                          0.598674 -0.434958 -2.8,
+                          0.228666 -0.703784 -5,
+                          0.228666 -0.703784 -2.8,
+                          -37.6 -2.25 -5,
+                          -0.598674 -0.434958 -5,
+                          -0.228666 -0.703784 -5,
+                          -0.228666 -0.703784 -2.8,
+                          -0.228666 -0.703784 -5,
+                          -0.598674 -0.434958 -5,
+                          -0.1 -2.25 -5,
+                          -37.6 -2.25 -5,
+                          -0.228666 -0.703784 -5,
+                          0.228666 -0.703784 -2.8,
+                          -0.228666 -0.703784 -5,
+                          -0.228666 -0.703784 -2.8,
+                          -37.6 -2.25 -5,
+                          -0.74 0 -5,
+                          -0.598674 -0.434958 -5,
+                          -0.598674 -0.434958 -2.8,
+                          -0.598674 -0.434958 -5,
+                          -0.74 0 -5,
+                          -0.228666 -0.703784 -2.8,
+                          -0.598674 -0.434958 -5,
+                          -0.598674 -0.434958 -2.8,
+                          -37.6 -2.25 -5,
+                          -0.598674 0.434958 -5,
+                          -0.74 0 -5,
+                          -0.74 0 -2.8,
+                          -0.74 0 -5,
+                          -0.598674 0.434958 -5,
+                          -0.598674 -0.434958 -2.8,
+                          -0.74 0 -5,
+                          -0.74 0 -2.8,
+                          -37.6 -2.25 -5,
+                          -0.228666 0.703784 -5,
+                          -0.598674 0.434958 -5,
+                          -0.598674 0.434958 -2.8,
+                          -0.598674 0.434958 -5,
+                          -0.228666 0.703784 -5,
+                          -0.74 0 -2.8,
+                          -0.598674 0.434958 -5,
+                          -0.598674 0.434958 -2.8,
+                          2.4 2.25 -5,
+                          0.228666 0.703784 -5,
+                          -0.228666 0.703784 -5,
+                          -0.228666 0.703784 -2.8,
+                          -0.228666 0.703784 -5,
+                          0.228666 0.703784 -5,
+                          2.4 2.25 -5,
+                          -0.228666 0.703784 -5,
+                          -37.6 -2.25 -5,
+                          -0.598674 0.434958 -2.8,
+                          -0.228666 0.703784 -5,
+                          -0.228666 0.703784 -2.8,
+                          2.4 2.25 -5,
+                          0.598674 0.434958 -5,
+                          0.228666 0.703784 -5,
+                          0.228666 0.703784 -2.8,
+                          0.228666 0.703784 -5,
+                          0.598674 0.434958 -5,
+                          -0.228666 0.703784 -2.8,
+                          0.228666 0.703784 -5,
+                          0.228666 0.703784 -2.8,
+                          0.228666 0.703784 -2.8,
+                          0.598674 0.434958 -5,
+                          0.598674 0.434958 -2.8,
+                          -37.6 -2.25 -2.5,
+                          -37.6 -2.25 -5,
+                          -0.1 -2.25 -5,
+                          -37.6 2.25 -5,
+                          2.4 2.25 -5,
+                          -37.6 -2.25 -5,
+                          -37.6 2.25 -2.5,
+                          -37.6 2.25 -5,
+                          -37.6 -2.25 -5,
+                          -37.6 2.25 -2.5,
+                          -37.6 -2.25 -5,
+                          -37.6 -2.25 -2.5,
+                          -0.1 -2.25 -2.8,
+                          -0.1 -2.25 -5,
+                          0.856699 -2.0597 -5,
+                          -37.6 -2.25 2.5,
+                          -0.1 -2.25 -5,
+                          -37.6 -2.25 5,
+                          -2.25 -2.25 -2.8,
+                          -37.6 -2.25 5,
+                          -0.1 -2.25 -5,
+                          -2.25 -2.25 -2.8,
+                          -0.1 -2.25 -5,
+                          -0.1 -2.25 -2.8,
+                          -37.6 -2.25 2.5,
+                          -37.6 -2.25 -2.5,
+                          -0.1 -2.25 -5,
+                          2.4 2.25 -5,
+                          1.66777 -1.51777 -5,
+                          0.856699 -2.0597 -5,
+                          0.856699 -2.0597 -2.8,
+                          0.856699 -2.0597 -5,
+                          1.66777 -1.51777 -5,
+                          0.856699 -2.0597 -2.8,
+                          -0.1 -2.25 -2.8,
+                          0.856699 -2.0597 -5,
+                          2.4 2.25 -5,
+                          2.2097 -0.706699 -5,
+                          1.66777 -1.51777 -5,
+                          1.66777 -1.51777 -2.8,
+                          1.66777 -1.51777 -5,
+                          2.2097 -0.706699 -5,
+                          0.856699 -2.0597 -2.8,
+                          1.66777 -1.51777 -5,
+                          1.66777 -1.51777 -2.8,
+                          2.4 2.25 -5,
+                          2.4 0.25 -5,
+                          2.2097 -0.706699 -5,
+                          2.2097 -0.706699 -2.8,
+                          2.2097 -0.706699 -5,
+                          2.4 0.25 -5,
+                          1.66777 -1.51777 -2.8,
+                          2.2097 -0.706699 -5,
+                          2.2097 -0.706699 -2.8,
+                          2.4 2.25 -2.8,
+                          2.4 0.25 -5,
+                          2.4 2.25 -5,
+                          2.4 2.25 -2.8,
+                          2.4 0.25 -2.8,
+                          2.4 0.25 -5,
+                          2.2097 -0.706699 -2.8,
+                          2.4 0.25 -5,
+                          2.4 0.25 -2.8,
+                          2.4 2.25 -2.8,
+                          2.4 2.25 -5,
+                          -37.6 2.25 -5,
+                          -2.25 2.25 2.8,
+                          -37.6 2.25 -5,
+                          2.4 2.25 5,
+                          -37.6 2.25 -2.5,
+                          2.4 2.25 5,
+                          -37.6 2.25 -5,
+                          -2.25 2.25 -2.8,
+                          2.4 2.25 -2.8,
+                          -37.6 2.25 -5,
+                          -2.25 2.25 2.8,
+                          -2.25 2.25 -2.8,
+                          -37.6 2.25 -5,
+                          -0.1 -2.25 5,
+                          -0.606764 -0.440835 5,
+                          -0.75 0 5,
+                          -0.75 0 2.8,
+                          -0.75 0 5,
+                          -0.606764 -0.440835 5,
+                          -37.6 2.25 5,
+                          -0.75 0 5,
+                          -0.606764 0.440835 5,
+                          -0.606764 0.440835 2.8,
+                          -0.606764 0.440835 5,
+                          -0.75 0 5,
+                          -37.6 2.25 5,
+                          -0.1 -2.25 5,
+                          -0.75 0 5,
+                          -0.606764 0.440835 2.8,
+                          -0.75 0 5,
+                          -0.75 0 2.8,
+                          -0.1 -2.25 5,
+                          -0.231756 -0.713294 5,
+                          -0.606764 -0.440835 5,
+                          -0.606764 -0.440835 2.8,
+                          -0.606764 -0.440835 5,
+                          -0.231756 -0.713294 5,
+                          -0.606764 -0.440835 2.8,
+                          -0.75 0 2.8,
+                          -0.606764 -0.440835 5,
+                          -0.1 -2.25 5,
+                          0.231756 -0.713294 5,
+                          -0.231756 -0.713294 5,
+                          -0.231756 -0.713294 2.8,
+                          -0.231756 -0.713294 5,
+                          0.231756 -0.713294 5,
+                          -0.606764 -0.440835 2.8,
+                          -0.231756 -0.713294 5,
+                          -0.231756 -0.713294 2.8,
+                          0.856699 -2.0597 5,
+                          0.606764 -0.440835 5,
+                          0.231756 -0.713294 5,
+                          0.231756 -0.713294 2.8,
+                          0.231756 -0.713294 5,
+                          0.606764 -0.440835 5,
+                          0.856699 -2.0597 5,
+                          0.231756 -0.713294 5,
+                          -0.1 -2.25 5,
+                          -0.231756 -0.713294 2.8,
+                          0.231756 -0.713294 5,
+                          0.231756 -0.713294 2.8,
+                          0.856699 -2.0597 5,
+                          0.75 0 5,
+                          0.606764 -0.440835 5,
+                          0.606764 -0.440835 2.8,
+                          0.606764 -0.440835 5,
+                          0.75 0 5,
+                          0.231756 -0.713294 2.8,
+                          0.606764 -0.440835 5,
+                          0.606764 -0.440835 2.8,
+                          1.66777 -1.51777 5,
+                          0.606764 0.440835 5,
+                          0.75 0 5,
+                          0.75 0 2.8,
+                          0.75 0 5,
+                          0.606764 0.440835 5,
+                          0.856699 -2.0597 5,
+                          1.66777 -1.51777 5,
+                          0.75 0 5,
+                          0.606764 -0.440835 2.8,
+                          0.75 0 5,
+                          0.75 0 2.8,
+                          2.2097 -0.706699 5,
+                          0.231756 0.713294 5,
+                          0.606764 0.440835 5,
+                          0.606764 0.440835 2.8,
+                          0.606764 0.440835 5,
+                          0.231756 0.713294 5,
+                          1.66777 -1.51777 5,
+                          2.2097 -0.706699 5,
+                          0.606764 0.440835 5,
+                          0.75 0 2.8,
+                          0.606764 0.440835 5,
+                          0.606764 0.440835 2.8,
+                          -37.6 2.25 5,
+                          -0.231756 0.713294 5,
+                          0.231756 0.713294 5,
+                          0.231756 0.713294 2.8,
+                          0.231756 0.713294 5,
+                          -0.231756 0.713294 5,
+                          2.4 2.25 5,
+                          -37.6 2.25 5,
+                          0.231756 0.713294 5,
+                          2.4 0.25 5,
+                          2.4 2.25 5,
+                          0.231756 0.713294 5,
+                          2.2097 -0.706699 5,
+                          2.4 0.25 5,
+                          0.231756 0.713294 5,
+                          0.606764 0.440835 2.8,
+                          0.231756 0.713294 5,
+                          0.231756 0.713294 2.8,
+                          -37.6 2.25 5,
+                          -0.606764 0.440835 5,
+                          -0.231756 0.713294 5,
+                          -0.231756 0.713294 2.8,
+                          -0.231756 0.713294 5,
+                          -0.606764 0.440835 5,
+                          0.231756 0.713294 2.8,
+                          -0.231756 0.713294 5,
+                          -0.231756 0.713294 2.8,
+                          -0.231756 0.713294 2.8,
+                          -0.606764 0.440835 5,
+                          -0.606764 0.440835 2.8,
+                          -37.6 2.25 5,
+                          -37.6 -2.25 5,
+                          -0.1 -2.25 5,
+                          -0.1 -2.25 2.8,
+                          -0.1 -2.25 5,
+                          -37.6 -2.25 5,
+                          0.856699 -2.0597 2.8,
+                          0.856699 -2.0597 5,
+                          -0.1 -2.25 5,
+                          0.856699 -2.0597 2.8,
+                          -0.1 -2.25 5,
+                          -0.1 -2.25 2.8,
+                          -37.6 -2.25 2.5,
+                          -37.6 -2.25 5,
+                          -37.6 2.25 5,
+                          -2.25 -2.25 2.8,
+                          -0.1 -2.25 2.8,
+                          -37.6 -2.25 5,
+                          -2.25 -2.25 -2.8,
+                          -2.25 -2.25 2.8,
+                          -37.6 -2.25 5,
+                          -37.6 2.25 2.5,
+                          -37.6 2.25 5,
+                          2.4 2.25 5,
+                          -37.6 2.25 2.5,
+                          -37.6 -2.25 2.5,
+                          -37.6 2.25 5,
+                          2.4 0.25 2.8,
+                          2.4 2.25 5,
+                          2.4 0.25 5,
+                          2.4 2.25 2.8,
+                          2.4 2.25 5,
+                          2.4 0.25 2.8,
+                          -2.25 2.25 2.8,
+                          2.4 2.25 5,
+                          2.4 2.25 2.8,
+                          -37.6 2.25 -2.5,
+                          -37.6 2.25 2.5,
+                          2.4 2.25 5,
+                          2.4 0.25 2.8,
+                          2.4 0.25 5,
+                          2.2097 -0.706699 5,
+                          2.2097 -0.706699 2.8,
+                          2.2097 -0.706699 5,
+                          1.66777 -1.51777 5,
+                          2.2097 -0.706699 2.8,
+                          2.4 0.25 2.8,
+                          2.2097 -0.706699 5,
+                          1.66777 -1.51777 2.8,
+                          1.66777 -1.51777 5,
+                          0.856699 -2.0597 5,
+                          2.2097 -0.706699 2.8,
+                          1.66777 -1.51777 5,
+                          1.66777 -1.51777 2.8,
+                          1.66777 -1.51777 2.8,
+                          0.856699 -2.0597 5,
+                          0.856699 -2.0597 2.8,
+                          -42.25 -2.25 2.5,
+                          -42.25 2.25 2.5,
+                          -42.25 2.25 -2.5,
+                          -37.6 2.25 2.5,
+                          -42.25 2.25 -2.5,
+                          -42.25 2.25 2.5,
+                          -42.25 -2.25 -2.5,
+                          -42.25 -2.25 2.5,
+                          -42.25 2.25 -2.5,
+                          -40.9093 0.525005 -2.5,
+                          -42.25 -2.25 -2.5,
+                          -42.25 2.25 -2.5,
+                          -37.6 2.25 -2.5,
+                          -42.25 2.25 -2.5,
+                          -37.6 2.25 2.5,
+                          -40.525 0.909323 -2.5,
+                          -42.25 2.25 -2.5,
+                          -37.6 2.25 -2.5,
+                          -40.525 0.909323 -2.5,
+                          -40.9093 0.525005 -2.5,
+                          -42.25 2.25 -2.5,
+                          -40.9093 -0.525005 2.5,
+                          -42.25 2.25 2.5,
+                          -42.25 -2.25 2.5,
+                          -39.475 0.909323 2.5,
+                          -37.6 2.25 2.5,
+                          -42.25 2.25 2.5,
+                          -40.9093 -0.525005 2.5,
+                          -41.05 0 2.5,
+                          -42.25 2.25 2.5,
+                          -40.9093 0.525005 2.5,
+                          -42.25 2.25 2.5,
+                          -41.05 0 2.5,
+                          -40 1.05 2.5,
+                          -39.475 0.909323 2.5,
+                          -42.25 2.25 2.5,
+                          -40.525 0.909323 2.5,
+                          -40 1.05 2.5,
+                          -42.25 2.25 2.5,
+                          -40.9093 0.525005 2.5,
+                          -40.525 0.909323 2.5,
+                          -42.25 2.25 2.5,
+                          -37.6 -2.25 -2.5,
+                          -42.25 -2.25 2.5,
+                          -42.25 -2.25 -2.5,
+                          -37.6 -2.25 2.5,
+                          -42.25 -2.25 2.5,
+                          -37.6 -2.25 -2.5,
+                          -40.525 -0.909323 2.5,
+                          -42.25 -2.25 2.5,
+                          -37.6 -2.25 2.5,
+                          -40.525 -0.909323 2.5,
+                          -40.9093 -0.525005 2.5,
+                          -42.25 -2.25 2.5,
+                          -39.475 -0.909323 -2.5,
+                          -37.6 -2.25 -2.5,
+                          -42.25 -2.25 -2.5,
+                          -40.9093 0.525005 -2.5,
+                          -41.05 0 -2.5,
+                          -42.25 -2.25 -2.5,
+                          -40.9093 -0.525005 -2.5,
+                          -42.25 -2.25 -2.5,
+                          -41.05 0 -2.5,
+                          -40 -1.05 -2.5,
+                          -39.475 -0.909323 -2.5,
+                          -42.25 -2.25 -2.5,
+                          -40.525 -0.909323 -2.5,
+                          -40 -1.05 -2.5,
+                          -42.25 -2.25 -2.5,
+                          -40.9093 -0.525005 -2.5,
+                          -40.525 -0.909323 -2.5,
+                          -42.25 -2.25 -2.5,
+                          -2.25 2.25 -2.8,
+                          -2.25 -2.25 -2.8,
+                          -0.1 -2.25 -2.8,
+                          -0.74 0 -2.8,
+                          -2.25 2.25 -2.8,
+                          -0.1 -2.25 -2.8,
+                          -0.598674 -0.434958 -2.8,
+                          -0.74 0 -2.8,
+                          -0.1 -2.25 -2.8,
+                          -0.228666 -0.703784 -2.8,
+                          -0.598674 -0.434958 -2.8,
+                          -0.1 -2.25 -2.8,
+                          0.228666 -0.703784 -2.8,
+                          -0.228666 -0.703784 -2.8,
+                          -0.1 -2.25 -2.8,
+                          0.856699 -2.0597 -2.8,
+                          0.228666 -0.703784 -2.8,
+                          -0.1 -2.25 -2.8,
+                          -39.0907 -0.525005 -2.5,
+                          -37.6 2.25 -2.5,
+                          -37.6 -2.25 -2.5,
+                          -39.475 -0.909323 -2.5,
+                          -39.0907 -0.525005 -2.5,
+                          -37.6 -2.25 -2.5,
+                          -39.0907 0.525005 2.5,
+                          -37.6 -2.25 2.5,
+                          -37.6 2.25 2.5,
+                          -40 -1.05 2.5,
+                          -40.525 -0.909323 2.5,
+                          -37.6 -2.25 2.5,
+                          -39.475 -0.909323 2.5,
+                          -40 -1.05 2.5,
+                          -37.6 -2.25 2.5,
+                          -39.0907 -0.525005 2.5,
+                          -39.475 -0.909323 2.5,
+                          -37.6 -2.25 2.5,
+                          -38.95 0 2.5,
+                          -39.0907 -0.525005 2.5,
+                          -37.6 -2.25 2.5,
+                          -39.0907 0.525005 2.5,
+                          -38.95 0 2.5,
+                          -37.6 -2.25 2.5,
+                          -0.231756 -0.713294 2.8,
+                          -0.1 -2.25 2.8,
+                          -2.25 -2.25 2.8,
+                          0.231756 -0.713294 2.8,
+                          0.606764 -0.440835 2.8,
+                          -0.1 -2.25 2.8,
+                          0.856699 -2.0597 2.8,
+                          -0.1 -2.25 2.8,
+                          0.606764 -0.440835 2.8,
+                          -0.231756 -0.713294 2.8,
+                          0.231756 -0.713294 2.8,
+                          -0.1 -2.25 2.8,
+                          -2.25 2.25 2.8,
+                          -2.25 -2.25 2.8,
+                          -2.25 -2.25 -2.8,
+                          -0.606764 0.440835 2.8,
+                          -2.25 -2.25 2.8,
+                          -2.25 2.25 2.8,
+                          -0.606764 0.440835 2.8,
+                          -0.75 0 2.8,
+                          -2.25 -2.25 2.8,
+                          -0.606764 -0.440835 2.8,
+                          -2.25 -2.25 2.8,
+                          -0.75 0 2.8,
+                          -0.606764 -0.440835 2.8,
+                          -0.231756 -0.713294 2.8,
+                          -2.25 -2.25 2.8,
+                          -2.25 2.25 2.8,
+                          -2.25 -2.25 -2.8,
+                          -2.25 2.25 -2.8,
+                          -2.25 2.25 -2.8,
+                          2.4 0.25 -2.8,
+                          2.4 2.25 -2.8,
+                          0.228666 0.703784 -2.8,
+                          2.4 0.25 -2.8,
+                          -2.25 2.25 -2.8,
+                          2.2097 -0.706699 -2.8,
+                          2.4 0.25 -2.8,
+                          0.228666 0.703784 -2.8,
+                          2.2097 -0.706699 2.8,
+                          2.4 2.25 2.8,
+                          2.4 0.25 2.8,
+                          -0.231756 0.713294 2.8,
+                          -2.25 2.25 2.8,
+                          2.4 2.25 2.8,
+                          0.231756 0.713294 2.8,
+                          -0.231756 0.713294 2.8,
+                          2.4 2.25 2.8,
+                          0.606764 0.440835 2.8,
+                          0.231756 0.713294 2.8,
+                          2.4 2.25 2.8,
+                          0.75 0 2.8,
+                          0.606764 0.440835 2.8,
+                          2.4 2.25 2.8,
+                          0.856699 -2.0597 2.8,
+                          0.75 0 2.8,
+                          2.4 2.25 2.8,
+                          1.66777 -1.51777 2.8,
+                          0.856699 -2.0597 2.8,
+                          2.4 2.25 2.8,
+                          2.2097 -0.706699 2.8,
+                          1.66777 -1.51777 2.8,
+                          2.4 2.25 2.8,
+                          -0.228666 0.703784 -2.8,
+                          0.228666 0.703784 -2.8,
+                          -2.25 2.25 -2.8,
+                          -0.598674 0.434958 -2.8,
+                          -0.228666 0.703784 -2.8,
+                          -2.25 2.25 -2.8,
+                          -0.74 0 -2.8,
+                          -0.598674 0.434958 -2.8,
+                          -2.25 2.25 -2.8,
+                          -0.231756 0.713294 2.8,
+                          -0.606764 0.440835 2.8,
+                          -2.25 2.25 2.8,
+                          -39.475 0.909323 2.5,
+                          -39.0907 0.525005 2.5,
+                          -37.6 2.25 2.5,
+                          -40 1.05 -2.5,
+                          -40.525 0.909323 -2.5,
+                          -37.6 2.25 -2.5,
+                          -39.475 0.909323 -2.5,
+                          -40 1.05 -2.5,
+                          -37.6 2.25 -2.5,
+                          -39.0907 0.525005 -2.5,
+                          -39.475 0.909323 -2.5,
+                          -37.6 2.25 -2.5,
+                          -38.95 0 -2.5,
+                          -39.0907 0.525005 -2.5,
+                          -37.6 2.25 -2.5,
+                          -39.0907 -0.525005 -2.5,
+                          -38.95 0 -2.5,
+                          -37.6 2.25 -2.5,
+                          1.66777 -1.51777 -2.8,
+                          0.598674 0.434958 -2.8,
+                          0.74 0 -2.8,
+                          0.856699 -2.0597 -2.8,
+                          0.74 0 -2.8,
+                          0.598674 -0.434958 -2.8,
+                          0.856699 -2.0597 -2.8,
+                          1.66777 -1.51777 -2.8,
+                          0.74 0 -2.8,
+                          2.2097 -0.706699 -2.8,
+                          0.228666 0.703784 -2.8,
+                          0.598674 0.434958 -2.8,
+                          1.66777 -1.51777 -2.8,
+                          2.2097 -0.706699 -2.8,
+                          0.598674 0.434958 -2.8,
+                          0.856699 -2.0597 -2.8,
+                          0.598674 -0.434958 -2.8,
+                          0.228666 -0.703784 -2.8,
+                          0.856699 -2.0597 2.8,
+                          0.606764 -0.440835 2.8,
+                          0.75 0 2.8,
+                          -41.05 0 2.5,
+                          -41.05 0 -2.5,
+                          -40.9093 0.525005 -2.5,
+                          -40.9093 -0.525005 2.5,
+                          -40.9093 -0.525005 -2.5,
+                          -41.05 0 -2.5,
+                          -40.9093 -0.525005 2.5,
+                          -41.05 0 -2.5,
+                          -41.05 0 2.5,
+                          -40.9093 0.525005 2.5,
+                          -40.9093 0.525005 -2.5,
+                          -40.525 0.909323 -2.5,
+                          -40.9093 0.525005 2.5,
+                          -41.05 0 2.5,
+                          -40.9093 0.525005 -2.5,
+                          -40.525 0.909323 2.5,
+                          -40.525 0.909323 -2.5,
+                          -40 1.05 -2.5,
+                          -40.9093 0.525005 2.5,
+                          -40.525 0.909323 -2.5,
+                          -40.525 0.909323 2.5,
+                          -40 1.05 2.5,
+                          -40 1.05 -2.5,
+                          -39.475 0.909323 -2.5,
+                          -40.525 0.909323 2.5,
+                          -40 1.05 -2.5,
+                          -40 1.05 2.5,
+                          -39.475 0.909323 2.5,
+                          -39.475 0.909323 -2.5,
+                          -39.0907 0.525005 -2.5,
+                          -40 1.05 2.5,
+                          -39.475 0.909323 -2.5,
+                          -39.475 0.909323 2.5,
+                          -39.0907 0.525005 2.5,
+                          -39.0907 0.525005 -2.5,
+                          -38.95 0 -2.5,
+                          -39.475 0.909323 2.5,
+                          -39.0907 0.525005 -2.5,
+                          -39.0907 0.525005 2.5,
+                          -38.95 0 2.5,
+                          -38.95 0 -2.5,
+                          -39.0907 -0.525005 -2.5,
+                          -39.0907 0.525005 2.5,
+                          -38.95 0 -2.5,
+                          -38.95 0 2.5,
+                          -39.0907 -0.525005 2.5,
+                          -39.0907 -0.525005 -2.5,
+                          -39.475 -0.909323 -2.5,
+                          -38.95 0 2.5,
+                          -39.0907 -0.525005 -2.5,
+                          -39.0907 -0.525005 2.5,
+                          -39.475 -0.909323 2.5,
+                          -39.475 -0.909323 -2.5,
+                          -40 -1.05 -2.5,
+                          -39.0907 -0.525005 2.5,
+                          -39.475 -0.909323 -2.5,
+                          -39.475 -0.909323 2.5,
+                          -40 -1.05 2.5,
+                          -40 -1.05 -2.5,
+                          -40.525 -0.909323 -2.5,
+                          -39.475 -0.909323 2.5,
+                          -40 -1.05 -2.5,
+                          -40 -1.05 2.5,
+                          -40.525 -0.909323 2.5,
+                          -40.525 -0.909323 -2.5,
+                          -40.9093 -0.525005 -2.5,
+                          -40 -1.05 2.5,
+                          -40.525 -0.909323 -2.5,
+                          -40.525 -0.909323 2.5,
+                          -40.525 -0.909323 2.5,
+                          -40.9093 -0.525005 -2.5,
+                          -40.9093 -0.525005 2.5 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0 0 1
+    }
+    Separator {
+        Normal {
+            vector      [ 5.55112e-17 1 5.55112e-17,
+                          5.55112e-17 1 5.55112e-17,
+                          5.55112e-17 1 5.55112e-17,
+                          1 -1.11022e-16 -5.55112e-17,
+                          1 -1.11022e-16 -5.55112e-17,
+                          0.92388 -6.00848e-17 0.382683,
+                          5.55112e-17 1 5.55112e-17,
+                          5.55112e-17 1 5.55112e-17,
+                          5.55112e-17 1 5.55112e-17,
+                          5.55112e-17 1 5.55112e-17,
+                          5.55112e-17 1 5.55112e-17,
+                          5.55112e-17 1 5.55112e-17,
+                          0.92388 -1.45058e-16 -0.382683,
+                          0.92388 -1.45058e-16 -0.382683,
+                          1 -1.11022e-16 -3.00441e-16,
+                          0.92388 -1.45058e-16 -0.382683,
+                          1 -1.11022e-16 -3.00441e-16,
+                          1 -1.11022e-16 -3.00441e-16,
+                          5.55112e-17 1 5.55112e-17,
+                          5.55112e-17 1 5.55112e-17,
+                          5.55112e-17 1 5.55112e-17,
+                          0.92388 -6.00848e-17 0.382683,
+                          0.92388 -6.00848e-17 0.382683,
+                          0.707107 0 0.707107,
+                          5.55112e-17 1 5.55112e-17,
+                          5.55112e-17 1 5.55112e-17,
+                          5.55112e-17 1 5.55112e-17,
+                          0.92388 -6.00848e-17 0.382683,
+                          1 -1.11022e-16 -5.55112e-17,
+                          0.92388 -6.00848e-17 0.382683,
+                          5.55112e-17 1 5.55112e-17,
+                          5.55112e-17 1 5.55112e-17,
+                          5.55112e-17 1 5.55112e-17,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          0.382683 6.00848e-17 0.92388,
+                          5.55112e-17 1 5.55112e-17,
+                          5.55112e-17 1 5.55112e-17,
+                          5.55112e-17 1 5.55112e-17,
+                          0.92388 -6.00848e-17 0.382683,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          5.55112e-17 1 5.55112e-17,
+                          5.55112e-17 1 5.55112e-17,
+                          5.55112e-17 1 5.55112e-17,
+                          0.382683 6.00848e-17 0.92388,
+                          0.382683 6.00848e-17 0.92388,
+                          -4.979e-17 1.11022e-16 1,
+                          0.707107 0 0.707107,
+                          0.382683 6.00848e-17 0.92388,
+                          0.382683 6.00848e-17 0.92388,
+                          -4.979e-17 1.11022e-16 1,
+                          -4.979e-17 1.11022e-16 1,
+                          -0.382683 1.45058e-16 0.92388,
+                          0.382683 6.00848e-17 0.92388,
+                          -4.979e-17 1.11022e-16 1,
+                          -4.979e-17 1.11022e-16 1,
+                          -0.382683 1.45058e-16 0.92388,
+                          -0.382683 1.45058e-16 0.92388,
+                          -0.707107 1.57009e-16 0.707107,
+                          -4.979e-17 1.11022e-16 1,
+                          -0.382683 1.45058e-16 0.92388,
+                          -0.382683 1.45058e-16 0.92388,
+                          -0.707107 1.57009e-16 0.707107,
+                          -0.707107 1.57009e-16 0.707107,
+                          -0.92388 1.45058e-16 0.382683,
+                          -0.382683 1.45058e-16 0.92388,
+                          -0.707107 1.57009e-16 0.707107,
+                          -0.707107 1.57009e-16 0.707107,
+                          -0.92388 1.45058e-16 0.382683,
+                          -0.92388 1.45058e-16 0.382683,
+                          -1 1.11022e-16 1.77976e-16,
+                          -0.707107 1.57009e-16 0.707107,
+                          -0.92388 1.45058e-16 0.382683,
+                          -0.92388 1.45058e-16 0.382683,
+                          5.55112e-17 1 5.55112e-17,
+                          5.55112e-17 1 5.55112e-17,
+                          5.55112e-17 1 5.55112e-17,
+                          -1 1.11022e-16 1.77976e-16,
+                          -1 1.11022e-16 1.77976e-16,
+                          -0.92388 6.00848e-17 -0.382683,
+                          -0.92388 1.45058e-16 0.382683,
+                          -1 1.11022e-16 1.77976e-16,
+                          -1 1.11022e-16 1.77976e-16,
+                          5.55112e-17 1 5.55112e-17,
+                          5.55112e-17 1 5.55112e-17,
+                          5.55112e-17 1 5.55112e-17,
+                          -0.92388 6.00848e-17 -0.382683,
+                          -0.92388 6.00848e-17 -0.382683,
+                          -0.707107 0 -0.707107,
+                          5.55112e-17 1 5.55112e-17,
+                          5.55112e-17 1 5.55112e-17,
+                          5.55112e-17 1 5.55112e-17,
+                          -1 1.11022e-16 1.77976e-16,
+                          -0.92388 6.00848e-17 -0.382683,
+                          -0.92388 6.00848e-17 -0.382683,
+                          5.55112e-17 1 5.55112e-17,
+                          5.55112e-17 1 5.55112e-17,
+                          5.55112e-17 1 5.55112e-17,
+                          -0.707107 0 -0.707107,
+                          -0.707107 0 -0.707107,
+                          -0.382683 -6.00848e-17 -0.92388,
+                          5.55112e-17 1 5.55112e-17,
+                          5.55112e-17 1 5.55112e-17,
+                          5.55112e-17 1 5.55112e-17,
+                          -0.92388 6.00848e-17 -0.382683,
+                          -0.707107 0 -0.707107,
+                          -0.707107 0 -0.707107,
+                          5.55112e-17 1 5.55112e-17,
+                          5.55112e-17 1 5.55112e-17,
+                          5.55112e-17 1 5.55112e-17,
+                          -0.382683 -6.00848e-17 -0.92388,
+                          -0.382683 -6.00848e-17 -0.92388,
+                          -7.26747e-17 -1.11022e-16 -1,
+                          -0.707107 0 -0.707107,
+                          -0.382683 -6.00848e-17 -0.92388,
+                          -0.382683 -6.00848e-17 -0.92388,
+                          -7.26747e-17 -1.11022e-16 -1,
+                          -7.26747e-17 -1.11022e-16 -1,
+                          0.382683 -1.45058e-16 -0.92388,
+                          -0.382683 -6.00848e-17 -0.92388,
+                          -7.26747e-17 -1.11022e-16 -1,
+                          -7.26747e-17 -1.11022e-16 -1,
+                          0.382683 -1.45058e-16 -0.92388,
+                          0.382683 -1.45058e-16 -0.92388,
+                          0.707107 -1.57009e-16 -0.707107,
+                          -7.26747e-17 -1.11022e-16 -1,
+                          0.382683 -1.45058e-16 -0.92388,
+                          0.382683 -1.45058e-16 -0.92388,
+                          0.707107 -1.57009e-16 -0.707107,
+                          0.707107 -1.57009e-16 -0.707107,
+                          0.92388 -1.45058e-16 -0.382683,
+                          0.382683 -1.45058e-16 -0.92388,
+                          0.707107 -1.57009e-16 -0.707107,
+                          0.707107 -1.57009e-16 -0.707107,
+                          0.707107 -1.57009e-16 -0.707107,
+                          0.92388 -1.45058e-16 -0.382683,
+                          0.92388 -1.45058e-16 -0.382683,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17,
+                          -5.55112e-17 -1 -5.55112e-17 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -16.6194 -2.25 1.91342,
+                          -7.3806 -2.25 1.91342,
+                          -7 -2.25 -2.93116e-14,
+                          -7 -3.75 -2.93948e-14,
+                          -7 -2.25 -2.93116e-14,
+                          -7.3806 -2.25 1.91342,
+                          -17 -2.25 -2.75319e-14,
+                          -16.6194 -2.25 1.91342,
+                          -7 -2.25 -2.93116e-14,
+                          -7.3806 -2.25 -1.91342,
+                          -17 -2.25 -2.75319e-14,
+                          -7 -2.25 -2.93116e-14,
+                          -7.3806 -3.75 -1.91342,
+                          -7.3806 -2.25 -1.91342,
+                          -7 -2.25 -2.93116e-14,
+                          -7.3806 -3.75 -1.91342,
+                          -7 -2.25 -2.93116e-14,
+                          -7 -3.75 -2.93948e-14,
+                          -15.5355 -2.25 3.53553,
+                          -8.46447 -2.25 3.53553,
+                          -7.3806 -2.25 1.91342,
+                          -7.3806 -3.75 1.91342,
+                          -7.3806 -2.25 1.91342,
+                          -8.46447 -2.25 3.53553,
+                          -16.6194 -2.25 1.91342,
+                          -15.5355 -2.25 3.53553,
+                          -7.3806 -2.25 1.91342,
+                          -7.3806 -3.75 1.91342,
+                          -7 -3.75 -2.93948e-14,
+                          -7.3806 -2.25 1.91342,
+                          -13.9134 -2.25 4.6194,
+                          -10.0866 -2.25 4.6194,
+                          -8.46447 -2.25 3.53553,
+                          -8.46447 -3.75 3.53553,
+                          -8.46447 -2.25 3.53553,
+                          -10.0866 -2.25 4.6194,
+                          -15.5355 -2.25 3.53553,
+                          -13.9134 -2.25 4.6194,
+                          -8.46447 -2.25 3.53553,
+                          -7.3806 -3.75 1.91342,
+                          -8.46447 -2.25 3.53553,
+                          -8.46447 -3.75 3.53553,
+                          -13.9134 -2.25 4.6194,
+                          -12 -2.25 5,
+                          -10.0866 -2.25 4.6194,
+                          -10.0866 -3.75 4.6194,
+                          -10.0866 -2.25 4.6194,
+                          -12 -2.25 5,
+                          -8.46447 -3.75 3.53553,
+                          -10.0866 -2.25 4.6194,
+                          -10.0866 -3.75 4.6194,
+                          -12 -3.75 5,
+                          -12 -2.25 5,
+                          -13.9134 -2.25 4.6194,
+                          -10.0866 -3.75 4.6194,
+                          -12 -2.25 5,
+                          -12 -3.75 5,
+                          -13.9134 -3.75 4.6194,
+                          -13.9134 -2.25 4.6194,
+                          -15.5355 -2.25 3.53553,
+                          -12 -3.75 5,
+                          -13.9134 -2.25 4.6194,
+                          -13.9134 -3.75 4.6194,
+                          -15.5355 -3.75 3.53553,
+                          -15.5355 -2.25 3.53553,
+                          -16.6194 -2.25 1.91342,
+                          -13.9134 -3.75 4.6194,
+                          -15.5355 -2.25 3.53553,
+                          -15.5355 -3.75 3.53553,
+                          -16.6194 -3.75 1.91342,
+                          -16.6194 -2.25 1.91342,
+                          -17 -2.25 -2.75319e-14,
+                          -15.5355 -3.75 3.53553,
+                          -16.6194 -2.25 1.91342,
+                          -16.6194 -3.75 1.91342,
+                          -7.3806 -2.25 -1.91342,
+                          -16.6194 -2.25 -1.91342,
+                          -17 -2.25 -2.75319e-14,
+                          -17 -3.75 -2.76151e-14,
+                          -17 -2.25 -2.75319e-14,
+                          -16.6194 -2.25 -1.91342,
+                          -16.6194 -3.75 1.91342,
+                          -17 -2.25 -2.75319e-14,
+                          -17 -3.75 -2.76151e-14,
+                          -8.46447 -2.25 -3.53553,
+                          -15.5355 -2.25 -3.53553,
+                          -16.6194 -2.25 -1.91342,
+                          -16.6194 -3.75 -1.91342,
+                          -16.6194 -2.25 -1.91342,
+                          -15.5355 -2.25 -3.53553,
+                          -7.3806 -2.25 -1.91342,
+                          -8.46447 -2.25 -3.53553,
+                          -16.6194 -2.25 -1.91342,
+                          -17 -3.75 -2.76151e-14,
+                          -16.6194 -2.25 -1.91342,
+                          -16.6194 -3.75 -1.91342,
+                          -10.0866 -2.25 -4.6194,
+                          -13.9134 -2.25 -4.6194,
+                          -15.5355 -2.25 -3.53553,
+                          -15.5355 -3.75 -3.53553,
+                          -15.5355 -2.25 -3.53553,
+                          -13.9134 -2.25 -4.6194,
+                          -8.46447 -2.25 -3.53553,
+                          -10.0866 -2.25 -4.6194,
+                          -15.5355 -2.25 -3.53553,
+                          -16.6194 -3.75 -1.91342,
+                          -15.5355 -2.25 -3.53553,
+                          -15.5355 -3.75 -3.53553,
+                          -10.0866 -2.25 -4.6194,
+                          -12 -2.25 -5,
+                          -13.9134 -2.25 -4.6194,
+                          -13.9134 -3.75 -4.6194,
+                          -13.9134 -2.25 -4.6194,
+                          -12 -2.25 -5,
+                          -15.5355 -3.75 -3.53553,
+                          -13.9134 -2.25 -4.6194,
+                          -13.9134 -3.75 -4.6194,
+                          -12 -3.75 -5,
+                          -12 -2.25 -5,
+                          -10.0866 -2.25 -4.6194,
+                          -13.9134 -3.75 -4.6194,
+                          -12 -2.25 -5,
+                          -12 -3.75 -5,
+                          -10.0866 -3.75 -4.6194,
+                          -10.0866 -2.25 -4.6194,
+                          -8.46447 -2.25 -3.53553,
+                          -12 -3.75 -5,
+                          -10.0866 -2.25 -4.6194,
+                          -10.0866 -3.75 -4.6194,
+                          -8.46447 -3.75 -3.53553,
+                          -8.46447 -2.25 -3.53553,
+                          -7.3806 -2.25 -1.91342,
+                          -10.0866 -3.75 -4.6194,
+                          -8.46447 -2.25 -3.53553,
+                          -8.46447 -3.75 -3.53553,
+                          -8.46447 -3.75 -3.53553,
+                          -7.3806 -2.25 -1.91342,
+                          -7.3806 -3.75 -1.91342,
+                          -16.6194 -3.75 -1.91342,
+                          -7.3806 -3.75 -1.91342,
+                          -7 -3.75 -2.93948e-14,
+                          -17 -3.75 -2.76151e-14,
+                          -16.6194 -3.75 -1.91342,
+                          -7 -3.75 -2.93948e-14,
+                          -7.3806 -3.75 1.91342,
+                          -17 -3.75 -2.76151e-14,
+                          -7 -3.75 -2.93948e-14,
+                          -15.5355 -3.75 -3.53553,
+                          -8.46447 -3.75 -3.53553,
+                          -7.3806 -3.75 -1.91342,
+                          -16.6194 -3.75 -1.91342,
+                          -15.5355 -3.75 -3.53553,
+                          -7.3806 -3.75 -1.91342,
+                          -13.9134 -3.75 -4.6194,
+                          -10.0866 -3.75 -4.6194,
+                          -8.46447 -3.75 -3.53553,
+                          -15.5355 -3.75 -3.53553,
+                          -13.9134 -3.75 -4.6194,
+                          -8.46447 -3.75 -3.53553,
+                          -13.9134 -3.75 -4.6194,
+                          -12 -3.75 -5,
+                          -10.0866 -3.75 -4.6194,
+                          -7.3806 -3.75 1.91342,
+                          -16.6194 -3.75 1.91342,
+                          -17 -3.75 -2.76151e-14,
+                          -8.46447 -3.75 3.53553,
+                          -15.5355 -3.75 3.53553,
+                          -16.6194 -3.75 1.91342,
+                          -7.3806 -3.75 1.91342,
+                          -8.46447 -3.75 3.53553,
+                          -16.6194 -3.75 1.91342,
+                          -10.0866 -3.75 4.6194,
+                          -13.9134 -3.75 4.6194,
+                          -15.5355 -3.75 3.53553,
+                          -8.46447 -3.75 3.53553,
+                          -10.0866 -3.75 4.6194,
+                          -15.5355 -3.75 3.53553,
+                          -10.0866 -3.75 4.6194,
+                          -12 -3.75 5,
+                          -13.9134 -3.75 4.6194 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ -1.11022e-16 1 0,
+                          -1.11022e-16 1 0,
+                          -1.11022e-16 1 0,
+                          5.55112e-17 5.55112e-17 1,
+                          5.55112e-17 5.55112e-17 1,
+                          -0.382683 1.57502e-16 0.92388,
+                          -1.11022e-16 1 0,
+                          -1.11022e-16 1 0,
+                          -1.11022e-16 1 0,
+                          -1.11022e-16 1 0,
+                          -1.11022e-16 1 0,
+                          -1.11022e-16 1 0,
+                          0.382683 -5.49304e-17 0.92388,
+                          0.382683 -5.49304e-17 0.92388,
+                          3.00441e-16 5.55112e-17 1,
+                          0.382683 -5.49304e-17 0.92388,
+                          3.00441e-16 5.55112e-17 1,
+                          3.00441e-16 5.55112e-17 1,
+                          -1.11022e-16 1 0,
+                          -1.11022e-16 1 0,
+                          -1.11022e-16 1 0,
+                          -0.382683 1.57502e-16 0.92388,
+                          -0.382683 1.57502e-16 0.92388,
+                          -0.707107 2.35514e-16 0.707107,
+                          -1.11022e-16 1 0,
+                          -1.11022e-16 1 0,
+                          -1.11022e-16 1 0,
+                          -0.382683 1.57502e-16 0.92388,
+                          5.55112e-17 5.55112e-17 1,
+                          -0.382683 1.57502e-16 0.92388,
+                          -1.11022e-16 1 0,
+                          -1.11022e-16 1 0,
+                          -1.11022e-16 1 0,
+                          -0.707107 2.35514e-16 0.707107,
+                          -0.707107 2.35514e-16 0.707107,
+                          -0.92388 2.77671e-16 0.382683,
+                          -1.11022e-16 1 0,
+                          -1.11022e-16 1 0,
+                          -1.11022e-16 1 0,
+                          -0.382683 1.57502e-16 0.92388,
+                          -0.707107 2.35514e-16 0.707107,
+                          -0.707107 2.35514e-16 0.707107,
+                          -1.11022e-16 1 0,
+                          -1.11022e-16 1 0,
+                          -1.11022e-16 1 0,
+                          -0.92388 2.77671e-16 0.382683,
+                          -0.92388 2.77671e-16 0.382683,
+                          -1 2.77556e-16 -4.979e-17,
+                          -0.707107 2.35514e-16 0.707107,
+                          -0.92388 2.77671e-16 0.382683,
+                          -0.92388 2.77671e-16 0.382683,
+                          -1 2.77556e-16 -4.979e-17,
+                          -1 2.77556e-16 -4.979e-17,
+                          -0.92388 2.35185e-16 -0.382683,
+                          -0.92388 2.77671e-16 0.382683,
+                          -1 2.77556e-16 -4.979e-17,
+                          -1 2.77556e-16 -4.979e-17,
+                          -0.92388 2.35185e-16 -0.382683,
+                          -0.92388 2.35185e-16 -0.382683,
+                          -0.707107 1.57009e-16 -0.707107,
+                          -1 2.77556e-16 -4.979e-17,
+                          -0.92388 2.35185e-16 -0.382683,
+                          -0.92388 2.35185e-16 -0.382683,
+                          -0.707107 1.57009e-16 -0.707107,
+                          -0.707107 1.57009e-16 -0.707107,
+                          -0.382683 5.49304e-17 -0.92388,
+                          -0.92388 2.35185e-16 -0.382683,
+                          -0.707107 1.57009e-16 -0.707107,
+                          -0.707107 1.57009e-16 -0.707107,
+                          -0.382683 5.49304e-17 -0.92388,
+                          -0.382683 5.49304e-17 -0.92388,
+                          -1.77976e-16 -5.55112e-17 -1,
+                          -0.707107 1.57009e-16 -0.707107,
+                          -0.382683 5.49304e-17 -0.92388,
+                          -0.382683 5.49304e-17 -0.92388,
+                          -1.11022e-16 1 0,
+                          -1.11022e-16 1 0,
+                          -1.11022e-16 1 0,
+                          -1.77976e-16 -5.55112e-17 -1,
+                          -1.77976e-16 -5.55112e-17 -1,
+                          0.382683 -1.57502e-16 -0.92388,
+                          -0.382683 5.49304e-17 -0.92388,
+                          -1.77976e-16 -5.55112e-17 -1,
+                          -1.77976e-16 -5.55112e-17 -1,
+                          -1.11022e-16 1 0,
+                          -1.11022e-16 1 0,
+                          -1.11022e-16 1 0,
+                          0.382683 -1.57502e-16 -0.92388,
+                          0.382683 -1.57502e-16 -0.92388,
+                          0.707107 -2.35514e-16 -0.707107,
+                          -1.11022e-16 1 0,
+                          -1.11022e-16 1 0,
+                          -1.11022e-16 1 0,
+                          -1.77976e-16 -5.55112e-17 -1,
+                          0.382683 -1.57502e-16 -0.92388,
+                          0.382683 -1.57502e-16 -0.92388,
+                          -1.11022e-16 1 0,
+                          -1.11022e-16 1 0,
+                          -1.11022e-16 1 0,
+                          0.707107 -2.35514e-16 -0.707107,
+                          0.707107 -2.35514e-16 -0.707107,
+                          0.92388 -2.77671e-16 -0.382683,
+                          -1.11022e-16 1 0,
+                          -1.11022e-16 1 0,
+                          -1.11022e-16 1 0,
+                          0.382683 -1.57502e-16 -0.92388,
+                          0.707107 -2.35514e-16 -0.707107,
+                          0.707107 -2.35514e-16 -0.707107,
+                          -1.11022e-16 1 0,
+                          -1.11022e-16 1 0,
+                          -1.11022e-16 1 0,
+                          0.92388 -2.77671e-16 -0.382683,
+                          0.92388 -2.77671e-16 -0.382683,
+                          1 -2.77556e-16 -7.26747e-17,
+                          0.707107 -2.35514e-16 -0.707107,
+                          0.92388 -2.77671e-16 -0.382683,
+                          0.92388 -2.77671e-16 -0.382683,
+                          1 -2.77556e-16 -7.26747e-17,
+                          1 -2.77556e-16 -7.26747e-17,
+                          0.92388 -2.35185e-16 0.382683,
+                          0.92388 -2.77671e-16 -0.382683,
+                          1 -2.77556e-16 -7.26747e-17,
+                          1 -2.77556e-16 -7.26747e-17,
+                          0.92388 -2.35185e-16 0.382683,
+                          0.92388 -2.35185e-16 0.382683,
+                          0.707107 -1.57009e-16 0.707107,
+                          1 -2.77556e-16 -7.26747e-17,
+                          0.92388 -2.35185e-16 0.382683,
+                          0.92388 -2.35185e-16 0.382683,
+                          0.707107 -1.57009e-16 0.707107,
+                          0.707107 -1.57009e-16 0.707107,
+                          0.382683 -5.49304e-17 0.92388,
+                          0.92388 -2.35185e-16 0.382683,
+                          0.707107 -1.57009e-16 0.707107,
+                          0.707107 -1.57009e-16 0.707107,
+                          0.707107 -1.57009e-16 0.707107,
+                          0.382683 -5.49304e-17 0.92388,
+                          0.382683 -5.49304e-17 0.92388,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0,
+                          1.11022e-16 -1 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -29.9134 -2.25 -4.6194,
+                          -29.9134 -2.25 4.6194,
+                          -28 -2.25 5,
+                          -28 -3.75 5,
+                          -28 -2.25 5,
+                          -29.9134 -2.25 4.6194,
+                          -28 -2.25 -5,
+                          -29.9134 -2.25 -4.6194,
+                          -28 -2.25 5,
+                          -26.0866 -2.25 4.6194,
+                          -28 -2.25 -5,
+                          -28 -2.25 5,
+                          -26.0866 -3.75 4.6194,
+                          -26.0866 -2.25 4.6194,
+                          -28 -2.25 5,
+                          -26.0866 -3.75 4.6194,
+                          -28 -2.25 5,
+                          -28 -3.75 5,
+                          -31.5355 -2.25 -3.53553,
+                          -31.5355 -2.25 3.53553,
+                          -29.9134 -2.25 4.6194,
+                          -29.9134 -3.75 4.6194,
+                          -29.9134 -2.25 4.6194,
+                          -31.5355 -2.25 3.53553,
+                          -29.9134 -2.25 -4.6194,
+                          -31.5355 -2.25 -3.53553,
+                          -29.9134 -2.25 4.6194,
+                          -29.9134 -3.75 4.6194,
+                          -28 -3.75 5,
+                          -29.9134 -2.25 4.6194,
+                          -32.6194 -2.25 -1.91342,
+                          -32.6194 -2.25 1.91342,
+                          -31.5355 -2.25 3.53553,
+                          -31.5355 -3.75 3.53553,
+                          -31.5355 -2.25 3.53553,
+                          -32.6194 -2.25 1.91342,
+                          -31.5355 -2.25 -3.53553,
+                          -32.6194 -2.25 -1.91342,
+                          -31.5355 -2.25 3.53553,
+                          -29.9134 -3.75 4.6194,
+                          -31.5355 -2.25 3.53553,
+                          -31.5355 -3.75 3.53553,
+                          -32.6194 -2.25 -1.91342,
+                          -33 -2.25 0,
+                          -32.6194 -2.25 1.91342,
+                          -32.6194 -3.75 1.91342,
+                          -32.6194 -2.25 1.91342,
+                          -33 -2.25 0,
+                          -31.5355 -3.75 3.53553,
+                          -32.6194 -2.25 1.91342,
+                          -32.6194 -3.75 1.91342,
+                          -33 -3.75 0,
+                          -33 -2.25 0,
+                          -32.6194 -2.25 -1.91342,
+                          -32.6194 -3.75 1.91342,
+                          -33 -2.25 0,
+                          -33 -3.75 0,
+                          -32.6194 -3.75 -1.91342,
+                          -32.6194 -2.25 -1.91342,
+                          -31.5355 -2.25 -3.53553,
+                          -33 -3.75 0,
+                          -32.6194 -2.25 -1.91342,
+                          -32.6194 -3.75 -1.91342,
+                          -31.5355 -3.75 -3.53553,
+                          -31.5355 -2.25 -3.53553,
+                          -29.9134 -2.25 -4.6194,
+                          -32.6194 -3.75 -1.91342,
+                          -31.5355 -2.25 -3.53553,
+                          -31.5355 -3.75 -3.53553,
+                          -29.9134 -3.75 -4.6194,
+                          -29.9134 -2.25 -4.6194,
+                          -28 -2.25 -5,
+                          -31.5355 -3.75 -3.53553,
+                          -29.9134 -2.25 -4.6194,
+                          -29.9134 -3.75 -4.6194,
+                          -26.0866 -2.25 4.6194,
+                          -26.0866 -2.25 -4.6194,
+                          -28 -2.25 -5,
+                          -28 -3.75 -5,
+                          -28 -2.25 -5,
+                          -26.0866 -2.25 -4.6194,
+                          -29.9134 -3.75 -4.6194,
+                          -28 -2.25 -5,
+                          -28 -3.75 -5,
+                          -24.4645 -2.25 3.53553,
+                          -24.4645 -2.25 -3.53553,
+                          -26.0866 -2.25 -4.6194,
+                          -26.0866 -3.75 -4.6194,
+                          -26.0866 -2.25 -4.6194,
+                          -24.4645 -2.25 -3.53553,
+                          -26.0866 -2.25 4.6194,
+                          -24.4645 -2.25 3.53553,
+                          -26.0866 -2.25 -4.6194,
+                          -28 -3.75 -5,
+                          -26.0866 -2.25 -4.6194,
+                          -26.0866 -3.75 -4.6194,
+                          -23.3806 -2.25 1.91342,
+                          -23.3806 -2.25 -1.91342,
+                          -24.4645 -2.25 -3.53553,
+                          -24.4645 -3.75 -3.53553,
+                          -24.4645 -2.25 -3.53553,
+                          -23.3806 -2.25 -1.91342,
+                          -24.4645 -2.25 3.53553,
+                          -23.3806 -2.25 1.91342,
+                          -24.4645 -2.25 -3.53553,
+                          -26.0866 -3.75 -4.6194,
+                          -24.4645 -2.25 -3.53553,
+                          -24.4645 -3.75 -3.53553,
+                          -23.3806 -2.25 1.91342,
+                          -23 -2.25 0,
+                          -23.3806 -2.25 -1.91342,
+                          -23.3806 -3.75 -1.91342,
+                          -23.3806 -2.25 -1.91342,
+                          -23 -2.25 0,
+                          -24.4645 -3.75 -3.53553,
+                          -23.3806 -2.25 -1.91342,
+                          -23.3806 -3.75 -1.91342,
+                          -23 -3.75 0,
+                          -23 -2.25 0,
+                          -23.3806 -2.25 1.91342,
+                          -23.3806 -3.75 -1.91342,
+                          -23 -2.25 0,
+                          -23 -3.75 0,
+                          -23.3806 -3.75 1.91342,
+                          -23.3806 -2.25 1.91342,
+                          -24.4645 -2.25 3.53553,
+                          -23 -3.75 0,
+                          -23.3806 -2.25 1.91342,
+                          -23.3806 -3.75 1.91342,
+                          -24.4645 -3.75 3.53553,
+                          -24.4645 -2.25 3.53553,
+                          -26.0866 -2.25 4.6194,
+                          -23.3806 -3.75 1.91342,
+                          -24.4645 -2.25 3.53553,
+                          -24.4645 -3.75 3.53553,
+                          -24.4645 -3.75 3.53553,
+                          -26.0866 -2.25 4.6194,
+                          -26.0866 -3.75 4.6194,
+                          -26.0866 -3.75 -4.6194,
+                          -26.0866 -3.75 4.6194,
+                          -28 -3.75 5,
+                          -28 -3.75 -5,
+                          -26.0866 -3.75 -4.6194,
+                          -28 -3.75 5,
+                          -29.9134 -3.75 4.6194,
+                          -28 -3.75 -5,
+                          -28 -3.75 5,
+                          -24.4645 -3.75 -3.53553,
+                          -24.4645 -3.75 3.53553,
+                          -26.0866 -3.75 4.6194,
+                          -26.0866 -3.75 -4.6194,
+                          -24.4645 -3.75 -3.53553,
+                          -26.0866 -3.75 4.6194,
+                          -23.3806 -3.75 -1.91342,
+                          -23.3806 -3.75 1.91342,
+                          -24.4645 -3.75 3.53553,
+                          -24.4645 -3.75 -3.53553,
+                          -23.3806 -3.75 -1.91342,
+                          -24.4645 -3.75 3.53553,
+                          -23.3806 -3.75 -1.91342,
+                          -23 -3.75 0,
+                          -23.3806 -3.75 1.91342,
+                          -29.9134 -3.75 4.6194,
+                          -29.9134 -3.75 -4.6194,
+                          -28 -3.75 -5,
+                          -31.5355 -3.75 3.53553,
+                          -31.5355 -3.75 -3.53553,
+                          -29.9134 -3.75 -4.6194,
+                          -29.9134 -3.75 4.6194,
+                          -31.5355 -3.75 3.53553,
+                          -29.9134 -3.75 -4.6194,
+                          -32.6194 -3.75 1.91342,
+                          -32.6194 -3.75 -1.91342,
+                          -31.5355 -3.75 -3.53553,
+                          -31.5355 -3.75 3.53553,
+                          -32.6194 -3.75 1.91342,
+                          -31.5355 -3.75 -3.53553,
+                          -32.6194 -3.75 1.91342,
+                          -33 -3.75 0,
+                          -32.6194 -3.75 -1.91342 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/palm1_l.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/palm1_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..a82ff29233dd000269f89b275a8da271ecde3fc6
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/palm1_l.iv
@@ -0,0 +1,4267 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+    Separator {
+        Normal {
+            vector      [ -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -3.46945e-16 -1 -8.40265e-14,
+                          -3.46945e-16 -1 -8.40265e-14,
+                          -3.46945e-16 -1 -8.40265e-14,
+                          5.87863e-14 -8.38357e-14 1,
+                          5.87863e-14 -8.38357e-14 1,
+                          5.87863e-14 -8.38357e-14 1,
+                          5.87863e-14 -8.38357e-14 1,
+                          5.87863e-14 -8.38357e-14 1,
+                          5.87863e-14 -8.38357e-14 1,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -5.87863e-14 8.38357e-14 -1,
+                          -5.87863e-14 8.38357e-14 -1,
+                          -5.87863e-14 8.38357e-14 -1,
+                          -3.46945e-16 -1 -8.40265e-14,
+                          -3.46945e-16 -1 -8.40265e-14,
+                          -3.46945e-16 -1 -8.40265e-14,
+                          -0.707107 0.707107 1.00748e-13,
+                          -0.707107 0.707107 1.00748e-13,
+                          -0.707107 0.707107 1.00748e-13,
+                          -5.87863e-14 8.38357e-14 -1,
+                          -5.87863e-14 8.38357e-14 -1,
+                          -5.87863e-14 8.38357e-14 -1,
+                          -5.87863e-14 8.38357e-14 -1,
+                          -5.87863e-14 8.38357e-14 -1,
+                          -5.87863e-14 8.38357e-14 -1,
+                          -5.87863e-14 8.38357e-14 -1,
+                          -5.87863e-14 8.38357e-14 -1,
+                          -5.87863e-14 8.38357e-14 -1,
+                          -5.87863e-14 8.38357e-14 -1,
+                          -5.87863e-14 8.38357e-14 -1,
+                          -5.87863e-14 8.38357e-14 -1,
+                          5.87863e-14 -8.38357e-14 1,
+                          5.87863e-14 -8.38357e-14 1,
+                          5.87863e-14 -8.38357e-14 1,
+                          -0.707107 0.707107 1.00748e-13,
+                          -0.707107 0.707107 1.00748e-13,
+                          -0.707107 0.707107 1.00748e-13,
+                          5.87863e-14 -8.38357e-14 1,
+                          5.87863e-14 -8.38357e-14 1,
+                          5.87863e-14 -8.38357e-14 1,
+                          -3.46945e-16 -1 -8.40265e-14,
+                          -3.46945e-16 -1 -8.40265e-14,
+                          -3.46945e-16 -1 -8.40265e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -5.87863e-14 8.38357e-14 -1,
+                          -5.87863e-14 8.38357e-14 -1,
+                          -5.87863e-14 8.38357e-14 -1,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -3.46945e-16 -1 -8.40265e-14,
+                          -3.46945e-16 -1 -8.40265e-14,
+                          -3.46945e-16 -1 -8.40265e-14,
+                          5.87863e-14 -8.38357e-14 1,
+                          5.87863e-14 -8.38357e-14 1,
+                          5.87863e-14 -8.38357e-14 1,
+                          5.87863e-14 -8.38357e-14 1,
+                          5.87863e-14 -8.38357e-14 1,
+                          5.87863e-14 -8.38357e-14 1,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          -5.87863e-14 8.38357e-14 -1,
+                          -5.87863e-14 8.38357e-14 -1,
+                          -5.87863e-14 8.38357e-14 -1,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          3.46945e-16 1 8.40265e-14,
+                          3.46945e-16 1 8.40265e-14,
+                          3.46945e-16 1 8.40265e-14,
+                          3.46945e-16 1 8.40265e-14,
+                          3.46945e-16 1 8.40265e-14,
+                          3.46945e-16 1 8.40265e-14,
+                          0.707107 0.707107 1.8083e-14,
+                          0.707107 0.707107 1.8083e-14,
+                          0.707107 0.707107 1.8083e-14,
+                          0.707107 0.707107 1.8083e-14,
+                          0.707107 0.707107 1.8083e-14,
+                          0.707107 0.707107 1.8083e-14,
+                          5.87863e-14 -8.38357e-14 1,
+                          5.87863e-14 -8.38357e-14 1,
+                          5.87863e-14 -8.38357e-14 1,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          5.87863e-14 -8.38357e-14 1,
+                          5.87863e-14 -8.38357e-14 1,
+                          5.87863e-14 -8.38357e-14 1,
+                          -3.46945e-16 -1 -8.40265e-14,
+                          -3.46945e-16 -1 -8.40265e-14,
+                          -3.46945e-16 -1 -8.40265e-14,
+                          -3.46945e-16 -1 -8.40265e-14,
+                          -3.46945e-16 -1 -8.40265e-14,
+                          -3.46945e-16 -1 -8.40265e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          -1 4.57967e-16 5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          1 -4.57967e-16 -5.84532e-14,
+                          -5.87863e-14 8.38357e-14 -1,
+                          -5.87863e-14 8.38357e-14 -1,
+                          -5.87863e-14 8.38357e-14 -1,
+                          3.46945e-16 1 8.37816e-14,
+                          3.46945e-16 1 8.37816e-14,
+                          -2.90927e-14 0.866025 -0.5,
+                          2.96936e-14 0.866025 0.5,
+                          2.96936e-14 0.866025 0.5,
+                          3.46945e-16 1 8.40265e-14,
+                          2.96936e-14 0.866025 0.5,
+                          3.46945e-16 1 8.40265e-14,
+                          3.46945e-16 1 8.40265e-14,
+                          -2.90927e-14 0.866025 -0.5,
+                          -2.90927e-14 0.866025 -0.5,
+                          -5.0737e-14 0.5 -0.866025,
+                          -2.90927e-14 0.866025 -0.5,
+                          3.46945e-16 1 8.37816e-14,
+                          -2.90927e-14 0.866025 -0.5,
+                          -5.0737e-14 0.5 -0.866025,
+                          -5.0737e-14 0.5 -0.866025,
+                          -5.87863e-14 8.18757e-14 -1,
+                          -2.90927e-14 0.866025 -0.5,
+                          -5.0737e-14 0.5 -0.866025,
+                          -5.0737e-14 0.5 -0.866025,
+                          -5.87863e-14 8.18757e-14 -1,
+                          -5.87863e-14 8.18757e-14 -1,
+                          -5.10839e-14 -0.5 -0.866025,
+                          -5.0737e-14 0.5 -0.866025,
+                          -5.87863e-14 8.18757e-14 -1,
+                          -5.87863e-14 8.18757e-14 -1,
+                          -5.10839e-14 -0.5 -0.866025,
+                          -5.10839e-14 -0.5 -0.866025,
+                          -2.96936e-14 -0.866025 -0.5,
+                          -5.87863e-14 8.18757e-14 -1,
+                          -5.10839e-14 -0.5 -0.866025,
+                          -5.10839e-14 -0.5 -0.866025,
+                          -2.96936e-14 -0.866025 -0.5,
+                          -2.96936e-14 -0.866025 -0.5,
+                          -3.46945e-16 -1 -8.39041e-14,
+                          -5.10839e-14 -0.5 -0.866025,
+                          -2.96936e-14 -0.866025 -0.5,
+                          -2.96936e-14 -0.866025 -0.5,
+                          -3.46945e-16 -1 -8.39041e-14,
+                          -3.46945e-16 -1 -8.39041e-14,
+                          2.90927e-14 -0.866025 0.5,
+                          -2.96936e-14 -0.866025 -0.5,
+                          -3.46945e-16 -1 -8.39041e-14,
+                          -3.46945e-16 -1 -8.39041e-14,
+                          2.90927e-14 -0.866025 0.5,
+                          2.90927e-14 -0.866025 0.5,
+                          5.0737e-14 -0.5 0.866025,
+                          -3.46945e-16 -1 -8.39041e-14,
+                          2.90927e-14 -0.866025 0.5,
+                          2.90927e-14 -0.866025 0.5,
+                          5.0737e-14 -0.5 0.866025,
+                          5.0737e-14 -0.5 0.866025,
+                          5.87863e-14 -8.19981e-14 1,
+                          2.90927e-14 -0.866025 0.5,
+                          5.0737e-14 -0.5 0.866025,
+                          5.0737e-14 -0.5 0.866025,
+                          5.87863e-14 -8.22202e-14 1,
+                          5.87863e-14 -8.19981e-14 1,
+                          5.10839e-14 0.5 0.866025,
+                          5.0737e-14 -0.5 0.866025,
+                          5.87863e-14 -8.19981e-14 1,
+                          5.87863e-14 -8.22202e-14 1,
+                          5.10839e-14 0.5 0.866025,
+                          5.10839e-14 0.5 0.866025,
+                          2.96936e-14 0.866025 0.5,
+                          5.87863e-14 -8.22202e-14 1,
+                          5.10839e-14 0.5 0.866025,
+                          5.10839e-14 0.5 0.866025,
+                          5.10839e-14 0.5 0.866025,
+                          2.96936e-14 0.866025 0.5,
+                          2.96936e-14 0.866025 0.5 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -5 -15.3 31.5,
+                          -5 -46.3 27,
+                          -5 -46.3 31.5,
+                          -2.3 -46.3 31.5,
+                          -5 -46.3 31.5,
+                          -5 -46.3 27,
+                          5 -15.3 31.5,
+                          -5 -15.3 31.5,
+                          -5 -46.3 31.5,
+                          -2.3 -46.3 31.5,
+                          5 -15.3 31.5,
+                          -5 -46.3 31.5,
+                          -5 -15.3 31.5,
+                          -5 -15.3 27,
+                          -5 -46.3 27,
+                          -2.3 -46.3 27,
+                          -5 -46.3 27,
+                          -5 -15.3 27,
+                          -2.3 -46.3 27,
+                          -2.3 -46.3 31.5,
+                          -5 -46.3 27,
+                          -2 -12.3 27,
+                          -5 -15.3 27,
+                          -5 -15.3 31.5,
+                          2.3 -46.3 27,
+                          -2.3 -46.3 27,
+                          -5 -15.3 27,
+                          5 -46.3 27,
+                          2.3 -46.3 27,
+                          -5 -15.3 27,
+                          5 -15.3 27,
+                          5 -46.3 27,
+                          -5 -15.3 27,
+                          -2 -12.3 27,
+                          5 -15.3 27,
+                          -5 -15.3 27,
+                          2 -12.3 31.5,
+                          -2 -12.3 31.5,
+                          -5 -15.3 31.5,
+                          -2 -12.3 27,
+                          -5 -15.3 31.5,
+                          -2 -12.3 31.5,
+                          5 -15.3 31.5,
+                          2 -12.3 31.5,
+                          -5 -15.3 31.5,
+                          2.3 -50.95 27,
+                          -2.3 -50.95 31.5,
+                          -2.3 -50.95 27,
+                          -2.3 -49.7825 29.875,
+                          -2.3 -50.95 27,
+                          -2.3 -50.95 31.5,
+                          -2.3 -46.3 27,
+                          2.3 -50.95 27,
+                          -2.3 -50.95 27,
+                          -2.3 -48.075 28.1675,
+                          -2.3 -46.3 27,
+                          -2.3 -50.95 27,
+                          -2.3 -49.7825 29.875,
+                          -2.3 -49.95 29.25,
+                          -2.3 -50.95 27,
+                          -2.3 -49.7825 28.625,
+                          -2.3 -50.95 27,
+                          -2.3 -49.95 29.25,
+                          -2.3 -48.7 28,
+                          -2.3 -48.075 28.1675,
+                          -2.3 -50.95 27,
+                          -2.3 -49.325 28.1675,
+                          -2.3 -48.7 28,
+                          -2.3 -50.95 27,
+                          -2.3 -49.7825 28.625,
+                          -2.3 -49.325 28.1675,
+                          -2.3 -50.95 27,
+                          2.3 -50.95 27,
+                          2.3 -50.95 31.5,
+                          -2.3 -50.95 31.5,
+                          2.3 -46.3 31.5,
+                          -2.3 -50.95 31.5,
+                          2.3 -50.95 31.5,
+                          -2.3 -46.3 31.5,
+                          -2.3 -50.95 31.5,
+                          2.3 -46.3 31.5,
+                          -2.3 -49.325 30.3325,
+                          -2.3 -50.95 31.5,
+                          -2.3 -46.3 31.5,
+                          -2.3 -49.325 30.3325,
+                          -2.3 -49.7825 29.875,
+                          -2.3 -50.95 31.5,
+                          2.3 -49.7825 28.625,
+                          2.3 -50.95 31.5,
+                          2.3 -50.95 27,
+                          2.3 -48.075 30.3325,
+                          2.3 -46.3 31.5,
+                          2.3 -50.95 31.5,
+                          2.3 -49.7825 28.625,
+                          2.3 -49.95 29.25,
+                          2.3 -50.95 31.5,
+                          2.3 -49.7825 29.875,
+                          2.3 -50.95 31.5,
+                          2.3 -49.95 29.25,
+                          2.3 -48.7 30.5,
+                          2.3 -48.075 30.3325,
+                          2.3 -50.95 31.5,
+                          2.3 -49.325 30.3325,
+                          2.3 -48.7 30.5,
+                          2.3 -50.95 31.5,
+                          2.3 -49.7825 29.875,
+                          2.3 -49.325 30.3325,
+                          2.3 -50.95 31.5,
+                          2.3 -46.3 27,
+                          2.3 -50.95 27,
+                          -2.3 -46.3 27,
+                          2.3 -49.325 28.1675,
+                          2.3 -50.95 27,
+                          2.3 -46.3 27,
+                          2.3 -49.325 28.1675,
+                          2.3 -49.7825 28.625,
+                          2.3 -50.95 27,
+                          2 -12.3 27,
+                          -2 -12.3 31.5,
+                          2 -12.3 31.5,
+                          -2 -12.3 27,
+                          -2 -12.3 31.5,
+                          2 -12.3 27,
+                          5 -15.3 27,
+                          2 -12.3 31.5,
+                          5 -15.3 31.5,
+                          2 -12.3 27,
+                          2 -12.3 31.5,
+                          5 -15.3 27,
+                          2.3 -46.3 31.5,
+                          5 -46.3 31.5,
+                          5 -15.3 31.5,
+                          5 -15.3 27,
+                          5 -15.3 31.5,
+                          5 -46.3 31.5,
+                          -2.3 -46.3 31.5,
+                          2.3 -46.3 31.5,
+                          5 -15.3 31.5,
+                          2.3 -46.3 27,
+                          5 -46.3 31.5,
+                          2.3 -46.3 31.5,
+                          5 -46.3 27,
+                          5 -46.3 31.5,
+                          2.3 -46.3 27,
+                          5 -15.3 27,
+                          5 -46.3 31.5,
+                          5 -46.3 27,
+                          2.3 -47.6175 29.875,
+                          2.3 -46.3 27,
+                          2.3 -46.3 31.5,
+                          2.3 -48.075 30.3325,
+                          2.3 -47.6175 29.875,
+                          2.3 -46.3 31.5,
+                          -2.3 -47.6175 28.625,
+                          -2.3 -46.3 31.5,
+                          -2.3 -46.3 27,
+                          -2.3 -48.7 30.5,
+                          -2.3 -49.325 30.3325,
+                          -2.3 -46.3 31.5,
+                          -2.3 -48.075 30.3325,
+                          -2.3 -48.7 30.5,
+                          -2.3 -46.3 31.5,
+                          -2.3 -47.6175 29.875,
+                          -2.3 -48.075 30.3325,
+                          -2.3 -46.3 31.5,
+                          -2.3 -47.45 29.25,
+                          -2.3 -47.6175 29.875,
+                          -2.3 -46.3 31.5,
+                          -2.3 -47.6175 28.625,
+                          -2.3 -47.45 29.25,
+                          -2.3 -46.3 31.5,
+                          -2.3 -48.075 28.1675,
+                          -2.3 -47.6175 28.625,
+                          -2.3 -46.3 27,
+                          2.3 -48.7 28,
+                          2.3 -49.325 28.1675,
+                          2.3 -46.3 27,
+                          2.3 -48.075 28.1675,
+                          2.3 -48.7 28,
+                          2.3 -46.3 27,
+                          2.3 -47.6175 28.625,
+                          2.3 -48.075 28.1675,
+                          2.3 -46.3 27,
+                          2.3 -47.45 29.25,
+                          2.3 -47.6175 28.625,
+                          2.3 -46.3 27,
+                          2.3 -47.6175 29.875,
+                          2.3 -47.45 29.25,
+                          2.3 -46.3 27,
+                          -2 -12.3 27,
+                          2 -12.3 27,
+                          5 -15.3 27,
+                          2.3 -49.95 29.25,
+                          -2.3 -49.95 29.25,
+                          -2.3 -49.7825 29.875,
+                          2.3 -49.7825 28.625,
+                          -2.3 -49.7825 28.625,
+                          -2.3 -49.95 29.25,
+                          2.3 -49.7825 28.625,
+                          -2.3 -49.95 29.25,
+                          2.3 -49.95 29.25,
+                          2.3 -49.7825 29.875,
+                          -2.3 -49.7825 29.875,
+                          -2.3 -49.325 30.3325,
+                          2.3 -49.7825 29.875,
+                          2.3 -49.95 29.25,
+                          -2.3 -49.7825 29.875,
+                          2.3 -49.325 30.3325,
+                          -2.3 -49.325 30.3325,
+                          -2.3 -48.7 30.5,
+                          2.3 -49.7825 29.875,
+                          -2.3 -49.325 30.3325,
+                          2.3 -49.325 30.3325,
+                          2.3 -48.7 30.5,
+                          -2.3 -48.7 30.5,
+                          -2.3 -48.075 30.3325,
+                          2.3 -49.325 30.3325,
+                          -2.3 -48.7 30.5,
+                          2.3 -48.7 30.5,
+                          2.3 -48.075 30.3325,
+                          -2.3 -48.075 30.3325,
+                          -2.3 -47.6175 29.875,
+                          2.3 -48.7 30.5,
+                          -2.3 -48.075 30.3325,
+                          2.3 -48.075 30.3325,
+                          2.3 -47.6175 29.875,
+                          -2.3 -47.6175 29.875,
+                          -2.3 -47.45 29.25,
+                          2.3 -48.075 30.3325,
+                          -2.3 -47.6175 29.875,
+                          2.3 -47.6175 29.875,
+                          2.3 -47.45 29.25,
+                          -2.3 -47.45 29.25,
+                          -2.3 -47.6175 28.625,
+                          2.3 -47.6175 29.875,
+                          -2.3 -47.45 29.25,
+                          2.3 -47.45 29.25,
+                          2.3 -47.6175 28.625,
+                          -2.3 -47.6175 28.625,
+                          -2.3 -48.075 28.1675,
+                          2.3 -47.45 29.25,
+                          -2.3 -47.6175 28.625,
+                          2.3 -47.6175 28.625,
+                          2.3 -48.075 28.1675,
+                          -2.3 -48.075 28.1675,
+                          -2.3 -48.7 28,
+                          2.3 -47.6175 28.625,
+                          -2.3 -48.075 28.1675,
+                          2.3 -48.075 28.1675,
+                          2.3 -48.7 28,
+                          -2.3 -48.7 28,
+                          -2.3 -49.325 28.1675,
+                          2.3 -48.075 28.1675,
+                          -2.3 -48.7 28,
+                          2.3 -48.7 28,
+                          2.3 -49.325 28.1675,
+                          -2.3 -49.325 28.1675,
+                          -2.3 -49.7825 28.625,
+                          2.3 -48.7 28,
+                          -2.3 -49.325 28.1675,
+                          2.3 -49.325 28.1675,
+                          2.3 -49.325 28.1675,
+                          -2.3 -49.7825 28.625,
+                          2.3 -49.7825 28.625 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          2.03914e-16 1 8.37918e-14,
+                          2.03914e-16 1 8.37918e-14,
+                          2.03914e-16 1 8.37918e-14,
+                          5.76973e-14 -8.40243e-14 1,
+                          5.76973e-14 -8.40243e-14 1,
+                          5.76973e-14 -8.40243e-14 1,
+                          5.76973e-14 -8.40243e-14 1,
+                          5.76973e-14 -8.40243e-14 1,
+                          5.76973e-14 -8.40243e-14 1,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          -5.76973e-14 8.40243e-14 -1,
+                          -5.76973e-14 8.40243e-14 -1,
+                          -5.76973e-14 8.40243e-14 -1,
+                          2.03914e-16 1 8.37918e-14,
+                          2.03914e-16 1 8.37918e-14,
+                          2.03914e-16 1 8.37918e-14,
+                          0.707107 -0.707107 -1.00495e-13,
+                          0.707107 -0.707107 -1.00495e-13,
+                          0.707107 -0.707107 -1.00495e-13,
+                          -5.76973e-14 8.40243e-14 -1,
+                          -5.76973e-14 8.40243e-14 -1,
+                          -5.76973e-14 8.40243e-14 -1,
+                          -5.76973e-14 8.40243e-14 -1,
+                          -5.76973e-14 8.40243e-14 -1,
+                          -5.76973e-14 8.40243e-14 -1,
+                          -5.76973e-14 8.40243e-14 -1,
+                          -5.76973e-14 8.40243e-14 -1,
+                          -5.76973e-14 8.40243e-14 -1,
+                          -5.76973e-14 8.40243e-14 -1,
+                          -5.76973e-14 8.40243e-14 -1,
+                          -5.76973e-14 8.40243e-14 -1,
+                          5.76973e-14 -8.40243e-14 1,
+                          5.76973e-14 -8.40243e-14 1,
+                          5.76973e-14 -8.40243e-14 1,
+                          0.707107 -0.707107 -1.00495e-13,
+                          0.707107 -0.707107 -1.00495e-13,
+                          0.707107 -0.707107 -1.00495e-13,
+                          5.76973e-14 -8.40243e-14 1,
+                          5.76973e-14 -8.40243e-14 1,
+                          5.76973e-14 -8.40243e-14 1,
+                          2.03914e-16 1 8.37918e-14,
+                          2.03914e-16 1 8.37918e-14,
+                          2.03914e-16 1 8.37918e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          -5.76973e-14 8.40243e-14 -1,
+                          -5.76973e-14 8.40243e-14 -1,
+                          -5.76973e-14 8.40243e-14 -1,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          2.03914e-16 1 8.37918e-14,
+                          2.03914e-16 1 8.37918e-14,
+                          2.03914e-16 1 8.37918e-14,
+                          5.76973e-14 -8.40243e-14 1,
+                          5.76973e-14 -8.40243e-14 1,
+                          5.76973e-14 -8.40243e-14 1,
+                          5.76973e-14 -8.40243e-14 1,
+                          5.76973e-14 -8.40243e-14 1,
+                          5.76973e-14 -8.40243e-14 1,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -5.76973e-14 8.40243e-14 -1,
+                          -5.76973e-14 8.40243e-14 -1,
+                          -5.76973e-14 8.40243e-14 -1,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -2.03914e-16 -1 -8.37918e-14,
+                          -2.03914e-16 -1 -8.37918e-14,
+                          -2.03914e-16 -1 -8.37918e-14,
+                          -2.03914e-16 -1 -8.37918e-14,
+                          -2.03914e-16 -1 -8.37918e-14,
+                          -2.03914e-16 -1 -8.37918e-14,
+                          -0.707107 -0.707107 -1.80048e-14,
+                          -0.707107 -0.707107 -1.80048e-14,
+                          -0.707107 -0.707107 -1.80048e-14,
+                          -0.707107 -0.707107 -1.80048e-14,
+                          -0.707107 -0.707107 -1.80048e-14,
+                          -0.707107 -0.707107 -1.80048e-14,
+                          5.76973e-14 -8.40243e-14 1,
+                          5.76973e-14 -8.40243e-14 1,
+                          5.76973e-14 -8.40243e-14 1,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          5.76973e-14 -8.40243e-14 1,
+                          5.76973e-14 -8.40243e-14 1,
+                          5.76973e-14 -8.40243e-14 1,
+                          2.03914e-16 1 8.37918e-14,
+                          2.03914e-16 1 8.37918e-14,
+                          2.03914e-16 1 8.37918e-14,
+                          2.03914e-16 1 8.37918e-14,
+                          2.03914e-16 1 8.37918e-14,
+                          2.03914e-16 1 8.37918e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          1 -4.56232e-16 -5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -1 4.56232e-16 5.83292e-14,
+                          -5.76973e-14 8.40243e-14 -1,
+                          -5.76973e-14 8.40243e-14 -1,
+                          -5.76973e-14 8.40243e-14 -1,
+                          -2.03914e-16 -1 -8.40367e-14,
+                          -2.03914e-16 -1 -8.40367e-14,
+                          -2.90253e-14 -0.866025 -0.5,
+                          2.86721e-14 -0.866025 0.5,
+                          2.86721e-14 -0.866025 0.5,
+                          -2.03914e-16 -1 -8.37918e-14,
+                          2.86721e-14 -0.866025 0.5,
+                          -2.03914e-16 -1 -8.37918e-14,
+                          -2.03914e-16 -1 -8.37918e-14,
+                          -2.90253e-14 -0.866025 -0.5,
+                          -2.90253e-14 -0.866025 -0.5,
+                          -5.00693e-14 -0.5 -0.866025,
+                          -2.90253e-14 -0.866025 -0.5,
+                          -2.03914e-16 -1 -8.40367e-14,
+                          -2.90253e-14 -0.866025 -0.5,
+                          -5.00693e-14 -0.5 -0.866025,
+                          -5.00693e-14 -0.5 -0.866025,
+                          -5.76973e-14 8.59844e-14 -1,
+                          -2.90253e-14 -0.866025 -0.5,
+                          -5.00693e-14 -0.5 -0.866025,
+                          -5.00693e-14 -0.5 -0.866025,
+                          -5.76973e-14 8.59844e-14 -1,
+                          -5.76973e-14 8.59844e-14 -1,
+                          -4.98654e-14 0.5 -0.866025,
+                          -5.00693e-14 -0.5 -0.866025,
+                          -5.76973e-14 8.59844e-14 -1,
+                          -5.76973e-14 8.59844e-14 -1,
+                          -4.98654e-14 0.5 -0.866025,
+                          -4.98654e-14 0.5 -0.866025,
+                          -2.86721e-14 0.866025 -0.5,
+                          -5.76973e-14 8.59844e-14 -1,
+                          -4.98654e-14 0.5 -0.866025,
+                          -4.98654e-14 0.5 -0.866025,
+                          -2.86721e-14 0.866025 -0.5,
+                          -2.86721e-14 0.866025 -0.5,
+                          2.03914e-16 1 8.39143e-14,
+                          -4.98654e-14 0.5 -0.866025,
+                          -2.86721e-14 0.866025 -0.5,
+                          -2.86721e-14 0.866025 -0.5,
+                          2.03914e-16 1 8.39143e-14,
+                          2.03914e-16 1 8.39143e-14,
+                          2.90253e-14 0.866025 0.5,
+                          -2.86721e-14 0.866025 -0.5,
+                          2.03914e-16 1 8.39143e-14,
+                          2.03914e-16 1 8.39143e-14,
+                          2.90253e-14 0.866025 0.5,
+                          2.90253e-14 0.866025 0.5,
+                          5.00693e-14 0.5 0.866025,
+                          2.03914e-16 1 8.39143e-14,
+                          2.90253e-14 0.866025 0.5,
+                          2.90253e-14 0.866025 0.5,
+                          5.00693e-14 0.5 0.866025,
+                          5.00693e-14 0.5 0.866025,
+                          5.76973e-14 -8.58619e-14 1,
+                          2.90253e-14 0.866025 0.5,
+                          5.00693e-14 0.5 0.866025,
+                          5.00693e-14 0.5 0.866025,
+                          5.76973e-14 -8.56398e-14 1,
+                          5.76973e-14 -8.58619e-14 1,
+                          4.98654e-14 -0.5 0.866025,
+                          5.00693e-14 0.5 0.866025,
+                          5.76973e-14 -8.58619e-14 1,
+                          5.76973e-14 -8.56398e-14 1,
+                          4.98654e-14 -0.5 0.866025,
+                          4.98654e-14 -0.5 0.866025,
+                          2.86721e-14 -0.866025 0.5,
+                          5.76973e-14 -8.56398e-14 1,
+                          4.98654e-14 -0.5 0.866025,
+                          4.98654e-14 -0.5 0.866025,
+                          4.98654e-14 -0.5 0.866025,
+                          2.86721e-14 -0.866025 0.5,
+                          2.86721e-14 -0.866025 0.5 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 18.5 -42.1 31.5,
+                          18.5 -11.1 27,
+                          18.5 -11.1 31.5,
+                          15.8 -11.1 31.5,
+                          18.5 -11.1 31.5,
+                          18.5 -11.1 27,
+                          8.5 -42.1 31.5,
+                          18.5 -42.1 31.5,
+                          18.5 -11.1 31.5,
+                          15.8 -11.1 31.5,
+                          8.5 -42.1 31.5,
+                          18.5 -11.1 31.5,
+                          18.5 -42.1 31.5,
+                          18.5 -42.1 27,
+                          18.5 -11.1 27,
+                          15.8 -11.1 27,
+                          18.5 -11.1 27,
+                          18.5 -42.1 27,
+                          15.8 -11.1 27,
+                          15.8 -11.1 31.5,
+                          18.5 -11.1 27,
+                          15.5 -45.1 27,
+                          18.5 -42.1 27,
+                          18.5 -42.1 31.5,
+                          11.2 -11.1 27,
+                          15.8 -11.1 27,
+                          18.5 -42.1 27,
+                          8.5 -11.1 27,
+                          11.2 -11.1 27,
+                          18.5 -42.1 27,
+                          8.5 -42.1 27,
+                          8.5 -11.1 27,
+                          18.5 -42.1 27,
+                          15.5 -45.1 27,
+                          8.5 -42.1 27,
+                          18.5 -42.1 27,
+                          11.5 -45.1 31.5,
+                          15.5 -45.1 31.5,
+                          18.5 -42.1 31.5,
+                          15.5 -45.1 27,
+                          18.5 -42.1 31.5,
+                          15.5 -45.1 31.5,
+                          8.5 -42.1 31.5,
+                          11.5 -45.1 31.5,
+                          18.5 -42.1 31.5,
+                          11.2 -6.45 27,
+                          15.8 -6.45 31.5,
+                          15.8 -6.45 27,
+                          15.8 -7.61747 29.875,
+                          15.8 -6.45 27,
+                          15.8 -6.45 31.5,
+                          15.8 -11.1 27,
+                          11.2 -6.45 27,
+                          15.8 -6.45 27,
+                          15.8 -9.325 28.1675,
+                          15.8 -11.1 27,
+                          15.8 -6.45 27,
+                          15.8 -7.61747 29.875,
+                          15.8 -7.45 29.25,
+                          15.8 -6.45 27,
+                          15.8 -7.61747 28.625,
+                          15.8 -6.45 27,
+                          15.8 -7.45 29.25,
+                          15.8 -8.7 28,
+                          15.8 -9.325 28.1675,
+                          15.8 -6.45 27,
+                          15.8 -8.075 28.1675,
+                          15.8 -8.7 28,
+                          15.8 -6.45 27,
+                          15.8 -7.61747 28.625,
+                          15.8 -8.075 28.1675,
+                          15.8 -6.45 27,
+                          11.2 -6.45 27,
+                          11.2 -6.45 31.5,
+                          15.8 -6.45 31.5,
+                          11.2 -11.1 31.5,
+                          15.8 -6.45 31.5,
+                          11.2 -6.45 31.5,
+                          15.8 -11.1 31.5,
+                          15.8 -6.45 31.5,
+                          11.2 -11.1 31.5,
+                          15.8 -8.075 30.3325,
+                          15.8 -6.45 31.5,
+                          15.8 -11.1 31.5,
+                          15.8 -8.075 30.3325,
+                          15.8 -7.61747 29.875,
+                          15.8 -6.45 31.5,
+                          11.2 -7.61747 28.625,
+                          11.2 -6.45 31.5,
+                          11.2 -6.45 27,
+                          11.2 -9.325 30.3325,
+                          11.2 -11.1 31.5,
+                          11.2 -6.45 31.5,
+                          11.2 -7.61747 28.625,
+                          11.2 -7.45 29.25,
+                          11.2 -6.45 31.5,
+                          11.2 -7.61747 29.875,
+                          11.2 -6.45 31.5,
+                          11.2 -7.45 29.25,
+                          11.2 -8.7 30.5,
+                          11.2 -9.325 30.3325,
+                          11.2 -6.45 31.5,
+                          11.2 -8.075 30.3325,
+                          11.2 -8.7 30.5,
+                          11.2 -6.45 31.5,
+                          11.2 -7.61747 29.875,
+                          11.2 -8.075 30.3325,
+                          11.2 -6.45 31.5,
+                          11.2 -11.1 27,
+                          11.2 -6.45 27,
+                          15.8 -11.1 27,
+                          11.2 -8.075 28.1675,
+                          11.2 -6.45 27,
+                          11.2 -11.1 27,
+                          11.2 -8.075 28.1675,
+                          11.2 -7.61747 28.625,
+                          11.2 -6.45 27,
+                          11.5 -45.1 27,
+                          15.5 -45.1 31.5,
+                          11.5 -45.1 31.5,
+                          15.5 -45.1 27,
+                          15.5 -45.1 31.5,
+                          11.5 -45.1 27,
+                          8.5 -42.1 27,
+                          11.5 -45.1 31.5,
+                          8.5 -42.1 31.5,
+                          11.5 -45.1 27,
+                          11.5 -45.1 31.5,
+                          8.5 -42.1 27,
+                          11.2 -11.1 31.5,
+                          8.5 -11.1 31.5,
+                          8.5 -42.1 31.5,
+                          8.5 -42.1 27,
+                          8.5 -42.1 31.5,
+                          8.5 -11.1 31.5,
+                          15.8 -11.1 31.5,
+                          11.2 -11.1 31.5,
+                          8.5 -42.1 31.5,
+                          11.2 -11.1 27,
+                          8.5 -11.1 31.5,
+                          11.2 -11.1 31.5,
+                          8.5 -11.1 27,
+                          8.5 -11.1 31.5,
+                          11.2 -11.1 27,
+                          8.5 -42.1 27,
+                          8.5 -11.1 31.5,
+                          8.5 -11.1 27,
+                          11.2 -9.78253 29.875,
+                          11.2 -11.1 27,
+                          11.2 -11.1 31.5,
+                          11.2 -9.325 30.3325,
+                          11.2 -9.78253 29.875,
+                          11.2 -11.1 31.5,
+                          15.8 -9.78253 28.625,
+                          15.8 -11.1 31.5,
+                          15.8 -11.1 27,
+                          15.8 -8.7 30.5,
+                          15.8 -8.075 30.3325,
+                          15.8 -11.1 31.5,
+                          15.8 -9.325 30.3325,
+                          15.8 -8.7 30.5,
+                          15.8 -11.1 31.5,
+                          15.8 -9.78253 29.875,
+                          15.8 -9.325 30.3325,
+                          15.8 -11.1 31.5,
+                          15.8 -9.95 29.25,
+                          15.8 -9.78253 29.875,
+                          15.8 -11.1 31.5,
+                          15.8 -9.78253 28.625,
+                          15.8 -9.95 29.25,
+                          15.8 -11.1 31.5,
+                          15.8 -9.325 28.1675,
+                          15.8 -9.78253 28.625,
+                          15.8 -11.1 27,
+                          11.2 -8.7 28,
+                          11.2 -8.075 28.1675,
+                          11.2 -11.1 27,
+                          11.2 -9.325 28.1675,
+                          11.2 -8.7 28,
+                          11.2 -11.1 27,
+                          11.2 -9.78253 28.625,
+                          11.2 -9.325 28.1675,
+                          11.2 -11.1 27,
+                          11.2 -9.95 29.25,
+                          11.2 -9.78253 28.625,
+                          11.2 -11.1 27,
+                          11.2 -9.78253 29.875,
+                          11.2 -9.95 29.25,
+                          11.2 -11.1 27,
+                          15.5 -45.1 27,
+                          11.5 -45.1 27,
+                          8.5 -42.1 27,
+                          11.2 -7.45 29.25,
+                          15.8 -7.45 29.25,
+                          15.8 -7.61747 29.875,
+                          11.2 -7.61747 28.625,
+                          15.8 -7.61747 28.625,
+                          15.8 -7.45 29.25,
+                          11.2 -7.61747 28.625,
+                          15.8 -7.45 29.25,
+                          11.2 -7.45 29.25,
+                          11.2 -7.61747 29.875,
+                          15.8 -7.61747 29.875,
+                          15.8 -8.075 30.3325,
+                          11.2 -7.61747 29.875,
+                          11.2 -7.45 29.25,
+                          15.8 -7.61747 29.875,
+                          11.2 -8.075 30.3325,
+                          15.8 -8.075 30.3325,
+                          15.8 -8.7 30.5,
+                          11.2 -7.61747 29.875,
+                          15.8 -8.075 30.3325,
+                          11.2 -8.075 30.3325,
+                          11.2 -8.7 30.5,
+                          15.8 -8.7 30.5,
+                          15.8 -9.325 30.3325,
+                          11.2 -8.075 30.3325,
+                          15.8 -8.7 30.5,
+                          11.2 -8.7 30.5,
+                          11.2 -9.325 30.3325,
+                          15.8 -9.325 30.3325,
+                          15.8 -9.78253 29.875,
+                          11.2 -8.7 30.5,
+                          15.8 -9.325 30.3325,
+                          11.2 -9.325 30.3325,
+                          11.2 -9.78253 29.875,
+                          15.8 -9.78253 29.875,
+                          15.8 -9.95 29.25,
+                          11.2 -9.325 30.3325,
+                          15.8 -9.78253 29.875,
+                          11.2 -9.78253 29.875,
+                          11.2 -9.95 29.25,
+                          15.8 -9.95 29.25,
+                          15.8 -9.78253 28.625,
+                          11.2 -9.78253 29.875,
+                          15.8 -9.95 29.25,
+                          11.2 -9.95 29.25,
+                          11.2 -9.78253 28.625,
+                          15.8 -9.78253 28.625,
+                          15.8 -9.325 28.1675,
+                          11.2 -9.95 29.25,
+                          15.8 -9.78253 28.625,
+                          11.2 -9.78253 28.625,
+                          11.2 -9.325 28.1675,
+                          15.8 -9.325 28.1675,
+                          15.8 -8.7 28,
+                          11.2 -9.78253 28.625,
+                          15.8 -9.325 28.1675,
+                          11.2 -9.325 28.1675,
+                          11.2 -8.7 28,
+                          15.8 -8.7 28,
+                          15.8 -8.075 28.1675,
+                          11.2 -9.325 28.1675,
+                          15.8 -8.7 28,
+                          11.2 -8.7 28,
+                          11.2 -8.075 28.1675,
+                          15.8 -8.075 28.1675,
+                          15.8 -7.61747 28.625,
+                          11.2 -8.7 28,
+                          15.8 -8.075 28.1675,
+                          11.2 -8.075 28.1675,
+                          11.2 -8.075 28.1675,
+                          15.8 -7.61747 28.625,
+                          11.2 -7.61747 28.625 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          2.62111e-16 1 8.38699e-14,
+                          2.62111e-16 1 8.38699e-14,
+                          2.62111e-16 1 8.38699e-14,
+                          5.77316e-14 -8.39306e-14 1,
+                          5.77316e-14 -8.39306e-14 1,
+                          5.77316e-14 -8.39306e-14 1,
+                          5.77316e-14 -8.39306e-14 1,
+                          5.77316e-14 -8.39306e-14 1,
+                          5.77316e-14 -8.39306e-14 1,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          -5.77316e-14 8.39306e-14 -1,
+                          -5.77316e-14 8.39306e-14 -1,
+                          -5.77316e-14 8.39306e-14 -1,
+                          2.62111e-16 1 8.38699e-14,
+                          2.62111e-16 1 8.38699e-14,
+                          2.62111e-16 1 8.38699e-14,
+                          0.707107 -0.707107 -1.00526e-13,
+                          0.707107 -0.707107 -1.00526e-13,
+                          0.707107 -0.707107 -1.00526e-13,
+                          -5.77316e-14 8.39306e-14 -1,
+                          -5.77316e-14 8.39306e-14 -1,
+                          -5.77316e-14 8.39306e-14 -1,
+                          -5.77316e-14 8.39306e-14 -1,
+                          -5.77316e-14 8.39306e-14 -1,
+                          -5.77316e-14 8.39306e-14 -1,
+                          -5.77316e-14 8.39306e-14 -1,
+                          -5.77316e-14 8.39306e-14 -1,
+                          -5.77316e-14 8.39306e-14 -1,
+                          -5.77316e-14 8.39306e-14 -1,
+                          -5.77316e-14 8.39306e-14 -1,
+                          -5.77316e-14 8.39306e-14 -1,
+                          5.77316e-14 -8.39306e-14 1,
+                          5.77316e-14 -8.39306e-14 1,
+                          5.77316e-14 -8.39306e-14 1,
+                          0.707107 -0.707107 -1.00526e-13,
+                          0.707107 -0.707107 -1.00526e-13,
+                          0.707107 -0.707107 -1.00526e-13,
+                          5.77316e-14 -8.39306e-14 1,
+                          5.77316e-14 -8.39306e-14 1,
+                          5.77316e-14 -8.39306e-14 1,
+                          2.62111e-16 1 8.38699e-14,
+                          2.62111e-16 1 8.38699e-14,
+                          2.62111e-16 1 8.38699e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          -5.77316e-14 8.39306e-14 -1,
+                          -5.77316e-14 8.39306e-14 -1,
+                          -5.77316e-14 8.39306e-14 -1,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          2.62111e-16 1 8.38699e-14,
+                          2.62111e-16 1 8.38699e-14,
+                          2.62111e-16 1 8.38699e-14,
+                          5.77316e-14 -8.39306e-14 1,
+                          5.77316e-14 -8.39306e-14 1,
+                          5.77316e-14 -8.39306e-14 1,
+                          5.77316e-14 -8.39306e-14 1,
+                          5.77316e-14 -8.39306e-14 1,
+                          5.77316e-14 -8.39306e-14 1,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -5.77316e-14 8.39306e-14 -1,
+                          -5.77316e-14 8.39306e-14 -1,
+                          -5.77316e-14 8.39306e-14 -1,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -2.62111e-16 -1 -8.38699e-14,
+                          -2.62111e-16 -1 -8.38699e-14,
+                          -2.62111e-16 -1 -8.38699e-14,
+                          -2.62111e-16 -1 -8.38699e-14,
+                          -2.62111e-16 -1 -8.38699e-14,
+                          -2.62111e-16 -1 -8.38699e-14,
+                          -0.707107 -0.707107 -1.80842e-14,
+                          -0.707107 -0.707107 -1.80842e-14,
+                          -0.707107 -0.707107 -1.80842e-14,
+                          -0.707107 -0.707107 -1.80842e-14,
+                          -0.707107 -0.707107 -1.80842e-14,
+                          -0.707107 -0.707107 -1.80842e-14,
+                          5.77316e-14 -8.39306e-14 1,
+                          5.77316e-14 -8.39306e-14 1,
+                          5.77316e-14 -8.39306e-14 1,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          5.77316e-14 -8.39306e-14 1,
+                          5.77316e-14 -8.39306e-14 1,
+                          5.77316e-14 -8.39306e-14 1,
+                          2.62111e-16 1 8.38699e-14,
+                          2.62111e-16 1 8.38699e-14,
+                          2.62111e-16 1 8.38699e-14,
+                          2.62111e-16 1 8.38699e-14,
+                          2.62111e-16 1 8.38699e-14,
+                          2.62111e-16 1 8.38699e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          1 -4.86506e-16 -5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -1 4.86506e-16 5.8295e-14,
+                          -5.77316e-14 8.39306e-14 -1,
+                          -5.77316e-14 8.39306e-14 -1,
+                          -5.77316e-14 8.39306e-14 -1,
+                          -2.62111e-16 -1 -8.41148e-14,
+                          -2.62111e-16 -1 -8.41148e-14,
+                          -2.90928e-14 -0.866025 -0.5,
+                          2.86388e-14 -0.866025 0.5,
+                          2.86388e-14 -0.866025 0.5,
+                          -2.62111e-16 -1 -8.38699e-14,
+                          2.86388e-14 -0.866025 0.5,
+                          -2.62111e-16 -1 -8.38699e-14,
+                          -2.62111e-16 -1 -8.38699e-14,
+                          -2.90928e-14 -0.866025 -0.5,
+                          -2.90928e-14 -0.866025 -0.5,
+                          -5.0128e-14 -0.5 -0.866025,
+                          -2.90928e-14 -0.866025 -0.5,
+                          -2.62111e-16 -1 -8.41148e-14,
+                          -2.90928e-14 -0.866025 -0.5,
+                          -5.0128e-14 -0.5 -0.866025,
+                          -5.0128e-14 -0.5 -0.866025,
+                          -5.77316e-14 8.58907e-14 -1,
+                          -2.90928e-14 -0.866025 -0.5,
+                          -5.0128e-14 -0.5 -0.866025,
+                          -5.0128e-14 -0.5 -0.866025,
+                          -5.77316e-14 8.58907e-14 -1,
+                          -5.77316e-14 8.58907e-14 -1,
+                          -4.98659e-14 0.5 -0.866025,
+                          -5.0128e-14 -0.5 -0.866025,
+                          -5.77316e-14 8.58907e-14 -1,
+                          -5.77316e-14 8.58907e-14 -1,
+                          -4.98659e-14 0.5 -0.866025,
+                          -4.98659e-14 0.5 -0.866025,
+                          -2.86388e-14 0.866025 -0.5,
+                          -5.77316e-14 8.58907e-14 -1,
+                          -4.98659e-14 0.5 -0.866025,
+                          -4.98659e-14 0.5 -0.866025,
+                          -2.86388e-14 0.866025 -0.5,
+                          -2.86388e-14 0.866025 -0.5,
+                          2.62111e-16 1 8.39923e-14,
+                          -4.98659e-14 0.5 -0.866025,
+                          -2.86388e-14 0.866025 -0.5,
+                          -2.86388e-14 0.866025 -0.5,
+                          2.62111e-16 1 8.39923e-14,
+                          2.62111e-16 1 8.39923e-14,
+                          2.90928e-14 0.866025 0.5,
+                          -2.86388e-14 0.866025 -0.5,
+                          2.62111e-16 1 8.39923e-14,
+                          2.62111e-16 1 8.39923e-14,
+                          2.90928e-14 0.866025 0.5,
+                          2.90928e-14 0.866025 0.5,
+                          5.0128e-14 0.5 0.866025,
+                          2.62111e-16 1 8.39923e-14,
+                          2.90928e-14 0.866025 0.5,
+                          2.90928e-14 0.866025 0.5,
+                          5.0128e-14 0.5 0.866025,
+                          5.0128e-14 0.5 0.866025,
+                          5.77316e-14 -8.57682e-14 1,
+                          2.90928e-14 0.866025 0.5,
+                          5.0128e-14 0.5 0.866025,
+                          5.0128e-14 0.5 0.866025,
+                          5.77316e-14 -8.55462e-14 1,
+                          5.77316e-14 -8.57682e-14 1,
+                          4.98659e-14 -0.5 0.866025,
+                          5.0128e-14 0.5 0.866025,
+                          5.77316e-14 -8.57682e-14 1,
+                          5.77316e-14 -8.55462e-14 1,
+                          4.98659e-14 -0.5 0.866025,
+                          4.98659e-14 -0.5 0.866025,
+                          2.86388e-14 -0.866025 0.5,
+                          5.77316e-14 -8.55462e-14 1,
+                          4.98659e-14 -0.5 0.866025,
+                          4.98659e-14 -0.5 0.866025,
+                          4.98659e-14 -0.5 0.866025,
+                          2.86388e-14 -0.866025 0.5,
+                          2.86388e-14 -0.866025 0.5 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -8.5 -42.1 31.5,
+                          -8.5 -11.1 27,
+                          -8.5 -11.1 31.5,
+                          -11.2 -11.1 31.5,
+                          -8.5 -11.1 31.5,
+                          -8.5 -11.1 27,
+                          -18.5 -42.1 31.5,
+                          -8.5 -42.1 31.5,
+                          -8.5 -11.1 31.5,
+                          -11.2 -11.1 31.5,
+                          -18.5 -42.1 31.5,
+                          -8.5 -11.1 31.5,
+                          -8.5 -42.1 31.5,
+                          -8.5 -42.1 27,
+                          -8.5 -11.1 27,
+                          -11.2 -11.1 27,
+                          -8.5 -11.1 27,
+                          -8.5 -42.1 27,
+                          -11.2 -11.1 27,
+                          -11.2 -11.1 31.5,
+                          -8.5 -11.1 27,
+                          -11.5 -45.1 27,
+                          -8.5 -42.1 27,
+                          -8.5 -42.1 31.5,
+                          -15.8 -11.1 27,
+                          -11.2 -11.1 27,
+                          -8.5 -42.1 27,
+                          -18.5 -11.1 27,
+                          -15.8 -11.1 27,
+                          -8.5 -42.1 27,
+                          -18.5 -42.1 27,
+                          -18.5 -11.1 27,
+                          -8.5 -42.1 27,
+                          -11.5 -45.1 27,
+                          -18.5 -42.1 27,
+                          -8.5 -42.1 27,
+                          -15.5 -45.1 31.5,
+                          -11.5 -45.1 31.5,
+                          -8.5 -42.1 31.5,
+                          -11.5 -45.1 27,
+                          -8.5 -42.1 31.5,
+                          -11.5 -45.1 31.5,
+                          -18.5 -42.1 31.5,
+                          -15.5 -45.1 31.5,
+                          -8.5 -42.1 31.5,
+                          -15.8 -6.45 27,
+                          -11.2 -6.45 31.5,
+                          -11.2 -6.45 27,
+                          -11.2 -7.61747 29.875,
+                          -11.2 -6.45 27,
+                          -11.2 -6.45 31.5,
+                          -11.2 -11.1 27,
+                          -15.8 -6.45 27,
+                          -11.2 -6.45 27,
+                          -11.2 -9.325 28.1675,
+                          -11.2 -11.1 27,
+                          -11.2 -6.45 27,
+                          -11.2 -7.61747 29.875,
+                          -11.2 -7.45 29.25,
+                          -11.2 -6.45 27,
+                          -11.2 -7.61747 28.625,
+                          -11.2 -6.45 27,
+                          -11.2 -7.45 29.25,
+                          -11.2 -8.7 28,
+                          -11.2 -9.325 28.1675,
+                          -11.2 -6.45 27,
+                          -11.2 -8.075 28.1675,
+                          -11.2 -8.7 28,
+                          -11.2 -6.45 27,
+                          -11.2 -7.61747 28.625,
+                          -11.2 -8.075 28.1675,
+                          -11.2 -6.45 27,
+                          -15.8 -6.45 27,
+                          -15.8 -6.45 31.5,
+                          -11.2 -6.45 31.5,
+                          -15.8 -11.1 31.5,
+                          -11.2 -6.45 31.5,
+                          -15.8 -6.45 31.5,
+                          -11.2 -11.1 31.5,
+                          -11.2 -6.45 31.5,
+                          -15.8 -11.1 31.5,
+                          -11.2 -8.075 30.3325,
+                          -11.2 -6.45 31.5,
+                          -11.2 -11.1 31.5,
+                          -11.2 -8.075 30.3325,
+                          -11.2 -7.61747 29.875,
+                          -11.2 -6.45 31.5,
+                          -15.8 -7.61747 28.625,
+                          -15.8 -6.45 31.5,
+                          -15.8 -6.45 27,
+                          -15.8 -9.325 30.3325,
+                          -15.8 -11.1 31.5,
+                          -15.8 -6.45 31.5,
+                          -15.8 -7.61747 28.625,
+                          -15.8 -7.45 29.25,
+                          -15.8 -6.45 31.5,
+                          -15.8 -7.61747 29.875,
+                          -15.8 -6.45 31.5,
+                          -15.8 -7.45 29.25,
+                          -15.8 -8.7 30.5,
+                          -15.8 -9.325 30.3325,
+                          -15.8 -6.45 31.5,
+                          -15.8 -8.075 30.3325,
+                          -15.8 -8.7 30.5,
+                          -15.8 -6.45 31.5,
+                          -15.8 -7.61747 29.875,
+                          -15.8 -8.075 30.3325,
+                          -15.8 -6.45 31.5,
+                          -15.8 -11.1 27,
+                          -15.8 -6.45 27,
+                          -11.2 -11.1 27,
+                          -15.8 -8.075 28.1675,
+                          -15.8 -6.45 27,
+                          -15.8 -11.1 27,
+                          -15.8 -8.075 28.1675,
+                          -15.8 -7.61747 28.625,
+                          -15.8 -6.45 27,
+                          -15.5 -45.1 27,
+                          -11.5 -45.1 31.5,
+                          -15.5 -45.1 31.5,
+                          -11.5 -45.1 27,
+                          -11.5 -45.1 31.5,
+                          -15.5 -45.1 27,
+                          -18.5 -42.1 27,
+                          -15.5 -45.1 31.5,
+                          -18.5 -42.1 31.5,
+                          -15.5 -45.1 27,
+                          -15.5 -45.1 31.5,
+                          -18.5 -42.1 27,
+                          -15.8 -11.1 31.5,
+                          -18.5 -11.1 31.5,
+                          -18.5 -42.1 31.5,
+                          -18.5 -42.1 27,
+                          -18.5 -42.1 31.5,
+                          -18.5 -11.1 31.5,
+                          -11.2 -11.1 31.5,
+                          -15.8 -11.1 31.5,
+                          -18.5 -42.1 31.5,
+                          -15.8 -11.1 27,
+                          -18.5 -11.1 31.5,
+                          -15.8 -11.1 31.5,
+                          -18.5 -11.1 27,
+                          -18.5 -11.1 31.5,
+                          -15.8 -11.1 27,
+                          -18.5 -42.1 27,
+                          -18.5 -11.1 31.5,
+                          -18.5 -11.1 27,
+                          -15.8 -9.78253 29.875,
+                          -15.8 -11.1 27,
+                          -15.8 -11.1 31.5,
+                          -15.8 -9.325 30.3325,
+                          -15.8 -9.78253 29.875,
+                          -15.8 -11.1 31.5,
+                          -11.2 -9.78253 28.625,
+                          -11.2 -11.1 31.5,
+                          -11.2 -11.1 27,
+                          -11.2 -8.7 30.5,
+                          -11.2 -8.075 30.3325,
+                          -11.2 -11.1 31.5,
+                          -11.2 -9.325 30.3325,
+                          -11.2 -8.7 30.5,
+                          -11.2 -11.1 31.5,
+                          -11.2 -9.78253 29.875,
+                          -11.2 -9.325 30.3325,
+                          -11.2 -11.1 31.5,
+                          -11.2 -9.95 29.25,
+                          -11.2 -9.78253 29.875,
+                          -11.2 -11.1 31.5,
+                          -11.2 -9.78253 28.625,
+                          -11.2 -9.95 29.25,
+                          -11.2 -11.1 31.5,
+                          -11.2 -9.325 28.1675,
+                          -11.2 -9.78253 28.625,
+                          -11.2 -11.1 27,
+                          -15.8 -8.7 28,
+                          -15.8 -8.075 28.1675,
+                          -15.8 -11.1 27,
+                          -15.8 -9.325 28.1675,
+                          -15.8 -8.7 28,
+                          -15.8 -11.1 27,
+                          -15.8 -9.78253 28.625,
+                          -15.8 -9.325 28.1675,
+                          -15.8 -11.1 27,
+                          -15.8 -9.95 29.25,
+                          -15.8 -9.78253 28.625,
+                          -15.8 -11.1 27,
+                          -15.8 -9.78253 29.875,
+                          -15.8 -9.95 29.25,
+                          -15.8 -11.1 27,
+                          -11.5 -45.1 27,
+                          -15.5 -45.1 27,
+                          -18.5 -42.1 27,
+                          -15.8 -7.45 29.25,
+                          -11.2 -7.45 29.25,
+                          -11.2 -7.61747 29.875,
+                          -15.8 -7.61747 28.625,
+                          -11.2 -7.61747 28.625,
+                          -11.2 -7.45 29.25,
+                          -15.8 -7.61747 28.625,
+                          -11.2 -7.45 29.25,
+                          -15.8 -7.45 29.25,
+                          -15.8 -7.61747 29.875,
+                          -11.2 -7.61747 29.875,
+                          -11.2 -8.075 30.3325,
+                          -15.8 -7.61747 29.875,
+                          -15.8 -7.45 29.25,
+                          -11.2 -7.61747 29.875,
+                          -15.8 -8.075 30.3325,
+                          -11.2 -8.075 30.3325,
+                          -11.2 -8.7 30.5,
+                          -15.8 -7.61747 29.875,
+                          -11.2 -8.075 30.3325,
+                          -15.8 -8.075 30.3325,
+                          -15.8 -8.7 30.5,
+                          -11.2 -8.7 30.5,
+                          -11.2 -9.325 30.3325,
+                          -15.8 -8.075 30.3325,
+                          -11.2 -8.7 30.5,
+                          -15.8 -8.7 30.5,
+                          -15.8 -9.325 30.3325,
+                          -11.2 -9.325 30.3325,
+                          -11.2 -9.78253 29.875,
+                          -15.8 -8.7 30.5,
+                          -11.2 -9.325 30.3325,
+                          -15.8 -9.325 30.3325,
+                          -15.8 -9.78253 29.875,
+                          -11.2 -9.78253 29.875,
+                          -11.2 -9.95 29.25,
+                          -15.8 -9.325 30.3325,
+                          -11.2 -9.78253 29.875,
+                          -15.8 -9.78253 29.875,
+                          -15.8 -9.95 29.25,
+                          -11.2 -9.95 29.25,
+                          -11.2 -9.78253 28.625,
+                          -15.8 -9.78253 29.875,
+                          -11.2 -9.95 29.25,
+                          -15.8 -9.95 29.25,
+                          -15.8 -9.78253 28.625,
+                          -11.2 -9.78253 28.625,
+                          -11.2 -9.325 28.1675,
+                          -15.8 -9.95 29.25,
+                          -11.2 -9.78253 28.625,
+                          -15.8 -9.78253 28.625,
+                          -15.8 -9.325 28.1675,
+                          -11.2 -9.325 28.1675,
+                          -11.2 -8.7 28,
+                          -15.8 -9.78253 28.625,
+                          -11.2 -9.325 28.1675,
+                          -15.8 -9.325 28.1675,
+                          -15.8 -8.7 28,
+                          -11.2 -8.7 28,
+                          -11.2 -8.075 28.1675,
+                          -15.8 -9.325 28.1675,
+                          -11.2 -8.7 28,
+                          -15.8 -8.7 28,
+                          -15.8 -8.075 28.1675,
+                          -11.2 -8.075 28.1675,
+                          -11.2 -7.61747 28.625,
+                          -15.8 -8.7 28,
+                          -11.2 -8.075 28.1675,
+                          -15.8 -8.075 28.1675,
+                          -15.8 -8.075 28.1675,
+                          -11.2 -7.61747 28.625,
+                          -15.8 -7.61747 28.625 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.25 0.25 0.25
+    }
+    Separator {
+        Normal {
+            vector      [ -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          1 -3.6551e-16 -5.86753e-14,
+                          1 -3.6551e-16 -5.86753e-14,
+                          0.951057 0.309017 -2.98202e-14,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          1 -4.26742e-16 -5.86753e-14,
+                          1 -4.26742e-16 -5.86753e-14,
+                          1 -4.26742e-16 -5.86753e-14,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          0.951057 0.309017 -2.98202e-14,
+                          0.951057 0.309017 -2.98202e-14,
+                          0.809017 0.587785 1.9539e-15,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          1 -3.6551e-16 -5.86753e-14,
+                          0.951057 0.309017 -2.98202e-14,
+                          0.951057 0.309017 -2.98202e-14,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          0.809017 0.587785 1.9539e-15,
+                          0.809017 0.587785 1.9539e-15,
+                          0.587785 0.809017 3.35367e-14,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          0.951057 0.309017 -2.98202e-14,
+                          0.809017 0.587785 1.9539e-15,
+                          0.809017 0.587785 1.9539e-15,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          0.587785 0.809017 3.35367e-14,
+                          0.587785 0.809017 3.35367e-14,
+                          0.309017 0.951057 6.18368e-14,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          0.809017 0.587785 1.9539e-15,
+                          0.587785 0.809017 3.35367e-14,
+                          0.587785 0.809017 3.35367e-14,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          0.309017 0.951057 6.18368e-14,
+                          0.309017 0.951057 6.18368e-14,
+                          2.7929e-16 1 8.40838e-14,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          0.587785 0.809017 3.35367e-14,
+                          0.309017 0.951057 6.18368e-14,
+                          0.309017 0.951057 6.18368e-14,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          2.7929e-16 1 8.40838e-14,
+                          2.7929e-16 1 8.40838e-14,
+                          2.7929e-16 1 8.40838e-14,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          0.309017 0.951057 6.18368e-14,
+                          2.7929e-16 1 8.40838e-14,
+                          5.01335e-16 1 8.40838e-14,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          2.7929e-16 1 8.40838e-14,
+                          2.7929e-16 1 8.40838e-14,
+                          -0.309017 0.951057 9.81001e-14,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          2.7929e-16 1 8.40838e-14,
+                          2.7929e-16 1 8.40838e-14,
+                          2.7929e-16 1 8.40838e-14,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -0.309017 0.951057 9.81001e-14,
+                          -0.309017 0.951057 9.81001e-14,
+                          -0.587785 0.809017 1.02514e-13,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          2.7929e-16 1 8.40838e-14,
+                          -0.309017 0.951057 9.81001e-14,
+                          -0.309017 0.951057 9.81001e-14,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -0.587785 0.809017 1.02514e-13,
+                          -0.587785 0.809017 1.02514e-13,
+                          -0.809017 0.587785 9.68925e-14,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -0.309017 0.951057 9.81001e-14,
+                          -0.587785 0.809017 1.02514e-13,
+                          -0.587785 0.809017 1.02514e-13,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -0.809017 0.587785 9.68925e-14,
+                          -0.809017 0.587785 9.68925e-14,
+                          -0.951057 0.309017 8.17868e-14,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -0.587785 0.809017 1.02514e-13,
+                          -0.809017 0.587785 9.68925e-14,
+                          -0.809017 0.587785 9.68925e-14,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -0.951057 0.309017 8.17868e-14,
+                          -0.951057 0.309017 8.17868e-14,
+                          -1 4.87974e-16 5.86753e-14,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -5.87863e-14 8.38444e-14 -1,
+                          -0.809017 0.587785 9.68925e-14,
+                          -0.951057 0.309017 8.17868e-14,
+                          -0.951057 0.309017 8.17868e-14,
+                          -1 4.26742e-16 5.86753e-14,
+                          -1 4.26742e-16 5.86753e-14,
+                          -1 4.26742e-16 5.86753e-14,
+                          -0.951057 0.309017 8.17868e-14,
+                          -1 4.87974e-16 5.86753e-14,
+                          -1 4.87974e-16 5.86753e-14,
+                          -1 4.26742e-16 5.86753e-14,
+                          -1 4.26742e-16 5.86753e-14,
+                          -0.951057 -0.309017 2.98202e-14,
+                          -1 4.26742e-16 5.86753e-14,
+                          -1 4.26742e-16 5.86753e-14,
+                          -1 4.26742e-16 5.86753e-14,
+                          -0.951057 -0.309017 2.98202e-14,
+                          -0.951057 -0.309017 2.98202e-14,
+                          -0.809017 -0.587785 -1.9539e-15,
+                          -1 4.26742e-16 5.86753e-14,
+                          -0.951057 -0.309017 2.98202e-14,
+                          -0.951057 -0.309017 2.98202e-14,
+                          -0.809017 -0.587785 -1.9539e-15,
+                          -0.809017 -0.587785 -1.9539e-15,
+                          -0.587785 -0.809017 -3.35367e-14,
+                          -0.951057 -0.309017 2.98202e-14,
+                          -0.809017 -0.587785 -1.9539e-15,
+                          -0.809017 -0.587785 -1.9539e-15,
+                          -0.587785 -0.809017 -3.35367e-14,
+                          -0.587785 -0.809017 -3.35367e-14,
+                          -0.309017 -0.951057 -6.18368e-14,
+                          -0.809017 -0.587785 -1.9539e-15,
+                          -0.587785 -0.809017 -3.35367e-14,
+                          -0.587785 -0.809017 -3.35367e-14,
+                          -0.309017 -0.951057 -6.18368e-14,
+                          -0.309017 -0.951057 -6.18368e-14,
+                          -3.40523e-16 -1 -8.40838e-14,
+                          -0.587785 -0.809017 -3.35367e-14,
+                          -0.309017 -0.951057 -6.18368e-14,
+                          -0.309017 -0.951057 -6.18368e-14,
+                          -2.7929e-16 -1 -8.40838e-14,
+                          -2.7929e-16 -1 -8.40838e-14,
+                          -2.7929e-16 -1 -8.40838e-14,
+                          -0.309017 -0.951057 -6.18368e-14,
+                          -3.40523e-16 -1 -8.40838e-14,
+                          -3.40523e-16 -1 -8.40838e-14,
+                          -2.7929e-16 -1 -8.40838e-14,
+                          -2.7929e-16 -1 -8.40838e-14,
+                          0.169799 -0.985479 -9.28258e-14,
+                          -2.7929e-16 -1 -8.40838e-14,
+                          -2.7929e-16 -1 -8.40838e-14,
+                          -2.7929e-16 -1 -8.40838e-14,
+                          0.169799 -0.985479 -9.28258e-14,
+                          0.169799 -0.985479 -9.28258e-14,
+                          0.334666 -0.942337 -9.88719e-14,
+                          -2.7929e-16 -1 -8.40838e-14,
+                          0.169799 -0.985479 -9.28258e-14,
+                          0.169799 -0.985479 -9.28258e-14,
+                          0.334666 -0.942337 -9.88719e-14,
+                          0.334666 -0.942337 -9.88719e-14,
+                          0.334666 -0.942337 -9.88719e-14,
+                          0.169799 -0.985479 -9.28258e-14,
+                          0.334666 -0.942337 -9.88719e-14,
+                          0.334666 -0.942337 -9.88719e-14,
+                          0.334666 -0.942337 -9.88719e-14,
+                          0.334666 -0.942337 -9.88719e-14,
+                          0.604101 -0.796908 -1.02453e-13,
+                          0.334666 -0.942337 -9.88719e-14,
+                          0.334666 -0.942337 -9.88719e-14,
+                          0.334666 -0.942337 -9.88719e-14,
+                          0.604101 -0.796908 -1.02453e-13,
+                          0.604101 -0.796908 -1.02453e-13,
+                          0.816904 -0.576773 -9.64294e-14,
+                          0.334666 -0.942337 -9.88719e-14,
+                          0.604101 -0.796908 -1.02453e-13,
+                          0.604101 -0.796908 -1.02453e-13,
+                          0.816904 -0.576773 -9.64294e-14,
+                          0.816904 -0.576773 -9.64294e-14,
+                          0.953128 -0.302569 -8.13661e-14,
+                          0.604101 -0.796908 -1.02453e-13,
+                          0.816904 -0.576773 -9.64294e-14,
+                          0.816904 -0.576773 -9.64294e-14,
+                          0.953128 -0.302569 -8.13661e-14,
+                          0.953128 -0.302569 -8.13661e-14,
+                          1 -2.04697e-16 -5.86753e-14,
+                          0.816904 -0.576773 -9.64294e-14,
+                          0.953128 -0.302569 -8.13661e-14,
+                          0.953128 -0.302569 -8.13661e-14,
+                          1 -4.26742e-16 -5.86753e-14,
+                          1 -4.26742e-16 -5.86753e-14,
+                          1 -4.26742e-16 -5.86753e-14,
+                          0.953128 -0.302569 -8.13661e-14,
+                          1 -2.04697e-16 -5.86753e-14,
+                          1 -2.04697e-16 -5.86753e-14,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1,
+                          5.87863e-14 -8.38444e-14 1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 65.8125 -22.8861 31.5,
+                          65.8042 -19.2639 31.5,
+                          66 -20.5 31.5,
+                          66 -20.5 33.5,
+                          66 -20.5 31.5,
+                          65.8042 -19.2639 31.5,
+                          66 -21.6758 31.5,
+                          65.8125 -22.8861 31.5,
+                          66 -20.5 31.5,
+                          66 -20.5 33.5,
+                          66 -21.6758 31.5,
+                          66 -20.5 31.5,
+                          65.2676 -23.9829 31.5,
+                          65.2361 -18.1489 31.5,
+                          65.8042 -19.2639 31.5,
+                          65.8042 -19.2639 33.5,
+                          65.8042 -19.2639 31.5,
+                          65.2361 -18.1489 31.5,
+                          65.8125 -22.8861 31.5,
+                          65.2676 -23.9829 31.5,
+                          65.8042 -19.2639 31.5,
+                          66 -20.5 33.5,
+                          65.8042 -19.2639 31.5,
+                          65.8042 -19.2639 33.5,
+                          64.4164 -24.8634 31.5,
+                          64.3512 -17.2639 31.5,
+                          65.2361 -18.1489 31.5,
+                          65.2361 -18.1489 33.5,
+                          65.2361 -18.1489 31.5,
+                          64.3512 -17.2639 31.5,
+                          65.2676 -23.9829 31.5,
+                          64.4164 -24.8634 31.5,
+                          65.2361 -18.1489 31.5,
+                          65.8042 -19.2639 33.5,
+                          65.2361 -18.1489 31.5,
+                          65.2361 -18.1489 33.5,
+                          63.3387 -25.4452 31.5,
+                          63.2361 -16.6958 31.5,
+                          64.3512 -17.2639 31.5,
+                          64.3512 -17.2639 33.5,
+                          64.3512 -17.2639 31.5,
+                          63.2361 -16.6958 31.5,
+                          64.4164 -24.8634 31.5,
+                          63.3387 -25.4452 31.5,
+                          64.3512 -17.2639 31.5,
+                          65.2361 -18.1489 33.5,
+                          64.3512 -17.2639 31.5,
+                          64.3512 -17.2639 33.5,
+                          20.4711 -40.6693 31.5,
+                          62 -16.5 31.5,
+                          63.2361 -16.6958 31.5,
+                          63.2361 -16.6958 33.5,
+                          63.2361 -16.6958 31.5,
+                          62 -16.5 31.5,
+                          63.3387 -25.4452 31.5,
+                          20.4711 -40.6693 31.5,
+                          63.2361 -16.6958 31.5,
+                          64.3512 -17.2639 33.5,
+                          63.2361 -16.6958 31.5,
+                          63.2361 -16.6958 33.5,
+                          -19.5 -40.9 31.5,
+                          -19.5 -16.5 31.5,
+                          62 -16.5 31.5,
+                          62 -16.5 33.5,
+                          62 -16.5 31.5,
+                          -19.5 -16.5 31.5,
+                          19.1324 -40.9 31.5,
+                          -19.5 -40.9 31.5,
+                          62 -16.5 31.5,
+                          19.8116 -40.8419 31.5,
+                          19.1324 -40.9 31.5,
+                          62 -16.5 31.5,
+                          20.4711 -40.6693 31.5,
+                          19.8116 -40.8419 31.5,
+                          62 -16.5 31.5,
+                          63.2361 -16.6958 33.5,
+                          62 -16.5 31.5,
+                          62 -16.5 33.5,
+                          -20.7361 -40.7042 31.5,
+                          -20.7361 -16.6958 31.5,
+                          -19.5 -16.5 31.5,
+                          -19.5 -16.5 33.5,
+                          -19.5 -16.5 31.5,
+                          -20.7361 -16.6958 31.5,
+                          -19.5 -40.9 31.5,
+                          -20.7361 -40.7042 31.5,
+                          -19.5 -16.5 31.5,
+                          -19.5 -16.5 33.5,
+                          62 -16.5 33.5,
+                          -19.5 -16.5 31.5,
+                          -21.8511 -40.1361 31.5,
+                          -21.8511 -17.2639 31.5,
+                          -20.7361 -16.6958 31.5,
+                          -20.7361 -16.6958 33.5,
+                          -20.7361 -16.6958 31.5,
+                          -21.8511 -17.2639 31.5,
+                          -20.7361 -40.7042 31.5,
+                          -21.8511 -40.1361 31.5,
+                          -20.7361 -16.6958 31.5,
+                          -19.5 -16.5 33.5,
+                          -20.7361 -16.6958 31.5,
+                          -20.7361 -16.6958 33.5,
+                          -22.7361 -39.2511 31.5,
+                          -22.7361 -18.1489 31.5,
+                          -21.8511 -17.2639 31.5,
+                          -21.8511 -17.2639 33.5,
+                          -21.8511 -17.2639 31.5,
+                          -22.7361 -18.1489 31.5,
+                          -21.8511 -40.1361 31.5,
+                          -22.7361 -39.2511 31.5,
+                          -21.8511 -17.2639 31.5,
+                          -20.7361 -16.6958 33.5,
+                          -21.8511 -17.2639 31.5,
+                          -21.8511 -17.2639 33.5,
+                          -23.3042 -38.1361 31.5,
+                          -23.3042 -19.2639 31.5,
+                          -22.7361 -18.1489 31.5,
+                          -22.7361 -18.1489 33.5,
+                          -22.7361 -18.1489 31.5,
+                          -23.3042 -19.2639 31.5,
+                          -22.7361 -39.2511 31.5,
+                          -23.3042 -38.1361 31.5,
+                          -22.7361 -18.1489 31.5,
+                          -21.8511 -17.2639 33.5,
+                          -22.7361 -18.1489 31.5,
+                          -22.7361 -18.1489 33.5,
+                          -23.5 -36.9 31.5,
+                          -23.5 -20.5 31.5,
+                          -23.3042 -19.2639 31.5,
+                          -23.3042 -19.2639 33.5,
+                          -23.3042 -19.2639 31.5,
+                          -23.5 -20.5 31.5,
+                          -23.3042 -38.1361 31.5,
+                          -23.5 -36.9 31.5,
+                          -23.3042 -19.2639 31.5,
+                          -22.7361 -18.1489 33.5,
+                          -23.3042 -19.2639 31.5,
+                          -23.3042 -19.2639 33.5,
+                          -23.5 -20.5 33.5,
+                          -23.5 -20.5 31.5,
+                          -23.5 -36.9 31.5,
+                          -23.3042 -19.2639 33.5,
+                          -23.5 -20.5 31.5,
+                          -23.5 -20.5 33.5,
+                          -23.5 -36.9 33.5,
+                          -23.5 -36.9 31.5,
+                          -23.3042 -38.1361 31.5,
+                          -23.5 -20.5 33.5,
+                          -23.5 -36.9 31.5,
+                          -23.5 -36.9 33.5,
+                          -23.3042 -38.1361 33.5,
+                          -23.3042 -38.1361 31.5,
+                          -22.7361 -39.2511 31.5,
+                          -23.5 -36.9 33.5,
+                          -23.3042 -38.1361 31.5,
+                          -23.3042 -38.1361 33.5,
+                          -22.7361 -39.2511 33.5,
+                          -22.7361 -39.2511 31.5,
+                          -21.8511 -40.1361 31.5,
+                          -23.3042 -38.1361 33.5,
+                          -22.7361 -39.2511 31.5,
+                          -22.7361 -39.2511 33.5,
+                          -21.8511 -40.1361 33.5,
+                          -21.8511 -40.1361 31.5,
+                          -20.7361 -40.7042 31.5,
+                          -22.7361 -39.2511 33.5,
+                          -21.8511 -40.1361 31.5,
+                          -21.8511 -40.1361 33.5,
+                          -20.7361 -40.7042 33.5,
+                          -20.7361 -40.7042 31.5,
+                          -19.5 -40.9 31.5,
+                          -21.8511 -40.1361 33.5,
+                          -20.7361 -40.7042 31.5,
+                          -20.7361 -40.7042 33.5,
+                          -19.5 -40.9 33.5,
+                          -19.5 -40.9 31.5,
+                          19.1324 -40.9 31.5,
+                          -20.7361 -40.7042 33.5,
+                          -19.5 -40.9 31.5,
+                          -19.5 -40.9 33.5,
+                          19.1324 -40.9 33.5,
+                          19.1324 -40.9 31.5,
+                          19.8116 -40.8419 31.5,
+                          -19.5 -40.9 33.5,
+                          19.1324 -40.9 31.5,
+                          19.1324 -40.9 33.5,
+                          19.8116 -40.8419 33.5,
+                          19.8116 -40.8419 31.5,
+                          20.4711 -40.6693 31.5,
+                          19.1324 -40.9 33.5,
+                          19.8116 -40.8419 31.5,
+                          19.8116 -40.8419 33.5,
+                          20.4711 -40.6693 33.5,
+                          20.4711 -40.6693 31.5,
+                          63.3387 -25.4452 31.5,
+                          19.8116 -40.8419 33.5,
+                          20.4711 -40.6693 31.5,
+                          20.4711 -40.6693 33.5,
+                          63.3387 -25.4452 33.5,
+                          63.3387 -25.4452 31.5,
+                          64.4164 -24.8634 31.5,
+                          20.4711 -40.6693 33.5,
+                          63.3387 -25.4452 31.5,
+                          63.3387 -25.4452 33.5,
+                          64.4164 -24.8634 33.5,
+                          64.4164 -24.8634 31.5,
+                          65.2676 -23.9829 31.5,
+                          63.3387 -25.4452 33.5,
+                          64.4164 -24.8634 31.5,
+                          64.4164 -24.8634 33.5,
+                          65.2676 -23.9829 33.5,
+                          65.2676 -23.9829 31.5,
+                          65.8125 -22.8861 31.5,
+                          64.4164 -24.8634 33.5,
+                          65.2676 -23.9829 31.5,
+                          65.2676 -23.9829 33.5,
+                          65.8125 -22.8861 33.5,
+                          65.8125 -22.8861 31.5,
+                          66 -21.6758 31.5,
+                          65.2676 -23.9829 33.5,
+                          65.8125 -22.8861 31.5,
+                          65.8125 -22.8861 33.5,
+                          66 -21.6758 33.5,
+                          66 -21.6758 31.5,
+                          66 -20.5 33.5,
+                          65.8125 -22.8861 33.5,
+                          66 -21.6758 31.5,
+                          66 -21.6758 33.5,
+                          63.3387 -25.4452 33.5,
+                          63.2361 -16.6958 33.5,
+                          62 -16.5 33.5,
+                          20.4711 -40.6693 33.5,
+                          63.3387 -25.4452 33.5,
+                          62 -16.5 33.5,
+                          -19.5 -16.5 33.5,
+                          20.4711 -40.6693 33.5,
+                          62 -16.5 33.5,
+                          63.3387 -25.4452 33.5,
+                          64.3512 -17.2639 33.5,
+                          63.2361 -16.6958 33.5,
+                          64.4164 -24.8634 33.5,
+                          65.2361 -18.1489 33.5,
+                          64.3512 -17.2639 33.5,
+                          63.3387 -25.4452 33.5,
+                          64.4164 -24.8634 33.5,
+                          64.3512 -17.2639 33.5,
+                          65.2676 -23.9829 33.5,
+                          65.8042 -19.2639 33.5,
+                          65.2361 -18.1489 33.5,
+                          64.4164 -24.8634 33.5,
+                          65.2676 -23.9829 33.5,
+                          65.2361 -18.1489 33.5,
+                          66 -21.6758 33.5,
+                          66 -20.5 33.5,
+                          65.8042 -19.2639 33.5,
+                          65.8125 -22.8861 33.5,
+                          66 -21.6758 33.5,
+                          65.8042 -19.2639 33.5,
+                          65.2676 -23.9829 33.5,
+                          65.8125 -22.8861 33.5,
+                          65.8042 -19.2639 33.5,
+                          -19.5 -16.5 33.5,
+                          19.8116 -40.8419 33.5,
+                          20.4711 -40.6693 33.5,
+                          -19.5 -16.5 33.5,
+                          19.1324 -40.9 33.5,
+                          19.8116 -40.8419 33.5,
+                          -19.5 -16.5 33.5,
+                          -19.5 -40.9 33.5,
+                          19.1324 -40.9 33.5,
+                          -20.7361 -16.6958 33.5,
+                          -20.7361 -40.7042 33.5,
+                          -19.5 -40.9 33.5,
+                          -19.5 -16.5 33.5,
+                          -20.7361 -16.6958 33.5,
+                          -19.5 -40.9 33.5,
+                          -21.8511 -17.2639 33.5,
+                          -21.8511 -40.1361 33.5,
+                          -20.7361 -40.7042 33.5,
+                          -20.7361 -16.6958 33.5,
+                          -21.8511 -17.2639 33.5,
+                          -20.7361 -40.7042 33.5,
+                          -22.7361 -18.1489 33.5,
+                          -22.7361 -39.2511 33.5,
+                          -21.8511 -40.1361 33.5,
+                          -21.8511 -17.2639 33.5,
+                          -22.7361 -18.1489 33.5,
+                          -21.8511 -40.1361 33.5,
+                          -23.3042 -19.2639 33.5,
+                          -23.3042 -38.1361 33.5,
+                          -22.7361 -39.2511 33.5,
+                          -22.7361 -18.1489 33.5,
+                          -23.3042 -19.2639 33.5,
+                          -22.7361 -39.2511 33.5,
+                          -23.5 -20.5 33.5,
+                          -23.5 -36.9 33.5,
+                          -23.3042 -38.1361 33.5,
+                          -23.3042 -19.2639 33.5,
+                          -23.5 -20.5 33.5,
+                          -23.3042 -38.1361 33.5 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+    Separator {
+        Normal {
+            vector      [ 5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          0.549454 0.835524 5.55112e-17,
+                          0.549454 0.835524 5.55112e-17,
+                          0.363732 0.931504 5.42981e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          0.711163 0.703028 5.42981e-17,
+                          0.711163 0.703028 5.42981e-17,
+                          0.549454 0.835524 5.55112e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          0.711163 0.703028 5.42981e-17,
+                          0.549454 0.835524 5.55112e-17,
+                          0.549454 0.835524 5.55112e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          0.363732 0.931504 5.42981e-17,
+                          0.363732 0.931504 5.42981e-17,
+                          0.162113 0.986772 5.0712e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          0.363732 0.931504 5.42981e-17,
+                          0.549454 0.835524 5.55112e-17,
+                          0.363732 0.931504 5.42981e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          0.162113 0.986772 5.0712e-17,
+                          0.162113 0.986772 5.0712e-17,
+                          -0.0465907 0.998914 4.49095e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          0.363732 0.931504 5.42981e-17,
+                          0.162113 0.986772 5.0712e-17,
+                          0.162113 0.986772 5.0712e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          -0.0465907 0.998914 4.49095e-17,
+                          -0.0465907 0.998914 4.49095e-17,
+                          -0.253258 0.967399 3.71442e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          0.162113 0.986772 5.0712e-17,
+                          -0.0465907 0.998914 4.49095e-17,
+                          -0.0465907 0.998914 4.49095e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          -0.253258 0.967399 3.71442e-17,
+                          -0.253258 0.967399 3.71442e-17,
+                          -0.448858 0.893603 2.77556e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          -0.0465907 0.998914 4.49095e-17,
+                          -0.253258 0.967399 3.71442e-17,
+                          -0.253258 0.967399 3.71442e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          -0.448858 0.893603 2.77556e-17,
+                          -0.448858 0.893603 2.77556e-17,
+                          -0.62484 0.780753 1.71539e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          -0.253258 0.967399 3.71442e-17,
+                          -0.448858 0.893603 2.77556e-17,
+                          -0.448858 0.893603 2.77556e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          -0.62484 0.780753 1.71539e-17,
+                          -0.62484 0.780753 1.71539e-17,
+                          -0.773513 0.63378 5.8025e-18,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          -0.448858 0.893603 2.77556e-17,
+                          -0.62484 0.780753 1.71539e-17,
+                          -0.62484 0.780753 1.71539e-17,
+                          -0.773513 0.63378 5.8025e-18,
+                          -0.773513 0.63378 5.8025e-18,
+                          -0.88838 0.459108 -5.8025e-18,
+                          -0.62484 0.780753 1.71539e-17,
+                          -0.773513 0.63378 5.8025e-18,
+                          -0.773513 0.63378 5.8025e-18,
+                          -0.88838 0.459108 -5.8025e-18,
+                          -0.88838 0.459108 -5.8025e-18,
+                          -0.964421 0.264371 -1.71539e-17,
+                          -0.773513 0.63378 5.8025e-18,
+                          -0.88838 0.459108 -5.8025e-18,
+                          -0.88838 0.459108 -5.8025e-18,
+                          -0.964421 0.264371 -1.71539e-17,
+                          -0.964421 0.264371 -1.71539e-17,
+                          -0.998312 0.0580795 -2.77556e-17,
+                          -0.88838 0.459108 -5.8025e-18,
+                          -0.964421 0.264371 -1.71539e-17,
+                          -0.964421 0.264371 -1.71539e-17,
+                          -0.998312 0.0580795 -2.77556e-17,
+                          -0.998312 0.0580795 -2.77556e-17,
+                          -0.988572 -0.15075 -3.71442e-17,
+                          -0.964421 0.264371 -1.71539e-17,
+                          -0.998312 0.0580795 -2.77556e-17,
+                          -0.998312 0.0580795 -2.77556e-17,
+                          -0.988572 -0.15075 -3.71442e-17,
+                          -0.988572 -0.15075 -3.71442e-17,
+                          -0.935626 -0.352992 -4.49095e-17,
+                          -0.998312 0.0580795 -2.77556e-17,
+                          -0.988572 -0.15075 -3.71442e-17,
+                          -0.988572 -0.15075 -3.71442e-17,
+                          -0.935626 -0.352992 -4.49095e-17,
+                          -0.935626 -0.352992 -4.49095e-17,
+                          -0.84179 -0.539806 -5.0712e-17,
+                          -0.988572 -0.15075 -3.71442e-17,
+                          -0.935626 -0.352992 -4.49095e-17,
+                          -0.935626 -0.352992 -4.49095e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          -0.84179 -0.539806 -5.0712e-17,
+                          -0.84179 -0.539806 -5.0712e-17,
+                          -0.711163 -0.703028 -5.42981e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          -0.935626 -0.352992 -4.49095e-17,
+                          -0.84179 -0.539806 -5.0712e-17,
+                          -0.84179 -0.539806 -5.0712e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          -0.711163 -0.703028 -5.42981e-17,
+                          -0.711163 -0.703028 -5.42981e-17,
+                          -0.549454 -0.835524 -5.55112e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          -0.84179 -0.539806 -5.0712e-17,
+                          -0.711163 -0.703028 -5.42981e-17,
+                          -0.711163 -0.703028 -5.42981e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          -0.549454 -0.835524 -5.55112e-17,
+                          -0.549454 -0.835524 -5.55112e-17,
+                          -0.363732 -0.931504 -5.42981e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          -0.711163 -0.703028 -5.42981e-17,
+                          -0.549454 -0.835524 -5.55112e-17,
+                          -0.549454 -0.835524 -5.55112e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          -0.363732 -0.931504 -5.42981e-17,
+                          -0.363732 -0.931504 -5.42981e-17,
+                          -0.162113 -0.986772 -5.0712e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          -0.549454 -0.835524 -5.55112e-17,
+                          -0.363732 -0.931504 -5.42981e-17,
+                          -0.363732 -0.931504 -5.42981e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          -0.162113 -0.986772 -5.0712e-17,
+                          -0.162113 -0.986772 -5.0712e-17,
+                          0.0465907 -0.998914 -4.49095e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          -0.363732 -0.931504 -5.42981e-17,
+                          -0.162113 -0.986772 -5.0712e-17,
+                          -0.162113 -0.986772 -5.0712e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          0.0465907 -0.998914 -4.49095e-17,
+                          0.0465907 -0.998914 -4.49095e-17,
+                          0.253258 -0.967399 -3.71442e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          -0.162113 -0.986772 -5.0712e-17,
+                          0.0465907 -0.998914 -4.49095e-17,
+                          0.0465907 -0.998914 -4.49095e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          0.253258 -0.967399 -3.71442e-17,
+                          0.253258 -0.967399 -3.71442e-17,
+                          0.448858 -0.893603 -2.77556e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          0.0465907 -0.998914 -4.49095e-17,
+                          0.253258 -0.967399 -3.71442e-17,
+                          0.253258 -0.967399 -3.71442e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          0.448858 -0.893603 -2.77556e-17,
+                          0.448858 -0.893603 -2.77556e-17,
+                          0.62484 -0.780753 -1.71539e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          0.253258 -0.967399 -3.71442e-17,
+                          0.448858 -0.893603 -2.77556e-17,
+                          0.448858 -0.893603 -2.77556e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          0.62484 -0.780753 -1.71539e-17,
+                          0.62484 -0.780753 -1.71539e-17,
+                          0.773513 -0.63378 -5.8025e-18,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          0.448858 -0.893603 -2.77556e-17,
+                          0.62484 -0.780753 -1.71539e-17,
+                          0.62484 -0.780753 -1.71539e-17,
+                          0.773513 -0.63378 -5.8025e-18,
+                          0.773513 -0.63378 -5.8025e-18,
+                          0.88838 -0.459108 5.8025e-18,
+                          0.62484 -0.780753 -1.71539e-17,
+                          0.773513 -0.63378 -5.8025e-18,
+                          0.773513 -0.63378 -5.8025e-18,
+                          0.88838 -0.459108 5.8025e-18,
+                          0.88838 -0.459108 5.8025e-18,
+                          0.964421 -0.264371 1.71539e-17,
+                          0.773513 -0.63378 -5.8025e-18,
+                          0.88838 -0.459108 5.8025e-18,
+                          0.88838 -0.459108 5.8025e-18,
+                          0.964421 -0.264371 1.71539e-17,
+                          0.964421 -0.264371 1.71539e-17,
+                          0.998312 -0.0580795 2.77556e-17,
+                          0.88838 -0.459108 5.8025e-18,
+                          0.964421 -0.264371 1.71539e-17,
+                          0.964421 -0.264371 1.71539e-17,
+                          0.998312 -0.0580795 2.77556e-17,
+                          0.998312 -0.0580795 2.77556e-17,
+                          0.988572 0.15075 3.71442e-17,
+                          0.964421 -0.264371 1.71539e-17,
+                          0.998312 -0.0580795 2.77556e-17,
+                          0.998312 -0.0580795 2.77556e-17,
+                          0.988572 0.15075 3.71442e-17,
+                          0.988572 0.15075 3.71442e-17,
+                          0.935626 0.352992 4.49095e-17,
+                          0.998312 -0.0580795 2.77556e-17,
+                          0.988572 0.15075 3.71442e-17,
+                          0.988572 0.15075 3.71442e-17,
+                          0.935626 0.352992 4.49095e-17,
+                          0.935626 0.352992 4.49095e-17,
+                          0.84179 0.539806 5.0712e-17,
+                          0.988572 0.15075 3.71442e-17,
+                          0.935626 0.352992 4.49095e-17,
+                          0.935626 0.352992 4.49095e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          0.84179 0.539806 5.0712e-17,
+                          0.84179 0.539806 5.0712e-17,
+                          0.711163 0.703028 5.42981e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          0.935626 0.352992 4.49095e-17,
+                          0.84179 0.539806 5.0712e-17,
+                          0.84179 0.539806 5.0712e-17,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          0.84179 0.539806 5.0712e-17,
+                          0.711163 0.703028 5.42981e-17,
+                          0.711163 0.703028 5.42981e-17,
+                          0.835524 -0.549454 0,
+                          0.835524 -0.549454 0,
+                          0.561656 -0.827371 -2.12432e-17,
+                          0.98219 -0.187888 2.12432e-17,
+                          0.98219 -0.187888 2.12432e-17,
+                          0.835524 -0.549454 0,
+                          0.98219 -0.187888 2.12432e-17,
+                          0.835524 -0.549454 0,
+                          0.835524 -0.549454 0,
+                          0.561656 -0.827371 -2.12432e-17,
+                          0.561656 -0.827371 -2.12432e-17,
+                          0.202282 -0.979327 -3.92523e-17,
+                          0.561656 -0.827371 -2.12432e-17,
+                          0.835524 -0.549454 0,
+                          0.561656 -0.827371 -2.12432e-17,
+                          0.202282 -0.979327 -3.92523e-17,
+                          0.202282 -0.979327 -3.92523e-17,
+                          -0.187888 -0.98219 -5.12856e-17,
+                          0.202282 -0.979327 -3.92523e-17,
+                          0.561656 -0.827371 -2.12432e-17,
+                          0.202282 -0.979327 -3.92523e-17,
+                          -0.187888 -0.98219 -5.12856e-17,
+                          -0.187888 -0.98219 -5.12856e-17,
+                          -0.549454 -0.835524 -5.55112e-17,
+                          -0.187888 -0.98219 -5.12856e-17,
+                          0.202282 -0.979327 -3.92523e-17,
+                          -0.187888 -0.98219 -5.12856e-17,
+                          -0.549454 -0.835524 -5.55112e-17,
+                          -0.549454 -0.835524 -5.55112e-17,
+                          -0.827371 -0.561656 -5.12856e-17,
+                          -0.549454 -0.835524 -5.55112e-17,
+                          -0.187888 -0.98219 -5.12856e-17,
+                          -0.549454 -0.835524 -5.55112e-17,
+                          -0.827371 -0.561656 -5.12856e-17,
+                          -0.827371 -0.561656 -5.12856e-17,
+                          -0.979327 -0.202282 -3.92523e-17,
+                          -0.827371 -0.561656 -5.12856e-17,
+                          -0.549454 -0.835524 -5.55112e-17,
+                          -0.827371 -0.561656 -5.12856e-17,
+                          -0.979327 -0.202282 -3.92523e-17,
+                          -0.979327 -0.202282 -3.92523e-17,
+                          -0.98219 0.187888 -2.12432e-17,
+                          -0.979327 -0.202282 -3.92523e-17,
+                          -0.827371 -0.561656 -5.12856e-17,
+                          -0.979327 -0.202282 -3.92523e-17,
+                          -0.98219 0.187888 -2.12432e-17,
+                          -0.98219 0.187888 -2.12432e-17,
+                          -0.835524 0.549454 0,
+                          -0.98219 0.187888 -2.12432e-17,
+                          -0.979327 -0.202282 -3.92523e-17,
+                          -0.98219 0.187888 -2.12432e-17,
+                          -0.835524 0.549454 0,
+                          -0.835524 0.549454 0,
+                          -0.561656 0.827371 2.12432e-17,
+                          -0.98219 0.187888 -2.12432e-17,
+                          -0.835524 0.549454 0,
+                          -0.835524 0.549454 0,
+                          -0.561656 0.827371 2.12432e-17,
+                          -0.561656 0.827371 2.12432e-17,
+                          -0.202282 0.979327 3.92523e-17,
+                          -0.561656 0.827371 2.12432e-17,
+                          -0.835524 0.549454 0,
+                          -0.561656 0.827371 2.12432e-17,
+                          -0.202282 0.979327 3.92523e-17,
+                          -0.202282 0.979327 3.92523e-17,
+                          0.187888 0.98219 5.12856e-17,
+                          -0.561656 0.827371 2.12432e-17,
+                          -0.202282 0.979327 3.92523e-17,
+                          -0.202282 0.979327 3.92523e-17,
+                          0.187888 0.98219 5.12856e-17,
+                          0.187888 0.98219 5.12856e-17,
+                          0.549454 0.835524 5.55112e-17,
+                          -0.202282 0.979327 3.92523e-17,
+                          0.187888 0.98219 5.12856e-17,
+                          0.187888 0.98219 5.12856e-17,
+                          0.549454 0.835524 5.55112e-17,
+                          0.549454 0.835524 5.55112e-17,
+                          0.827371 0.561656 5.12856e-17,
+                          0.187888 0.98219 5.12856e-17,
+                          0.549454 0.835524 5.55112e-17,
+                          0.549454 0.835524 5.55112e-17,
+                          0.827371 0.561656 5.12856e-17,
+                          0.827371 0.561656 5.12856e-17,
+                          0.979327 0.202282 3.92523e-17,
+                          0.549454 0.835524 5.55112e-17,
+                          0.827371 0.561656 5.12856e-17,
+                          0.827371 0.561656 5.12856e-17,
+                          0.979327 0.202282 3.92523e-17,
+                          0.979327 0.202282 3.92523e-17,
+                          0.98219 -0.187888 2.12432e-17,
+                          0.827371 0.561656 5.12856e-17,
+                          0.979327 0.202282 3.92523e-17,
+                          0.979327 0.202282 3.92523e-17,
+                          0.979327 0.202282 3.92523e-17,
+                          0.98219 -0.187888 2.12432e-17,
+                          0.98219 -0.187888 2.12432e-17,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          -5.82312e-14 8.38577e-14 1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1,
+                          5.82312e-14 -8.38577e-14 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -0.809115 3.91731 -5,
+                          6.36533 16.3013 -5,
+                          9.61545 14.6217 -5,
+                          9.61545 14.6217 3.73035e-14,
+                          9.61545 14.6217 -5,
+                          6.36533 16.3013 -5,
+                          2.19782 3.34209 -5,
+                          9.61545 14.6217 -5,
+                          12.4453 12.303 -5,
+                          12.4453 12.303 3.73035e-14,
+                          12.4453 12.303 -5,
+                          9.61545 14.6217 -5,
+                          0.751561 3.92876 -5,
+                          -0.809115 3.91731 -5,
+                          9.61545 14.6217 -5,
+                          2.19782 3.34209 -5,
+                          0.751561 3.92876 -5,
+                          9.61545 14.6217 -5,
+                          12.4453 12.303 3.73035e-14,
+                          9.61545 14.6217 -5,
+                          9.61545 14.6217 3.73035e-14,
+                          -14.7313 -9.44661 -5,
+                          2.83699 17.2685 -5,
+                          6.36533 16.3013 -5,
+                          6.36533 16.3013 3.73035e-14,
+                          6.36533 16.3013 -5,
+                          2.83699 17.2685 -5,
+                          -3.3421 2.19782 -5,
+                          -14.7313 -9.44661 -5,
+                          6.36533 16.3013 -5,
+                          -2.24662 3.30949 -5,
+                          -3.3421 2.19782 -5,
+                          6.36533 16.3013 -5,
+                          -0.809115 3.91731 -5,
+                          -2.24662 3.30949 -5,
+                          6.36533 16.3013 -5,
+                          6.36533 16.3013 3.73035e-14,
+                          9.61545 14.6217 3.73035e-14,
+                          6.36533 16.3013 -5,
+                          -16.3735 -6.17735 -5,
+                          -0.815346 17.481 -5,
+                          2.83699 17.2685 -5,
+                          2.83699 17.2685 3.73035e-14,
+                          2.83699 17.2685 -5,
+                          -0.815346 17.481 -5,
+                          -14.7313 -9.44661 -5,
+                          -16.3735 -6.17735 -5,
+                          2.83699 17.2685 -5,
+                          6.36533 16.3013 3.73035e-14,
+                          2.83699 17.2685 -5,
+                          2.83699 17.2685 3.73035e-14,
+                          -17.3 -2.63811 -5,
+                          -4.43204 16.9295 -5,
+                          -0.815346 17.481 -5,
+                          -0.815346 17.481 3.73035e-14,
+                          -0.815346 17.481 -5,
+                          -4.43204 16.9295 -5,
+                          -16.3735 -6.17735 -5,
+                          -17.3 -2.63811 -5,
+                          -0.815346 17.481 -5,
+                          2.83699 17.2685 3.73035e-14,
+                          -0.815346 17.481 -5,
+                          -0.815346 17.481 3.73035e-14,
+                          -17.4705 1.01639 -5,
+                          -7.85501 15.6381 -5,
+                          -4.43204 16.9295 -5,
+                          -4.43204 16.9295 3.73035e-14,
+                          -4.43204 16.9295 -5,
+                          -7.85501 15.6381 -5,
+                          -17.3 -2.63811 -5,
+                          -17.4705 1.01639 -5,
+                          -4.43204 16.9295 -5,
+                          -0.815346 17.481 3.73035e-14,
+                          -4.43204 16.9295 -5,
+                          -4.43204 16.9295 3.73035e-14,
+                          -16.8774 4.62648 -5,
+                          -10.9347 13.6632 -5,
+                          -7.85501 15.6381 -5,
+                          -7.85501 15.6381 3.73035e-14,
+                          -7.85501 15.6381 -5,
+                          -10.9347 13.6632 -5,
+                          -17.4705 1.01639 -5,
+                          -16.8774 4.62648 -5,
+                          -7.85501 15.6381 -5,
+                          -4.43204 16.9295 3.73035e-14,
+                          -7.85501 15.6381 -5,
+                          -7.85501 15.6381 3.73035e-14,
+                          -15.5467 8.03439 -5,
+                          -13.5365 11.0912 -5,
+                          -10.9347 13.6632 -5,
+                          -10.9347 13.6632 3.64153e-14,
+                          -10.9347 13.6632 -5,
+                          -13.5365 11.0912 -5,
+                          -16.8774 4.62648 -5,
+                          -15.5467 8.03439 -5,
+                          -10.9347 13.6632 -5,
+                          -7.85501 15.6381 3.73035e-14,
+                          -10.9347 13.6632 -5,
+                          -10.9347 13.6632 3.64153e-14,
+                          -13.5365 11.0912 3.64153e-14,
+                          -13.5365 11.0912 -5,
+                          -15.5467 8.03439 -5,
+                          -10.9347 13.6632 3.64153e-14,
+                          -13.5365 11.0912 -5,
+                          -13.5365 11.0912 3.64153e-14,
+                          -15.5467 8.03439 3.64153e-14,
+                          -15.5467 8.03439 -5,
+                          -16.8774 4.62648 -5,
+                          -13.5365 11.0912 3.64153e-14,
+                          -15.5467 8.03439 -5,
+                          -15.5467 8.03439 3.64153e-14,
+                          -16.8774 4.62648 3.64153e-14,
+                          -16.8774 4.62648 -5,
+                          -17.4705 1.01639 -5,
+                          -15.5467 8.03439 3.64153e-14,
+                          -16.8774 4.62648 -5,
+                          -16.8774 4.62648 3.64153e-14,
+                          -17.4705 1.01639 3.55271e-14,
+                          -17.4705 1.01639 -5,
+                          -17.3 -2.63811 -5,
+                          -16.8774 4.62648 3.64153e-14,
+                          -17.4705 1.01639 -5,
+                          -17.4705 1.01639 3.55271e-14,
+                          -17.3 -2.63811 3.55271e-14,
+                          -17.3 -2.63811 -5,
+                          -16.3735 -6.17735 -5,
+                          -17.4705 1.01639 3.55271e-14,
+                          -17.3 -2.63811 -5,
+                          -17.3 -2.63811 3.55271e-14,
+                          -16.3735 -6.17735 3.55271e-14,
+                          -16.3735 -6.17735 -5,
+                          -14.7313 -9.44661 -5,
+                          -17.3 -2.63811 3.55271e-14,
+                          -16.3735 -6.17735 -5,
+                          -16.3735 -6.17735 3.55271e-14,
+                          -3.92876 0.751544 -5,
+                          -12.4453 -12.303 -5,
+                          -14.7313 -9.44661 -5,
+                          -14.7313 -9.44661 3.55271e-14,
+                          -14.7313 -9.44661 -5,
+                          -12.4453 -12.303 -5,
+                          -3.3421 2.19782 -5,
+                          -3.92876 0.751544 -5,
+                          -14.7313 -9.44661 -5,
+                          -16.3735 -6.17735 3.55271e-14,
+                          -14.7313 -9.44661 -5,
+                          -14.7313 -9.44661 3.55271e-14,
+                          -2.19782 -3.34209 -5,
+                          -9.61545 -14.6217 -5,
+                          -12.4453 -12.303 -5,
+                          -12.4453 -12.303 3.55271e-14,
+                          -12.4453 -12.303 -5,
+                          -9.61545 -14.6217 -5,
+                          -3.30948 -2.24663 -5,
+                          -2.19782 -3.34209 -5,
+                          -12.4453 -12.303 -5,
+                          -3.91731 -0.809138 -5,
+                          -3.30948 -2.24663 -5,
+                          -12.4453 -12.303 -5,
+                          -3.92876 0.751544 -5,
+                          -3.91731 -0.809138 -5,
+                          -12.4453 -12.303 -5,
+                          -14.7313 -9.44661 3.55271e-14,
+                          -12.4453 -12.303 -5,
+                          -12.4453 -12.303 3.55271e-14,
+                          0.809115 -3.91731 -5,
+                          -6.36533 -16.3013 -5,
+                          -9.61545 -14.6217 -5,
+                          -9.61545 -14.6217 3.55271e-14,
+                          -9.61545 -14.6217 -5,
+                          -6.36533 -16.3013 -5,
+                          -0.751561 -3.92876 -5,
+                          0.809115 -3.91731 -5,
+                          -9.61545 -14.6217 -5,
+                          -2.19782 -3.34209 -5,
+                          -0.751561 -3.92876 -5,
+                          -9.61545 -14.6217 -5,
+                          -12.4453 -12.303 3.55271e-14,
+                          -9.61545 -14.6217 -5,
+                          -9.61545 -14.6217 3.55271e-14,
+                          14.7313 9.44661 -5,
+                          -2.83699 -17.2685 -5,
+                          -6.36533 -16.3013 -5,
+                          -6.36533 -16.3013 3.55271e-14,
+                          -6.36533 -16.3013 -5,
+                          -2.83699 -17.2685 -5,
+                          3.3421 -2.19782 -5,
+                          14.7313 9.44661 -5,
+                          -6.36533 -16.3013 -5,
+                          2.24662 -3.30949 -5,
+                          3.3421 -2.19782 -5,
+                          -6.36533 -16.3013 -5,
+                          0.809115 -3.91731 -5,
+                          2.24662 -3.30949 -5,
+                          -6.36533 -16.3013 -5,
+                          -9.61545 -14.6217 3.55271e-14,
+                          -6.36533 -16.3013 -5,
+                          -6.36533 -16.3013 3.55271e-14,
+                          16.3735 6.17735 -5,
+                          0.815346 -17.481 -5,
+                          -2.83699 -17.2685 -5,
+                          -2.83699 -17.2685 3.55271e-14,
+                          -2.83699 -17.2685 -5,
+                          0.815346 -17.481 -5,
+                          14.7313 9.44661 -5,
+                          16.3735 6.17735 -5,
+                          -2.83699 -17.2685 -5,
+                          -6.36533 -16.3013 3.55271e-14,
+                          -2.83699 -17.2685 -5,
+                          -2.83699 -17.2685 3.55271e-14,
+                          17.3 2.63811 -5,
+                          4.43204 -16.9295 -5,
+                          0.815346 -17.481 -5,
+                          0.815346 -17.481 3.55271e-14,
+                          0.815346 -17.481 -5,
+                          4.43204 -16.9295 -5,
+                          16.3735 6.17735 -5,
+                          17.3 2.63811 -5,
+                          0.815346 -17.481 -5,
+                          -2.83699 -17.2685 3.55271e-14,
+                          0.815346 -17.481 -5,
+                          0.815346 -17.481 3.55271e-14,
+                          17.4705 -1.01639 -5,
+                          7.85501 -15.6381 -5,
+                          4.43204 -16.9295 -5,
+                          4.43204 -16.9295 3.55271e-14,
+                          4.43204 -16.9295 -5,
+                          7.85501 -15.6381 -5,
+                          17.3 2.63811 -5,
+                          17.4705 -1.01639 -5,
+                          4.43204 -16.9295 -5,
+                          0.815346 -17.481 3.55271e-14,
+                          4.43204 -16.9295 -5,
+                          4.43204 -16.9295 3.55271e-14,
+                          16.8774 -4.62648 -5,
+                          10.9347 -13.6632 -5,
+                          7.85501 -15.6381 -5,
+                          7.85501 -15.6381 3.55271e-14,
+                          7.85501 -15.6381 -5,
+                          10.9347 -13.6632 -5,
+                          17.4705 -1.01639 -5,
+                          16.8774 -4.62648 -5,
+                          7.85501 -15.6381 -5,
+                          4.43204 -16.9295 3.55271e-14,
+                          7.85501 -15.6381 -5,
+                          7.85501 -15.6381 3.55271e-14,
+                          15.5467 -8.03439 -5,
+                          13.5365 -11.0912 -5,
+                          10.9347 -13.6632 -5,
+                          10.9347 -13.6632 3.64153e-14,
+                          10.9347 -13.6632 -5,
+                          13.5365 -11.0912 -5,
+                          16.8774 -4.62648 -5,
+                          15.5467 -8.03439 -5,
+                          10.9347 -13.6632 -5,
+                          7.85501 -15.6381 3.55271e-14,
+                          10.9347 -13.6632 -5,
+                          10.9347 -13.6632 3.64153e-14,
+                          13.5365 -11.0912 3.64153e-14,
+                          13.5365 -11.0912 -5,
+                          15.5467 -8.03439 -5,
+                          10.9347 -13.6632 3.64153e-14,
+                          13.5365 -11.0912 -5,
+                          13.5365 -11.0912 3.64153e-14,
+                          15.5467 -8.03439 3.64153e-14,
+                          15.5467 -8.03439 -5,
+                          16.8774 -4.62648 -5,
+                          13.5365 -11.0912 3.64153e-14,
+                          15.5467 -8.03439 -5,
+                          15.5467 -8.03439 3.64153e-14,
+                          16.8774 -4.62648 3.64153e-14,
+                          16.8774 -4.62648 -5,
+                          17.4705 -1.01639 -5,
+                          15.5467 -8.03439 3.64153e-14,
+                          16.8774 -4.62648 -5,
+                          16.8774 -4.62648 3.64153e-14,
+                          17.4705 -1.01639 3.73035e-14,
+                          17.4705 -1.01639 -5,
+                          17.3 2.63811 -5,
+                          16.8774 -4.62648 3.64153e-14,
+                          17.4705 -1.01639 -5,
+                          17.4705 -1.01639 3.73035e-14,
+                          17.3 2.63811 3.73035e-14,
+                          17.3 2.63811 -5,
+                          16.3735 6.17735 -5,
+                          17.4705 -1.01639 3.73035e-14,
+                          17.3 2.63811 -5,
+                          17.3 2.63811 3.73035e-14,
+                          16.3735 6.17735 3.73035e-14,
+                          16.3735 6.17735 -5,
+                          14.7313 9.44661 -5,
+                          17.3 2.63811 3.73035e-14,
+                          16.3735 6.17735 -5,
+                          16.3735 6.17735 3.73035e-14,
+                          3.92876 -0.751544 -5,
+                          12.4453 12.303 -5,
+                          14.7313 9.44661 -5,
+                          14.7313 9.44661 3.73035e-14,
+                          14.7313 9.44661 -5,
+                          12.4453 12.303 -5,
+                          3.92876 -0.751544 -5,
+                          14.7313 9.44661 -5,
+                          3.3421 -2.19782 -5,
+                          16.3735 6.17735 3.73035e-14,
+                          14.7313 9.44661 -5,
+                          14.7313 9.44661 3.73035e-14,
+                          3.30948 2.24663 -5,
+                          2.19782 3.34209 -5,
+                          12.4453 12.303 -5,
+                          3.91731 0.809138 -5,
+                          3.30948 2.24663 -5,
+                          12.4453 12.303 -5,
+                          3.92876 -0.751544 -5,
+                          3.91731 0.809138 -5,
+                          12.4453 12.303 -5,
+                          14.7313 9.44661 3.73035e-14,
+                          12.4453 12.303 -5,
+                          12.4453 12.303 3.73035e-14,
+                          3.3421 -2.19782 -10.8,
+                          3.3421 -2.19782 -5,
+                          2.24662 -3.30949 -5,
+                          3.92876 -0.751542 -10.8,
+                          3.92876 -0.751544 -5,
+                          3.3421 -2.19782 -5,
+                          3.92876 -0.751542 -10.8,
+                          3.3421 -2.19782 -5,
+                          3.3421 -2.19782 -10.8,
+                          2.24661 -3.30949 -10.8,
+                          2.24662 -3.30949 -5,
+                          0.809115 -3.91731 -5,
+                          2.24661 -3.30949 -10.8,
+                          3.3421 -2.19782 -10.8,
+                          2.24662 -3.30949 -5,
+                          0.809126 -3.91731 -10.8,
+                          0.809115 -3.91731 -5,
+                          -0.751561 -3.92876 -5,
+                          0.809126 -3.91731 -10.8,
+                          2.24661 -3.30949 -10.8,
+                          0.809115 -3.91731 -5,
+                          -0.751542 -3.92876 -10.8,
+                          -0.751561 -3.92876 -5,
+                          -2.19782 -3.34209 -5,
+                          -0.751542 -3.92876 -10.8,
+                          0.809126 -3.91731 -10.8,
+                          -0.751561 -3.92876 -5,
+                          -2.19782 -3.3421 -10.8,
+                          -2.19782 -3.34209 -5,
+                          -3.30948 -2.24663 -5,
+                          -2.19782 -3.3421 -10.8,
+                          -0.751542 -3.92876 -10.8,
+                          -2.19782 -3.34209 -5,
+                          -3.30949 -2.24661 -10.8,
+                          -3.30948 -2.24663 -5,
+                          -3.91731 -0.809138 -5,
+                          -3.30949 -2.24661 -10.8,
+                          -2.19782 -3.3421 -10.8,
+                          -3.30948 -2.24663 -5,
+                          -3.91731 -0.809126 -10.8,
+                          -3.91731 -0.809138 -5,
+                          -3.92876 0.751544 -5,
+                          -3.91731 -0.809126 -10.8,
+                          -3.30949 -2.24661 -10.8,
+                          -3.91731 -0.809138 -5,
+                          -3.92876 0.751542 -10.8,
+                          -3.92876 0.751544 -5,
+                          -3.3421 2.19782 -5,
+                          -3.92876 0.751542 -10.8,
+                          -3.91731 -0.809126 -10.8,
+                          -3.92876 0.751544 -5,
+                          -3.3421 2.19782 -10.8,
+                          -3.3421 2.19782 -5,
+                          -2.24662 3.30949 -5,
+                          -3.92876 0.751542 -10.8,
+                          -3.3421 2.19782 -5,
+                          -3.3421 2.19782 -10.8,
+                          -2.24661 3.30949 -10.8,
+                          -2.24662 3.30949 -5,
+                          -0.809115 3.91731 -5,
+                          -2.24661 3.30949 -10.8,
+                          -3.3421 2.19782 -10.8,
+                          -2.24662 3.30949 -5,
+                          -0.809126 3.91731 -10.8,
+                          -0.809115 3.91731 -5,
+                          0.751561 3.92876 -5,
+                          -2.24661 3.30949 -10.8,
+                          -0.809115 3.91731 -5,
+                          -0.809126 3.91731 -10.8,
+                          0.751542 3.92876 -10.8,
+                          0.751561 3.92876 -5,
+                          2.19782 3.34209 -5,
+                          -0.809126 3.91731 -10.8,
+                          0.751561 3.92876 -5,
+                          0.751542 3.92876 -10.8,
+                          2.19782 3.3421 -10.8,
+                          2.19782 3.34209 -5,
+                          3.30948 2.24663 -5,
+                          0.751542 3.92876 -10.8,
+                          2.19782 3.34209 -5,
+                          2.19782 3.3421 -10.8,
+                          3.30949 2.24661 -10.8,
+                          3.30948 2.24663 -5,
+                          3.91731 0.809138 -5,
+                          2.19782 3.3421 -10.8,
+                          3.30948 2.24663 -5,
+                          3.30949 2.24661 -10.8,
+                          3.91731 0.809126 -10.8,
+                          3.91731 0.809138 -5,
+                          3.92876 -0.751544 -5,
+                          3.30949 2.24661 -10.8,
+                          3.91731 0.809138 -5,
+                          3.91731 0.809126 -10.8,
+                          3.91731 0.809126 -10.8,
+                          3.92876 -0.751544 -5,
+                          3.92876 -0.751542 -10.8,
+                          -6.36533 -16.3013 3.55271e-14,
+                          12.4453 12.303 3.73035e-14,
+                          9.61545 14.6217 3.73035e-14,
+                          -9.61545 -14.6217 3.55271e-14,
+                          -6.36533 -16.3013 3.55271e-14,
+                          9.61545 14.6217 3.73035e-14,
+                          6.36533 16.3013 3.73035e-14,
+                          -9.61545 -14.6217 3.55271e-14,
+                          9.61545 14.6217 3.73035e-14,
+                          -2.83699 -17.2685 3.55271e-14,
+                          14.7313 9.44661 3.73035e-14,
+                          12.4453 12.303 3.73035e-14,
+                          -6.36533 -16.3013 3.55271e-14,
+                          -2.83699 -17.2685 3.55271e-14,
+                          12.4453 12.303 3.73035e-14,
+                          0.815346 -17.481 3.55271e-14,
+                          16.3735 6.17735 3.73035e-14,
+                          14.7313 9.44661 3.73035e-14,
+                          -2.83699 -17.2685 3.55271e-14,
+                          0.815346 -17.481 3.55271e-14,
+                          14.7313 9.44661 3.73035e-14,
+                          4.43204 -16.9295 3.55271e-14,
+                          17.3 2.63811 3.73035e-14,
+                          16.3735 6.17735 3.73035e-14,
+                          0.815346 -17.481 3.55271e-14,
+                          4.43204 -16.9295 3.55271e-14,
+                          16.3735 6.17735 3.73035e-14,
+                          7.85501 -15.6381 3.55271e-14,
+                          17.4705 -1.01639 3.73035e-14,
+                          17.3 2.63811 3.73035e-14,
+                          4.43204 -16.9295 3.55271e-14,
+                          7.85501 -15.6381 3.55271e-14,
+                          17.3 2.63811 3.73035e-14,
+                          10.9347 -13.6632 3.64153e-14,
+                          16.8774 -4.62648 3.64153e-14,
+                          17.4705 -1.01639 3.73035e-14,
+                          7.85501 -15.6381 3.55271e-14,
+                          10.9347 -13.6632 3.64153e-14,
+                          17.4705 -1.01639 3.73035e-14,
+                          13.5365 -11.0912 3.64153e-14,
+                          15.5467 -8.03439 3.64153e-14,
+                          16.8774 -4.62648 3.64153e-14,
+                          10.9347 -13.6632 3.64153e-14,
+                          13.5365 -11.0912 3.64153e-14,
+                          16.8774 -4.62648 3.64153e-14,
+                          6.36533 16.3013 3.73035e-14,
+                          -12.4453 -12.303 3.55271e-14,
+                          -9.61545 -14.6217 3.55271e-14,
+                          2.83699 17.2685 3.73035e-14,
+                          -14.7313 -9.44661 3.55271e-14,
+                          -12.4453 -12.303 3.55271e-14,
+                          6.36533 16.3013 3.73035e-14,
+                          2.83699 17.2685 3.73035e-14,
+                          -12.4453 -12.303 3.55271e-14,
+                          -0.815346 17.481 3.73035e-14,
+                          -16.3735 -6.17735 3.55271e-14,
+                          -14.7313 -9.44661 3.55271e-14,
+                          2.83699 17.2685 3.73035e-14,
+                          -0.815346 17.481 3.73035e-14,
+                          -14.7313 -9.44661 3.55271e-14,
+                          -4.43204 16.9295 3.73035e-14,
+                          -17.3 -2.63811 3.55271e-14,
+                          -16.3735 -6.17735 3.55271e-14,
+                          -0.815346 17.481 3.73035e-14,
+                          -4.43204 16.9295 3.73035e-14,
+                          -16.3735 -6.17735 3.55271e-14,
+                          -7.85501 15.6381 3.73035e-14,
+                          -17.4705 1.01639 3.55271e-14,
+                          -17.3 -2.63811 3.55271e-14,
+                          -4.43204 16.9295 3.73035e-14,
+                          -7.85501 15.6381 3.73035e-14,
+                          -17.3 -2.63811 3.55271e-14,
+                          -10.9347 13.6632 3.64153e-14,
+                          -16.8774 4.62648 3.64153e-14,
+                          -17.4705 1.01639 3.55271e-14,
+                          -7.85501 15.6381 3.73035e-14,
+                          -10.9347 13.6632 3.64153e-14,
+                          -17.4705 1.01639 3.55271e-14,
+                          -13.5365 11.0912 3.64153e-14,
+                          -15.5467 8.03439 3.64153e-14,
+                          -16.8774 4.62648 3.64153e-14,
+                          -10.9347 13.6632 3.64153e-14,
+                          -13.5365 11.0912 3.64153e-14,
+                          -16.8774 4.62648 3.64153e-14,
+                          2.24661 -3.30949 -10.8,
+                          -3.3421 2.19782 -10.8,
+                          3.3421 -2.19782 -10.8,
+                          -2.24661 3.30949 -10.8,
+                          3.3421 -2.19782 -10.8,
+                          -3.3421 2.19782 -10.8,
+                          -3.92876 0.751542 -10.8,
+                          -3.3421 2.19782 -10.8,
+                          2.24661 -3.30949 -10.8,
+                          -2.24661 3.30949 -10.8,
+                          3.92876 -0.751542 -10.8,
+                          3.3421 -2.19782 -10.8,
+                          -3.92876 0.751542 -10.8,
+                          2.24661 -3.30949 -10.8,
+                          0.809126 -3.91731 -10.8,
+                          -3.91731 -0.809126 -10.8,
+                          0.809126 -3.91731 -10.8,
+                          -0.751542 -3.92876 -10.8,
+                          -3.92876 0.751542 -10.8,
+                          0.809126 -3.91731 -10.8,
+                          -3.91731 -0.809126 -10.8,
+                          -3.30949 -2.24661 -10.8,
+                          -0.751542 -3.92876 -10.8,
+                          -2.19782 -3.3421 -10.8,
+                          -3.91731 -0.809126 -10.8,
+                          -0.751542 -3.92876 -10.8,
+                          -3.30949 -2.24661 -10.8,
+                          -0.809126 3.91731 -10.8,
+                          3.91731 0.809126 -10.8,
+                          3.92876 -0.751542 -10.8,
+                          -2.24661 3.30949 -10.8,
+                          -0.809126 3.91731 -10.8,
+                          3.92876 -0.751542 -10.8,
+                          0.751542 3.92876 -10.8,
+                          3.30949 2.24661 -10.8,
+                          3.91731 0.809126 -10.8,
+                          -0.809126 3.91731 -10.8,
+                          0.751542 3.92876 -10.8,
+                          3.91731 0.809126 -10.8,
+                          0.751542 3.92876 -10.8,
+                          2.19782 3.3421 -10.8,
+                          3.30949 2.24661 -10.8 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.25 0.25 0.25
+    }
+    Separator {
+        Normal {
+            vector      [ 3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          1 -3.87423e-17 5.55112e-17,
+                          1 -3.87423e-17 5.55112e-17,
+                          1 -3.87423e-17 5.55112e-17,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          0.980785 0.19509 7.32964e-17,
+                          0.980785 0.19509 7.32964e-17,
+                          1 8.37224e-17 5.55112e-17,
+                          0.980785 0.19509 7.32964e-17,
+                          1 8.37224e-17 5.55112e-17,
+                          1 8.37224e-17 5.55112e-17,
+                          4.7402e-17 -1 -9.66314e-17,
+                          4.7402e-17 -1 -9.66314e-17,
+                          4.7402e-17 -1 -9.66314e-17,
+                          1 -3.87423e-17 5.55112e-17,
+                          1 -3.87423e-17 5.55112e-17,
+                          1 -3.87423e-17 5.55112e-17,
+                          -1 3.87423e-17 -5.55112e-17,
+                          -1 3.87423e-17 -5.55112e-17,
+                          -1 3.87423e-17 -5.55112e-17,
+                          4.7402e-17 -1 -9.66314e-17,
+                          4.7402e-17 -1 -9.66314e-17,
+                          4.7402e-17 -1 -9.66314e-17,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          -1 3.87423e-17 -5.55112e-17,
+                          -1 3.87423e-17 -5.55112e-17,
+                          -0.980785 0.19509 -3.55927e-17,
+                          -1 3.87423e-17 -5.55112e-17,
+                          -1 3.87423e-17 -5.55112e-17,
+                          -1 3.87423e-17 -5.55112e-17,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          -0.980785 0.19509 -3.55927e-17,
+                          -0.980785 0.19509 -3.55927e-17,
+                          -0.92388 0.382683 -1.43064e-17,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          -0.980785 0.19509 -3.55927e-17,
+                          -1 3.87423e-17 -5.55112e-17,
+                          -0.980785 0.19509 -3.55927e-17,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          -0.92388 0.382683 -1.43064e-17,
+                          -0.92388 0.382683 -1.43064e-17,
+                          -0.83147 0.55557 7.52968e-18,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          -0.980785 0.19509 -3.55927e-17,
+                          -0.92388 0.382683 -1.43064e-17,
+                          -0.92388 0.382683 -1.43064e-17,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          -0.83147 0.55557 7.52968e-18,
+                          -0.83147 0.55557 7.52968e-18,
+                          -0.707107 0.707107 2.90764e-17,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          -0.92388 0.382683 -1.43064e-17,
+                          -0.83147 0.55557 7.52968e-18,
+                          -0.83147 0.55557 7.52968e-18,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          -0.707107 0.707107 2.90764e-17,
+                          -0.707107 0.707107 2.90764e-17,
+                          -0.55557 0.83147 4.95057e-17,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          -0.83147 0.55557 7.52968e-18,
+                          -0.707107 0.707107 2.90764e-17,
+                          -0.707107 0.707107 2.90764e-17,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          -0.55557 0.83147 4.95057e-17,
+                          -0.55557 0.83147 4.95057e-17,
+                          -0.382683 0.92388 6.80326e-17,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          -0.707107 0.707107 2.90764e-17,
+                          -0.55557 0.83147 4.95057e-17,
+                          -0.55557 0.83147 4.95057e-17,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          -0.382683 0.92388 6.80326e-17,
+                          -0.382683 0.92388 6.80326e-17,
+                          -0.19509 0.980785 8.39449e-17,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          -0.55557 0.83147 4.95057e-17,
+                          -0.382683 0.92388 6.80326e-17,
+                          -0.382683 0.92388 6.80326e-17,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          3.33067e-16 3.58229e-17 1,
+                          -0.19509 0.980785 8.39449e-17,
+                          -0.19509 0.980785 8.39449e-17,
+                          -3.30679e-16 1 9.66314e-17,
+                          -0.382683 0.92388 6.80326e-17,
+                          -0.19509 0.980785 8.39449e-17,
+                          -0.19509 0.980785 8.39449e-17,
+                          1.22363e-15 1 9.66314e-17,
+                          -3.30679e-16 1 9.66314e-17,
+                          0.19509 0.980785 1.05604e-16,
+                          -0.19509 0.980785 8.39449e-17,
+                          -3.30679e-16 1 9.66314e-17,
+                          1.22363e-15 1 9.66314e-17,
+                          0.19509 0.980785 1.05604e-16,
+                          0.19509 0.980785 1.05604e-16,
+                          0.382683 0.92388 1.10519e-16,
+                          1.22363e-15 1 9.66314e-17,
+                          0.19509 0.980785 1.05604e-16,
+                          0.19509 0.980785 1.05604e-16,
+                          0.382683 0.92388 1.10519e-16,
+                          0.382683 0.92388 1.10519e-16,
+                          0.55557 0.83147 1.11186e-16,
+                          0.19509 0.980785 1.05604e-16,
+                          0.382683 0.92388 1.10519e-16,
+                          0.382683 0.92388 1.10519e-16,
+                          0.55557 0.83147 1.11186e-16,
+                          0.55557 0.83147 1.11186e-16,
+                          0.707107 0.707107 1.07581e-16,
+                          0.382683 0.92388 1.10519e-16,
+                          0.55557 0.83147 1.11186e-16,
+                          0.55557 0.83147 1.11186e-16,
+                          0.707107 0.707107 1.07581e-16,
+                          0.707107 0.707107 1.07581e-16,
+                          0.83147 0.55557 9.98413e-17,
+                          0.55557 0.83147 1.11186e-16,
+                          0.707107 0.707107 1.07581e-16,
+                          0.707107 0.707107 1.07581e-16,
+                          0.83147 0.55557 9.98413e-17,
+                          0.83147 0.55557 9.98413e-17,
+                          0.92388 0.382683 8.82648e-17,
+                          0.707107 0.707107 1.07581e-16,
+                          0.83147 0.55557 9.98413e-17,
+                          0.83147 0.55557 9.98413e-17,
+                          0.92388 0.382683 8.82648e-17,
+                          0.92388 0.382683 8.82648e-17,
+                          0.980785 0.19509 7.32964e-17,
+                          0.83147 0.55557 9.98413e-17,
+                          0.92388 0.382683 8.82648e-17,
+                          0.92388 0.382683 8.82648e-17,
+                          0.92388 0.382683 8.82648e-17,
+                          0.980785 0.19509 7.32964e-17,
+                          0.980785 0.19509 7.32964e-17,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1,
+                          -3.33067e-16 -3.58229e-17 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -18.5 -38.5 2,
+                          18.5 -38.5 2,
+                          18.5 -1.42109e-14 2,
+                          18.5 -1.42109e-14 3.10862e-15,
+                          18.5 -1.42109e-14 2,
+                          18.5 -38.5 2,
+                          -18.5 -1.42109e-14 2,
+                          -18.5 -38.5 2,
+                          18.5 -1.42109e-14 2,
+                          18.1445 3.60918 2,
+                          -18.5 -1.42109e-14 2,
+                          18.5 -1.42109e-14 2,
+                          18.1445 3.60918 3.33067e-15,
+                          18.1445 3.60918 2,
+                          18.5 -1.42109e-14 2,
+                          18.1445 3.60918 3.33067e-15,
+                          18.5 -1.42109e-14 2,
+                          18.5 -1.42109e-14 3.10862e-15,
+                          18.5 -38.5 -6.66134e-16,
+                          18.5 -38.5 2,
+                          -18.5 -38.5 2,
+                          18.5 -1.42109e-14 3.10862e-15,
+                          18.5 -38.5 2,
+                          18.5 -38.5 -6.66134e-16,
+                          -18.5 -38.5 -2.66454e-15,
+                          -18.5 -38.5 2,
+                          -18.5 -1.42109e-14 2,
+                          18.5 -38.5 -6.66134e-16,
+                          -18.5 -38.5 2,
+                          -18.5 -38.5 -2.66454e-15,
+                          18.1445 3.60918 2,
+                          -18.1445 3.60918 2,
+                          -18.5 -1.42109e-14 2,
+                          -18.5 -1.42109e-14 1.11022e-15,
+                          -18.5 -1.42109e-14 2,
+                          -18.1445 3.60918 2,
+                          -18.5 -38.5 -2.66454e-15,
+                          -18.5 -1.42109e-14 2,
+                          -18.5 -1.42109e-14 1.11022e-15,
+                          17.0918 7.07962 2,
+                          -17.0918 7.07962 2,
+                          -18.1445 3.60918 2,
+                          -18.1445 3.60918 1.33227e-15,
+                          -18.1445 3.60918 2,
+                          -17.0918 7.07962 2,
+                          18.1445 3.60918 2,
+                          17.0918 7.07962 2,
+                          -18.1445 3.60918 2,
+                          -18.1445 3.60918 1.33227e-15,
+                          -18.5 -1.42109e-14 1.11022e-15,
+                          -18.1445 3.60918 2,
+                          15.3822 10.2781 2,
+                          -15.3822 10.2781 2,
+                          -17.0918 7.07962 2,
+                          -17.0918 7.07962 1.77636e-15,
+                          -17.0918 7.07962 2,
+                          -15.3822 10.2781 2,
+                          17.0918 7.07962 2,
+                          15.3822 10.2781 2,
+                          -17.0918 7.07962 2,
+                          -18.1445 3.60918 1.33227e-15,
+                          -17.0918 7.07962 2,
+                          -17.0918 7.07962 1.77636e-15,
+                          13.0815 13.0815 2,
+                          -13.0815 13.0815 2,
+                          -15.3822 10.2781 2,
+                          -15.3822 10.2781 2.22045e-15,
+                          -15.3822 10.2781 2,
+                          -13.0815 13.0815 2,
+                          15.3822 10.2781 2,
+                          13.0815 13.0815 2,
+                          -15.3822 10.2781 2,
+                          -17.0918 7.07962 1.77636e-15,
+                          -15.3822 10.2781 2,
+                          -15.3822 10.2781 2.22045e-15,
+                          10.2781 15.3822 2,
+                          -10.2781 15.3822 2,
+                          -13.0815 13.0815 2,
+                          -13.0815 13.0815 2.66454e-15,
+                          -13.0815 13.0815 2,
+                          -10.2781 15.3822 2,
+                          13.0815 13.0815 2,
+                          10.2781 15.3822 2,
+                          -13.0815 13.0815 2,
+                          -15.3822 10.2781 2.22045e-15,
+                          -13.0815 13.0815 2,
+                          -13.0815 13.0815 2.66454e-15,
+                          7.07962 17.0918 2,
+                          -7.07962 17.0918 2,
+                          -10.2781 15.3822 2,
+                          -10.2781 15.3822 2.88658e-15,
+                          -10.2781 15.3822 2,
+                          -7.07962 17.0918 2,
+                          10.2781 15.3822 2,
+                          7.07962 17.0918 2,
+                          -10.2781 15.3822 2,
+                          -13.0815 13.0815 2.66454e-15,
+                          -10.2781 15.3822 2,
+                          -10.2781 15.3822 2.88658e-15,
+                          3.60918 18.1445 2,
+                          -3.60918 18.1445 2,
+                          -7.07962 17.0918 2,
+                          -7.07962 17.0918 3.33067e-15,
+                          -7.07962 17.0918 2,
+                          -3.60918 18.1445 2,
+                          7.07962 17.0918 2,
+                          3.60918 18.1445 2,
+                          -7.07962 17.0918 2,
+                          -10.2781 15.3822 2.88658e-15,
+                          -7.07962 17.0918 2,
+                          -7.07962 17.0918 3.33067e-15,
+                          3.60918 18.1445 2,
+                          -2.4869e-14 18.5 2,
+                          -3.60918 18.1445 2,
+                          -3.60918 18.1445 3.55271e-15,
+                          -3.60918 18.1445 2,
+                          -2.4869e-14 18.5 2,
+                          -7.07962 17.0918 3.33067e-15,
+                          -3.60918 18.1445 2,
+                          -3.60918 18.1445 3.55271e-15,
+                          -3.55271e-15 18.5 3.77476e-15,
+                          -2.4869e-14 18.5 2,
+                          3.60918 18.1445 2,
+                          -3.60918 18.1445 3.55271e-15,
+                          -2.4869e-14 18.5 2,
+                          -3.55271e-15 18.5 3.77476e-15,
+                          3.60918 18.1445 3.9968e-15,
+                          3.60918 18.1445 2,
+                          7.07962 17.0918 2,
+                          -3.55271e-15 18.5 3.77476e-15,
+                          3.60918 18.1445 2,
+                          3.60918 18.1445 3.9968e-15,
+                          7.07962 17.0918 3.9968e-15,
+                          7.07962 17.0918 2,
+                          10.2781 15.3822 2,
+                          3.60918 18.1445 3.9968e-15,
+                          7.07962 17.0918 2,
+                          7.07962 17.0918 3.9968e-15,
+                          10.2781 15.3822 3.9968e-15,
+                          10.2781 15.3822 2,
+                          13.0815 13.0815 2,
+                          7.07962 17.0918 3.9968e-15,
+                          10.2781 15.3822 2,
+                          10.2781 15.3822 3.9968e-15,
+                          13.0815 13.0815 3.9968e-15,
+                          13.0815 13.0815 2,
+                          15.3822 10.2781 2,
+                          10.2781 15.3822 3.9968e-15,
+                          13.0815 13.0815 2,
+                          13.0815 13.0815 3.9968e-15,
+                          15.3822 10.2781 3.77476e-15,
+                          15.3822 10.2781 2,
+                          17.0918 7.07962 2,
+                          13.0815 13.0815 3.9968e-15,
+                          15.3822 10.2781 2,
+                          15.3822 10.2781 3.77476e-15,
+                          17.0918 7.07962 3.55271e-15,
+                          17.0918 7.07962 2,
+                          18.1445 3.60918 2,
+                          15.3822 10.2781 3.77476e-15,
+                          17.0918 7.07962 2,
+                          17.0918 7.07962 3.55271e-15,
+                          17.0918 7.07962 3.55271e-15,
+                          18.1445 3.60918 2,
+                          18.1445 3.60918 3.33067e-15,
+                          18.5 -38.5 -6.66134e-16,
+                          -18.5 -38.5 -2.66454e-15,
+                          -18.5 -1.42109e-14 1.11022e-15,
+                          18.5 -1.42109e-14 3.10862e-15,
+                          18.5 -38.5 -6.66134e-16,
+                          -18.5 -1.42109e-14 1.11022e-15,
+                          -18.1445 3.60918 1.33227e-15,
+                          18.5 -1.42109e-14 3.10862e-15,
+                          -18.5 -1.42109e-14 1.11022e-15,
+                          -18.1445 3.60918 1.33227e-15,
+                          18.1445 3.60918 3.33067e-15,
+                          18.5 -1.42109e-14 3.10862e-15,
+                          -17.0918 7.07962 1.77636e-15,
+                          17.0918 7.07962 3.55271e-15,
+                          18.1445 3.60918 3.33067e-15,
+                          -18.1445 3.60918 1.33227e-15,
+                          -17.0918 7.07962 1.77636e-15,
+                          18.1445 3.60918 3.33067e-15,
+                          -15.3822 10.2781 2.22045e-15,
+                          15.3822 10.2781 3.77476e-15,
+                          17.0918 7.07962 3.55271e-15,
+                          -17.0918 7.07962 1.77636e-15,
+                          -15.3822 10.2781 2.22045e-15,
+                          17.0918 7.07962 3.55271e-15,
+                          -13.0815 13.0815 2.66454e-15,
+                          13.0815 13.0815 3.9968e-15,
+                          15.3822 10.2781 3.77476e-15,
+                          -15.3822 10.2781 2.22045e-15,
+                          -13.0815 13.0815 2.66454e-15,
+                          15.3822 10.2781 3.77476e-15,
+                          -10.2781 15.3822 2.88658e-15,
+                          10.2781 15.3822 3.9968e-15,
+                          13.0815 13.0815 3.9968e-15,
+                          -13.0815 13.0815 2.66454e-15,
+                          -10.2781 15.3822 2.88658e-15,
+                          13.0815 13.0815 3.9968e-15,
+                          -7.07962 17.0918 3.33067e-15,
+                          7.07962 17.0918 3.9968e-15,
+                          10.2781 15.3822 3.9968e-15,
+                          -10.2781 15.3822 2.88658e-15,
+                          -7.07962 17.0918 3.33067e-15,
+                          10.2781 15.3822 3.9968e-15,
+                          -3.60918 18.1445 3.55271e-15,
+                          3.60918 18.1445 3.9968e-15,
+                          7.07962 17.0918 3.9968e-15,
+                          -7.07962 17.0918 3.33067e-15,
+                          -3.60918 18.1445 3.55271e-15,
+                          7.07962 17.0918 3.9968e-15,
+                          -3.60918 18.1445 3.55271e-15,
+                          -3.55271e-15 18.5 3.77476e-15,
+                          3.60918 18.1445 3.9968e-15 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+    Separator {
+        Normal {
+            vector      [ -5.87863e-14 8.3786e-14 -1,
+                          -5.87863e-14 8.3786e-14 -1,
+                          -5.87863e-14 8.3786e-14 -1,
+                          -0.866025 0.5 9.25787e-14,
+                          -0.866025 0.5 9.25787e-14,
+                          -0.866025 0.5 9.25787e-14,
+                          -5.87863e-14 8.3786e-14 -1,
+                          -5.87863e-14 8.3786e-14 -1,
+                          -5.87863e-14 8.3786e-14 -1,
+                          1.26656e-16 1 8.39134e-14,
+                          1.26656e-16 1 8.39134e-14,
+                          1.26656e-16 1 8.39134e-14,
+                          -0.866025 0.5 9.25787e-14,
+                          -0.866025 0.5 9.25787e-14,
+                          -0.866025 0.5 9.25787e-14,
+                          -0.866025 -0.5 8.66528e-15,
+                          -0.866025 -0.5 8.66528e-15,
+                          -0.866025 -0.5 8.66528e-15,
+                          -0.866025 -0.5 8.66528e-15,
+                          -0.866025 -0.5 8.66528e-15,
+                          -0.866025 -0.5 8.66528e-15,
+                          -5.87863e-14 8.3786e-14 -1,
+                          -5.87863e-14 8.3786e-14 -1,
+                          -5.87863e-14 8.3786e-14 -1,
+                          -1.26656e-16 -1 -8.39134e-14,
+                          -1.26656e-16 -1 -8.39134e-14,
+                          -1.26656e-16 -1 -8.39134e-14,
+                          -1.26656e-16 -1 -8.39134e-14,
+                          -1.26656e-16 -1 -8.39134e-14,
+                          -1.26656e-16 -1 -8.39134e-14,
+                          -5.87863e-14 8.3786e-14 -1,
+                          -5.87863e-14 8.3786e-14 -1,
+                          -5.87863e-14 8.3786e-14 -1,
+                          0.866025 -0.5 -9.25787e-14,
+                          0.866025 -0.5 -9.25787e-14,
+                          0.866025 -0.5 -9.25787e-14,
+                          0.866025 -0.5 -9.25787e-14,
+                          0.866025 -0.5 -9.25787e-14,
+                          0.866025 -0.5 -9.25787e-14,
+                          0.866025 0.5 -8.66528e-15,
+                          0.866025 0.5 -8.66528e-15,
+                          0.866025 0.5 -8.66528e-15,
+                          0.866025 0.5 -8.66528e-15,
+                          0.866025 0.5 -8.66528e-15,
+                          0.866025 0.5 -8.66528e-15,
+                          1.26656e-16 1 8.39134e-14,
+                          1.26656e-16 1 8.39134e-14,
+                          1.26656e-16 1 8.39134e-14,
+                          5.87863e-14 -8.3786e-14 1,
+                          5.87863e-14 -8.3786e-14 1,
+                          5.87863e-14 -8.3786e-14 1,
+                          5.87863e-14 -8.3786e-14 1,
+                          5.87863e-14 -8.3786e-14 1,
+                          5.87863e-14 -8.3786e-14 1,
+                          5.87863e-14 -8.3786e-14 1,
+                          5.87863e-14 -8.3786e-14 1,
+                          5.87863e-14 -8.3786e-14 1,
+                          5.87863e-14 -8.3786e-14 1,
+                          5.87863e-14 -8.3786e-14 1,
+                          5.87863e-14 -8.3786e-14 1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 12.125 -35.8816 2,
+                          10.75 -33.5 2,
+                          12.125 -31.1184 2,
+                          10.75 -33.5 27,
+                          12.125 -31.1184 2,
+                          10.75 -33.5 2,
+                          14.875 -31.1184 2,
+                          12.125 -35.8816 2,
+                          12.125 -31.1184 2,
+                          12.125 -31.1184 27,
+                          14.875 -31.1184 2,
+                          12.125 -31.1184 2,
+                          10.75 -33.5 27,
+                          12.125 -31.1184 27,
+                          12.125 -31.1184 2,
+                          12.125 -35.8816 27,
+                          10.75 -33.5 2,
+                          12.125 -35.8816 2,
+                          10.75 -33.5 27,
+                          10.75 -33.5 2,
+                          12.125 -35.8816 27,
+                          14.875 -31.1184 2,
+                          14.875 -35.8816 2,
+                          12.125 -35.8816 2,
+                          14.875 -35.8816 27,
+                          12.125 -35.8816 2,
+                          14.875 -35.8816 2,
+                          12.125 -35.8816 27,
+                          12.125 -35.8816 2,
+                          14.875 -35.8816 27,
+                          14.875 -31.1184 2,
+                          16.25 -33.5 2,
+                          14.875 -35.8816 2,
+                          16.25 -33.5 27,
+                          14.875 -35.8816 2,
+                          16.25 -33.5 2,
+                          14.875 -35.8816 27,
+                          14.875 -35.8816 2,
+                          16.25 -33.5 27,
+                          14.875 -31.1184 27,
+                          16.25 -33.5 2,
+                          14.875 -31.1184 2,
+                          16.25 -33.5 27,
+                          16.25 -33.5 2,
+                          14.875 -31.1184 27,
+                          14.875 -31.1184 27,
+                          14.875 -31.1184 2,
+                          12.125 -31.1184 27,
+                          14.875 -35.8816 27,
+                          14.875 -31.1184 27,
+                          12.125 -31.1184 27,
+                          12.125 -35.8816 27,
+                          14.875 -35.8816 27,
+                          12.125 -31.1184 27,
+                          10.75 -33.5 27,
+                          12.125 -35.8816 27,
+                          12.125 -31.1184 27,
+                          14.875 -35.8816 27,
+                          16.25 -33.5 27,
+                          14.875 -31.1184 27 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ -5.86198e-14 8.39296e-14 1,
+                          -5.86198e-14 8.39296e-14 1,
+                          -5.86198e-14 8.39296e-14 1,
+                          -0.866025 -0.5 -9.25181e-14,
+                          -0.866025 -0.5 -9.25181e-14,
+                          -0.866025 -0.5 -9.25181e-14,
+                          -5.86198e-14 8.39296e-14 1,
+                          -5.86198e-14 8.39296e-14 1,
+                          -5.86198e-14 8.39296e-14 1,
+                          1.32104e-16 -1 -8.40807e-14,
+                          1.32104e-16 -1 -8.40807e-14,
+                          1.32104e-16 -1 -8.40807e-14,
+                          -0.866025 -0.5 -9.25181e-14,
+                          -0.866025 -0.5 -9.25181e-14,
+                          -0.866025 -0.5 -9.25181e-14,
+                          -0.866025 0.5 -8.43743e-15,
+                          -0.866025 0.5 -8.43743e-15,
+                          -0.866025 0.5 -8.43743e-15,
+                          -0.866025 0.5 -8.43743e-15,
+                          -0.866025 0.5 -8.43743e-15,
+                          -0.866025 0.5 -8.43743e-15,
+                          -5.86198e-14 8.39296e-14 1,
+                          -5.86198e-14 8.39296e-14 1,
+                          -5.86198e-14 8.39296e-14 1,
+                          -1.32104e-16 1 8.40807e-14,
+                          -1.32104e-16 1 8.40807e-14,
+                          -1.32104e-16 1 8.40807e-14,
+                          -1.32104e-16 1 8.40807e-14,
+                          -1.32104e-16 1 8.40807e-14,
+                          -1.32104e-16 1 8.40807e-14,
+                          -5.86198e-14 8.39296e-14 1,
+                          -5.86198e-14 8.39296e-14 1,
+                          -5.86198e-14 8.39296e-14 1,
+                          0.866025 0.5 9.25181e-14,
+                          0.866025 0.5 9.25181e-14,
+                          0.866025 0.5 9.25181e-14,
+                          0.866025 0.5 9.25181e-14,
+                          0.866025 0.5 9.25181e-14,
+                          0.866025 0.5 9.25181e-14,
+                          0.866025 -0.5 8.43743e-15,
+                          0.866025 -0.5 8.43743e-15,
+                          0.866025 -0.5 8.43743e-15,
+                          0.866025 -0.5 8.43743e-15,
+                          0.866025 -0.5 8.43743e-15,
+                          0.866025 -0.5 8.43743e-15,
+                          1.32104e-16 -1 -8.40807e-14,
+                          1.32104e-16 -1 -8.40807e-14,
+                          1.32104e-16 -1 -8.40807e-14,
+                          5.86198e-14 -8.39296e-14 -1,
+                          5.86198e-14 -8.39296e-14 -1,
+                          5.86198e-14 -8.39296e-14 -1,
+                          5.86198e-14 -8.39296e-14 -1,
+                          5.86198e-14 -8.39296e-14 -1,
+                          5.86198e-14 -8.39296e-14 -1,
+                          5.86198e-14 -8.39296e-14 -1,
+                          5.86198e-14 -8.39296e-14 -1,
+                          5.86198e-14 -8.39296e-14 -1,
+                          5.86198e-14 -8.39296e-14 -1,
+                          5.86198e-14 -8.39296e-14 -1,
+                          5.86198e-14 -8.39296e-14 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -1.375 -12.1184 27,
+                          -2.75 -14.5 27,
+                          -1.375 -16.8816 27,
+                          -2.75 -14.5 2,
+                          -1.375 -16.8816 27,
+                          -2.75 -14.5 27,
+                          1.375 -16.8816 27,
+                          -1.375 -12.1184 27,
+                          -1.375 -16.8816 27,
+                          -1.375 -16.8816 2,
+                          1.375 -16.8816 27,
+                          -1.375 -16.8816 27,
+                          -2.75 -14.5 2,
+                          -1.375 -16.8816 2,
+                          -1.375 -16.8816 27,
+                          -1.375 -12.1184 2,
+                          -2.75 -14.5 27,
+                          -1.375 -12.1184 27,
+                          -2.75 -14.5 2,
+                          -2.75 -14.5 27,
+                          -1.375 -12.1184 2,
+                          1.375 -16.8816 27,
+                          1.375 -12.1184 27,
+                          -1.375 -12.1184 27,
+                          1.375 -12.1184 2,
+                          -1.375 -12.1184 27,
+                          1.375 -12.1184 27,
+                          -1.375 -12.1184 2,
+                          -1.375 -12.1184 27,
+                          1.375 -12.1184 2,
+                          1.375 -16.8816 27,
+                          2.75 -14.5 27,
+                          1.375 -12.1184 27,
+                          2.75 -14.5 2,
+                          1.375 -12.1184 27,
+                          2.75 -14.5 27,
+                          1.375 -12.1184 2,
+                          1.375 -12.1184 27,
+                          2.75 -14.5 2,
+                          1.375 -16.8816 2,
+                          2.75 -14.5 27,
+                          1.375 -16.8816 27,
+                          2.75 -14.5 2,
+                          2.75 -14.5 27,
+                          1.375 -16.8816 2,
+                          1.375 -16.8816 2,
+                          1.375 -16.8816 27,
+                          -1.375 -16.8816 2,
+                          1.375 -12.1184 2,
+                          1.375 -16.8816 2,
+                          -1.375 -16.8816 2,
+                          -1.375 -12.1184 2,
+                          1.375 -12.1184 2,
+                          -1.375 -16.8816 2,
+                          -2.75 -14.5 2,
+                          -1.375 -12.1184 2,
+                          -1.375 -16.8816 2,
+                          1.375 -12.1184 2,
+                          2.75 -14.5 2,
+                          1.375 -16.8816 2 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ -5.87863e-14 -8.40968e-14 -1,
+                          -5.87863e-14 -8.40968e-14 -1,
+                          -5.87863e-14 -8.40968e-14 -1,
+                          -0.866025 0.5 1.7652e-13,
+                          -0.866025 0.5 1.7652e-13,
+                          -0.866025 0.5 1.7652e-13,
+                          -5.87863e-14 -8.40968e-14 -1,
+                          -5.87863e-14 -8.40968e-14 -1,
+                          -5.87863e-14 -8.40968e-14 -1,
+                          1.30969e-16 1 2.51796e-13,
+                          1.30969e-16 1 2.51796e-13,
+                          1.30969e-16 1 2.51796e-13,
+                          -0.866025 0.5 1.7652e-13,
+                          -0.866025 0.5 1.7652e-13,
+                          -0.866025 0.5 1.7652e-13,
+                          -0.866025 -0.5 -7.52761e-14,
+                          -0.866025 -0.5 -7.52761e-14,
+                          -0.866025 -0.5 -7.52761e-14,
+                          -0.866025 -0.5 -7.52761e-14,
+                          -0.866025 -0.5 -7.52761e-14,
+                          -0.866025 -0.5 -7.52761e-14,
+                          -5.87863e-14 -8.40968e-14 -1,
+                          -5.87863e-14 -8.40968e-14 -1,
+                          -5.87863e-14 -8.40968e-14 -1,
+                          -1.30969e-16 -1 -2.51796e-13,
+                          -1.30969e-16 -1 -2.51796e-13,
+                          -1.30969e-16 -1 -2.51796e-13,
+                          -1.30969e-16 -1 -2.51796e-13,
+                          -1.30969e-16 -1 -2.51796e-13,
+                          -1.30969e-16 -1 -2.51796e-13,
+                          -5.87863e-14 -8.40968e-14 -1,
+                          -5.87863e-14 -8.40968e-14 -1,
+                          -5.87863e-14 -8.40968e-14 -1,
+                          0.866025 -0.5 -1.7652e-13,
+                          0.866025 -0.5 -1.7652e-13,
+                          0.866025 -0.5 -1.7652e-13,
+                          0.866025 -0.5 -1.7652e-13,
+                          0.866025 -0.5 -1.7652e-13,
+                          0.866025 -0.5 -1.7652e-13,
+                          0.866025 0.5 7.52761e-14,
+                          0.866025 0.5 7.52761e-14,
+                          0.866025 0.5 7.52761e-14,
+                          0.866025 0.5 7.52761e-14,
+                          0.866025 0.5 7.52761e-14,
+                          0.866025 0.5 7.52761e-14,
+                          1.30969e-16 1 2.51796e-13,
+                          1.30969e-16 1 2.51796e-13,
+                          1.30969e-16 1 2.51796e-13,
+                          5.87863e-14 8.40968e-14 1,
+                          5.87863e-14 8.40968e-14 1,
+                          5.87863e-14 8.40968e-14 1,
+                          5.87863e-14 8.40968e-14 1,
+                          5.87863e-14 8.40968e-14 1,
+                          5.87863e-14 8.40968e-14 1,
+                          5.87863e-14 8.40968e-14 1,
+                          5.87863e-14 8.40968e-14 1,
+                          5.87863e-14 8.40968e-14 1,
+                          5.87863e-14 8.40968e-14 1,
+                          5.87863e-14 8.40968e-14 1,
+                          5.87863e-14 8.40968e-14 1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -14.875 -35.8816 2,
+                          -16.25 -33.5 2,
+                          -14.875 -31.1184 2,
+                          -16.25 -33.5 27,
+                          -14.875 -31.1184 2,
+                          -16.25 -33.5 2,
+                          -12.125 -31.1184 2,
+                          -14.875 -35.8816 2,
+                          -14.875 -31.1184 2,
+                          -14.875 -31.1184 27,
+                          -12.125 -31.1184 2,
+                          -14.875 -31.1184 2,
+                          -16.25 -33.5 27,
+                          -14.875 -31.1184 27,
+                          -14.875 -31.1184 2,
+                          -14.875 -35.8816 27,
+                          -16.25 -33.5 2,
+                          -14.875 -35.8816 2,
+                          -16.25 -33.5 27,
+                          -16.25 -33.5 2,
+                          -14.875 -35.8816 27,
+                          -12.125 -31.1184 2,
+                          -12.125 -35.8816 2,
+                          -14.875 -35.8816 2,
+                          -12.125 -35.8816 27,
+                          -14.875 -35.8816 2,
+                          -12.125 -35.8816 2,
+                          -14.875 -35.8816 27,
+                          -14.875 -35.8816 2,
+                          -12.125 -35.8816 27,
+                          -12.125 -31.1184 2,
+                          -10.75 -33.5 2,
+                          -12.125 -35.8816 2,
+                          -10.75 -33.5 27,
+                          -12.125 -35.8816 2,
+                          -10.75 -33.5 2,
+                          -12.125 -35.8816 27,
+                          -12.125 -35.8816 2,
+                          -10.75 -33.5 27,
+                          -12.125 -31.1184 27,
+                          -10.75 -33.5 2,
+                          -12.125 -31.1184 2,
+                          -10.75 -33.5 27,
+                          -10.75 -33.5 2,
+                          -12.125 -31.1184 27,
+                          -12.125 -31.1184 27,
+                          -12.125 -31.1184 2,
+                          -14.875 -31.1184 27,
+                          -12.125 -35.8816 27,
+                          -12.125 -31.1184 27,
+                          -14.875 -31.1184 27,
+                          -14.875 -35.8816 27,
+                          -12.125 -35.8816 27,
+                          -14.875 -31.1184 27,
+                          -16.25 -33.5 27,
+                          -14.875 -35.8816 27,
+                          -14.875 -31.1184 27,
+                          -12.125 -35.8816 27,
+                          -10.75 -33.5 27,
+                          -12.125 -31.1184 27 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/palm1_r.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/palm1_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..25d3c3664dbad1e16d8d0cd2ddf65d24be14f05b
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/palm1_r.iv
@@ -0,0 +1,4267 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+    Separator {
+        Normal {
+            vector      [ 1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          5.84532e-14 -8.3919e-14 -1,
+                          5.84532e-14 -8.3919e-14 -1,
+                          5.84532e-14 -8.3919e-14 -1,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          -1.00149e-12 1 -8.38357e-14,
+                          -1.00149e-12 1 -8.38357e-14,
+                          -1.00149e-12 1 -8.38357e-14,
+                          -1.00149e-12 1 -8.38357e-14,
+                          -1.00149e-12 1 -8.38357e-14,
+                          -1.00149e-12 1 -8.38357e-14,
+                          0.707107 -0.707107 1.00574e-13,
+                          0.707107 -0.707107 1.00574e-13,
+                          0.707107 -0.707107 1.00574e-13,
+                          5.84532e-14 -8.3919e-14 -1,
+                          5.84532e-14 -8.3919e-14 -1,
+                          5.84532e-14 -8.3919e-14 -1,
+                          5.84532e-14 -8.3919e-14 -1,
+                          5.84532e-14 -8.3919e-14 -1,
+                          5.84532e-14 -8.3919e-14 -1,
+                          5.84532e-14 -8.3919e-14 -1,
+                          5.84532e-14 -8.3919e-14 -1,
+                          5.84532e-14 -8.3919e-14 -1,
+                          5.84532e-14 -8.3919e-14 -1,
+                          5.84532e-14 -8.3919e-14 -1,
+                          5.84532e-14 -8.3919e-14 -1,
+                          -5.84532e-14 8.3919e-14 1,
+                          -5.84532e-14 8.3919e-14 1,
+                          -5.84532e-14 8.3919e-14 1,
+                          0.707107 -0.707107 1.00574e-13,
+                          0.707107 -0.707107 1.00574e-13,
+                          0.707107 -0.707107 1.00574e-13,
+                          -5.84532e-14 8.3919e-14 1,
+                          -5.84532e-14 8.3919e-14 1,
+                          -5.84532e-14 8.3919e-14 1,
+                          -5.84532e-14 8.3919e-14 1,
+                          -5.84532e-14 8.3919e-14 1,
+                          -5.84532e-14 8.3919e-14 1,
+                          -5.84532e-14 8.3919e-14 1,
+                          -5.84532e-14 8.3919e-14 1,
+                          -5.84532e-14 8.3919e-14 1,
+                          -1.00149e-12 1 -8.38357e-14,
+                          -1.00149e-12 1 -8.38357e-14,
+                          -1.00149e-12 1 -8.38357e-14,
+                          -5.84532e-14 8.3919e-14 1,
+                          -5.84532e-14 8.3919e-14 1,
+                          -5.84532e-14 8.3919e-14 1,
+                          -1.00149e-12 1 -8.38357e-14,
+                          -1.00149e-12 1 -8.38357e-14,
+                          -1.00149e-12 1 -8.38357e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          -5.84532e-14 8.3919e-14 1,
+                          -5.84532e-14 8.3919e-14 1,
+                          -5.84532e-14 8.3919e-14 1,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          5.84532e-14 -8.3919e-14 -1,
+                          5.84532e-14 -8.3919e-14 -1,
+                          5.84532e-14 -8.3919e-14 -1,
+                          5.84532e-14 -8.3919e-14 -1,
+                          5.84532e-14 -8.3919e-14 -1,
+                          5.84532e-14 -8.3919e-14 -1,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          -1.00149e-12 1 -8.38357e-14,
+                          -1.00149e-12 1 -8.38357e-14,
+                          -1.00149e-12 1 -8.38357e-14,
+                          -1.00149e-12 1 -8.38357e-14,
+                          -1.00149e-12 1 -8.38357e-14,
+                          -1.00149e-12 1 -8.38357e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          5.84532e-14 -8.3919e-14 -1,
+                          5.84532e-14 -8.3919e-14 -1,
+                          5.84532e-14 -8.3919e-14 -1,
+                          -0.707107 -0.707107 1.79874e-14,
+                          -0.707107 -0.707107 1.79874e-14,
+                          -0.707107 -0.707107 1.79874e-14,
+                          -0.707107 -0.707107 1.79874e-14,
+                          -0.707107 -0.707107 1.79874e-14,
+                          -0.707107 -0.707107 1.79874e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          1.00149e-12 -1 8.38357e-14,
+                          1.00149e-12 -1 8.38357e-14,
+                          1.00149e-12 -1 8.38357e-14,
+                          1.00149e-12 -1 8.38357e-14,
+                          1.00149e-12 -1 8.38357e-14,
+                          1.00149e-12 -1 8.38357e-14,
+                          -5.84532e-14 8.3919e-14 1,
+                          -5.84532e-14 8.3919e-14 1,
+                          -5.84532e-14 8.3919e-14 1,
+                          -5.84532e-14 8.3919e-14 1,
+                          -5.84532e-14 8.3919e-14 1,
+                          -5.84532e-14 8.3919e-14 1,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          -1 -1.00132e-12 -5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1 1.00132e-12 5.83977e-14,
+                          1.00149e-12 -1 8.38357e-14,
+                          1.00149e-12 -1 8.38357e-14,
+                          8.9654e-13 -0.866025 -0.5,
+                          8.38087e-13 -0.866025 0.5,
+                          8.38087e-13 -0.866025 0.5,
+                          1.00149e-12 -1 8.40806e-14,
+                          8.38087e-13 -0.866025 0.5,
+                          1.00149e-12 -1 8.40806e-14,
+                          1.00149e-12 -1 8.40806e-14,
+                          8.9654e-13 -0.866025 -0.5,
+                          8.9654e-13 -0.866025 -0.5,
+                          5.51366e-13 -0.5 -0.866025,
+                          8.9654e-13 -0.866025 -0.5,
+                          1.00149e-12 -1 8.38357e-14,
+                          8.9654e-13 -0.866025 -0.5,
+                          5.51366e-13 -0.5 -0.866025,
+                          5.51366e-13 -0.5 -0.866025,
+                          5.84532e-14 -8.57566e-14 -1,
+                          8.9654e-13 -0.866025 -0.5,
+                          5.51366e-13 -0.5 -0.866025,
+                          5.51366e-13 -0.5 -0.866025,
+                          5.84532e-14 -8.55345e-14 -1,
+                          5.84532e-14 -8.57566e-14 -1,
+                          -4.50122e-13 0.5 -0.866025,
+                          5.51366e-13 -0.5 -0.866025,
+                          5.84532e-14 -8.57566e-14 -1,
+                          5.84532e-14 -8.55345e-14 -1,
+                          -4.50122e-13 0.5 -0.866025,
+                          -4.50122e-13 0.5 -0.866025,
+                          -8.38087e-13 0.866025 -0.5,
+                          5.84532e-14 -8.55345e-14 -1,
+                          -4.50122e-13 0.5 -0.866025,
+                          -4.50122e-13 0.5 -0.866025,
+                          -8.38087e-13 0.866025 -0.5,
+                          -8.38087e-13 0.866025 -0.5,
+                          -1.00149e-12 1 -8.39582e-14,
+                          -4.50122e-13 0.5 -0.866025,
+                          -8.38087e-13 0.866025 -0.5,
+                          -8.38087e-13 0.866025 -0.5,
+                          -1.00149e-12 1 -8.39582e-14,
+                          -1.00149e-12 1 -8.39582e-14,
+                          -8.9654e-13 0.866025 0.5,
+                          -8.38087e-13 0.866025 -0.5,
+                          -1.00149e-12 1 -8.39582e-14,
+                          -1.00149e-12 1 -8.39582e-14,
+                          -8.9654e-13 0.866025 0.5,
+                          -8.9654e-13 0.866025 0.5,
+                          -5.51366e-13 0.5 0.866025,
+                          -1.00149e-12 1 -8.39582e-14,
+                          -8.9654e-13 0.866025 0.5,
+                          -8.9654e-13 0.866025 0.5,
+                          -5.51366e-13 0.5 0.866025,
+                          -5.51366e-13 0.5 0.866025,
+                          -5.84532e-14 8.5879e-14 1,
+                          -8.9654e-13 0.866025 0.5,
+                          -5.51366e-13 0.5 0.866025,
+                          -5.51366e-13 0.5 0.866025,
+                          -5.84532e-14 8.5879e-14 1,
+                          -5.84532e-14 8.5879e-14 1,
+                          4.50122e-13 -0.5 0.866025,
+                          -5.51366e-13 0.5 0.866025,
+                          -5.84532e-14 8.5879e-14 1,
+                          -5.84532e-14 8.5879e-14 1,
+                          4.50122e-13 -0.5 0.866025,
+                          4.50122e-13 -0.5 0.866025,
+                          8.38087e-13 -0.866025 0.5,
+                          -5.84532e-14 8.5879e-14 1,
+                          4.50122e-13 -0.5 0.866025,
+                          4.50122e-13 -0.5 0.866025,
+                          4.50122e-13 -0.5 0.866025,
+                          8.38087e-13 -0.866025 0.5,
+                          8.38087e-13 -0.866025 0.5 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -8.5 -42.1 -27,
+                          -8.5 -42.1 -31.5,
+                          -8.5 -11.1 -31.5,
+                          -11.2 -11.1 -31.5,
+                          -8.5 -11.1 -31.5,
+                          -8.5 -42.1 -31.5,
+                          -8.5 -11.1 -27,
+                          -8.5 -42.1 -27,
+                          -8.5 -11.1 -31.5,
+                          -11.2 -11.1 -27,
+                          -8.5 -11.1 -27,
+                          -8.5 -11.1 -31.5,
+                          -11.2 -11.1 -27,
+                          -8.5 -11.1 -31.5,
+                          -11.2 -11.1 -31.5,
+                          -11.5 -45.1 -31.5,
+                          -8.5 -42.1 -31.5,
+                          -8.5 -42.1 -27,
+                          -15.8 -11.1 -31.5,
+                          -11.2 -11.1 -31.5,
+                          -8.5 -42.1 -31.5,
+                          -18.5 -11.1 -31.5,
+                          -15.8 -11.1 -31.5,
+                          -8.5 -42.1 -31.5,
+                          -18.5 -42.1 -31.5,
+                          -18.5 -11.1 -31.5,
+                          -8.5 -42.1 -31.5,
+                          -11.5 -45.1 -31.5,
+                          -18.5 -42.1 -31.5,
+                          -8.5 -42.1 -31.5,
+                          -18.5 -42.1 -27,
+                          -8.5 -42.1 -27,
+                          -8.5 -11.1 -27,
+                          -11.5 -45.1 -27,
+                          -11.5 -45.1 -31.5,
+                          -8.5 -42.1 -27,
+                          -15.5 -45.1 -27,
+                          -11.5 -45.1 -27,
+                          -8.5 -42.1 -27,
+                          -18.5 -42.1 -27,
+                          -15.5 -45.1 -27,
+                          -8.5 -42.1 -27,
+                          -11.2 -11.1 -27,
+                          -18.5 -42.1 -27,
+                          -8.5 -11.1 -27,
+                          -15.8 -6.45 -31.5,
+                          -15.8 -6.45 -27,
+                          -11.2 -6.45 -27,
+                          -15.8 -11.1 -27,
+                          -11.2 -6.45 -27,
+                          -15.8 -6.45 -27,
+                          -11.2 -6.45 -31.5,
+                          -15.8 -6.45 -31.5,
+                          -11.2 -6.45 -27,
+                          -11.2 -7.61747 -28.625,
+                          -11.2 -6.45 -31.5,
+                          -11.2 -6.45 -27,
+                          -11.2 -11.1 -27,
+                          -11.2 -6.45 -27,
+                          -15.8 -11.1 -27,
+                          -11.2 -8.075 -28.1675,
+                          -11.2 -6.45 -27,
+                          -11.2 -11.1 -27,
+                          -11.2 -8.075 -28.1675,
+                          -11.2 -7.61747 -28.625,
+                          -11.2 -6.45 -27,
+                          -15.8 -7.61747 -29.875,
+                          -15.8 -6.45 -27,
+                          -15.8 -6.45 -31.5,
+                          -15.8 -9.325 -28.1675,
+                          -15.8 -11.1 -27,
+                          -15.8 -6.45 -27,
+                          -15.8 -7.61747 -29.875,
+                          -15.8 -7.45 -29.25,
+                          -15.8 -6.45 -27,
+                          -15.8 -7.61747 -28.625,
+                          -15.8 -6.45 -27,
+                          -15.8 -7.45 -29.25,
+                          -15.8 -8.7 -28,
+                          -15.8 -9.325 -28.1675,
+                          -15.8 -6.45 -27,
+                          -15.8 -8.075 -28.1675,
+                          -15.8 -8.7 -28,
+                          -15.8 -6.45 -27,
+                          -15.8 -7.61747 -28.625,
+                          -15.8 -8.075 -28.1675,
+                          -15.8 -6.45 -27,
+                          -11.2 -11.1 -31.5,
+                          -15.8 -6.45 -31.5,
+                          -11.2 -6.45 -31.5,
+                          -15.8 -11.1 -31.5,
+                          -15.8 -6.45 -31.5,
+                          -11.2 -11.1 -31.5,
+                          -15.8 -8.075 -30.3325,
+                          -15.8 -6.45 -31.5,
+                          -15.8 -11.1 -31.5,
+                          -15.8 -8.075 -30.3325,
+                          -15.8 -7.61747 -29.875,
+                          -15.8 -6.45 -31.5,
+                          -11.2 -9.325 -30.3325,
+                          -11.2 -11.1 -31.5,
+                          -11.2 -6.45 -31.5,
+                          -11.2 -7.61747 -28.625,
+                          -11.2 -7.45 -29.25,
+                          -11.2 -6.45 -31.5,
+                          -11.2 -7.61747 -29.875,
+                          -11.2 -6.45 -31.5,
+                          -11.2 -7.45 -29.25,
+                          -11.2 -8.7 -30.5,
+                          -11.2 -9.325 -30.3325,
+                          -11.2 -6.45 -31.5,
+                          -11.2 -8.075 -30.3325,
+                          -11.2 -8.7 -30.5,
+                          -11.2 -6.45 -31.5,
+                          -11.2 -7.61747 -29.875,
+                          -11.2 -8.075 -30.3325,
+                          -11.2 -6.45 -31.5,
+                          -11.2 -9.78253 -29.875,
+                          -11.2 -11.1 -27,
+                          -11.2 -11.1 -31.5,
+                          -11.2 -9.325 -30.3325,
+                          -11.2 -9.78253 -29.875,
+                          -11.2 -11.1 -31.5,
+                          -18.5 -11.1 -27,
+                          -15.8 -11.1 -31.5,
+                          -18.5 -11.1 -31.5,
+                          -15.8 -11.1 -27,
+                          -15.8 -11.1 -31.5,
+                          -18.5 -11.1 -27,
+                          -15.8 -9.78253 -28.625,
+                          -15.8 -11.1 -31.5,
+                          -15.8 -11.1 -27,
+                          -15.8 -8.7 -30.5,
+                          -15.8 -8.075 -30.3325,
+                          -15.8 -11.1 -31.5,
+                          -15.8 -9.325 -30.3325,
+                          -15.8 -8.7 -30.5,
+                          -15.8 -11.1 -31.5,
+                          -15.8 -9.78253 -29.875,
+                          -15.8 -9.325 -30.3325,
+                          -15.8 -11.1 -31.5,
+                          -15.8 -9.95 -29.25,
+                          -15.8 -9.78253 -29.875,
+                          -15.8 -11.1 -31.5,
+                          -15.8 -9.78253 -28.625,
+                          -15.8 -9.95 -29.25,
+                          -15.8 -11.1 -31.5,
+                          -18.5 -11.1 -27,
+                          -18.5 -11.1 -31.5,
+                          -18.5 -42.1 -31.5,
+                          -11.5 -45.1 -31.5,
+                          -15.5 -45.1 -31.5,
+                          -18.5 -42.1 -31.5,
+                          -15.5 -45.1 -27,
+                          -18.5 -42.1 -31.5,
+                          -15.5 -45.1 -31.5,
+                          -18.5 -42.1 -27,
+                          -18.5 -42.1 -31.5,
+                          -15.5 -45.1 -27,
+                          -18.5 -11.1 -27,
+                          -18.5 -42.1 -31.5,
+                          -18.5 -42.1 -27,
+                          -11.5 -45.1 -27,
+                          -15.5 -45.1 -31.5,
+                          -11.5 -45.1 -31.5,
+                          -15.5 -45.1 -27,
+                          -15.5 -45.1 -31.5,
+                          -11.5 -45.1 -27,
+                          -15.8 -11.1 -27,
+                          -18.5 -11.1 -27,
+                          -18.5 -42.1 -27,
+                          -11.2 -11.1 -27,
+                          -15.8 -11.1 -27,
+                          -18.5 -42.1 -27,
+                          -15.8 -9.325 -28.1675,
+                          -15.8 -9.78253 -28.625,
+                          -15.8 -11.1 -27,
+                          -11.2 -8.7 -28,
+                          -11.2 -8.075 -28.1675,
+                          -11.2 -11.1 -27,
+                          -11.2 -9.325 -28.1675,
+                          -11.2 -8.7 -28,
+                          -11.2 -11.1 -27,
+                          -11.2 -9.78253 -28.625,
+                          -11.2 -9.325 -28.1675,
+                          -11.2 -11.1 -27,
+                          -11.2 -9.95 -29.25,
+                          -11.2 -9.78253 -28.625,
+                          -11.2 -11.1 -27,
+                          -11.2 -9.78253 -29.875,
+                          -11.2 -9.95 -29.25,
+                          -11.2 -11.1 -27,
+                          -15.8 -7.45 -29.25,
+                          -11.2 -7.45 -29.25,
+                          -11.2 -7.61747 -28.625,
+                          -15.8 -7.61747 -29.875,
+                          -11.2 -7.61747 -29.875,
+                          -11.2 -7.45 -29.25,
+                          -15.8 -7.61747 -29.875,
+                          -11.2 -7.45 -29.25,
+                          -15.8 -7.45 -29.25,
+                          -15.8 -7.61747 -28.625,
+                          -11.2 -7.61747 -28.625,
+                          -11.2 -8.075 -28.1675,
+                          -15.8 -7.61747 -28.625,
+                          -15.8 -7.45 -29.25,
+                          -11.2 -7.61747 -28.625,
+                          -15.8 -8.075 -28.1675,
+                          -11.2 -8.075 -28.1675,
+                          -11.2 -8.7 -28,
+                          -15.8 -7.61747 -28.625,
+                          -11.2 -8.075 -28.1675,
+                          -15.8 -8.075 -28.1675,
+                          -15.8 -8.7 -28,
+                          -11.2 -8.7 -28,
+                          -11.2 -9.325 -28.1675,
+                          -15.8 -8.075 -28.1675,
+                          -11.2 -8.7 -28,
+                          -15.8 -8.7 -28,
+                          -15.8 -9.325 -28.1675,
+                          -11.2 -9.325 -28.1675,
+                          -11.2 -9.78253 -28.625,
+                          -15.8 -8.7 -28,
+                          -11.2 -9.325 -28.1675,
+                          -15.8 -9.325 -28.1675,
+                          -15.8 -9.78253 -28.625,
+                          -11.2 -9.78253 -28.625,
+                          -11.2 -9.95 -29.25,
+                          -15.8 -9.325 -28.1675,
+                          -11.2 -9.78253 -28.625,
+                          -15.8 -9.78253 -28.625,
+                          -15.8 -9.95 -29.25,
+                          -11.2 -9.95 -29.25,
+                          -11.2 -9.78253 -29.875,
+                          -15.8 -9.78253 -28.625,
+                          -11.2 -9.95 -29.25,
+                          -15.8 -9.95 -29.25,
+                          -15.8 -9.78253 -29.875,
+                          -11.2 -9.78253 -29.875,
+                          -11.2 -9.325 -30.3325,
+                          -15.8 -9.95 -29.25,
+                          -11.2 -9.78253 -29.875,
+                          -15.8 -9.78253 -29.875,
+                          -15.8 -9.325 -30.3325,
+                          -11.2 -9.325 -30.3325,
+                          -11.2 -8.7 -30.5,
+                          -15.8 -9.78253 -29.875,
+                          -11.2 -9.325 -30.3325,
+                          -15.8 -9.325 -30.3325,
+                          -15.8 -8.7 -30.5,
+                          -11.2 -8.7 -30.5,
+                          -11.2 -8.075 -30.3325,
+                          -15.8 -9.325 -30.3325,
+                          -11.2 -8.7 -30.5,
+                          -15.8 -8.7 -30.5,
+                          -15.8 -8.075 -30.3325,
+                          -11.2 -8.075 -30.3325,
+                          -11.2 -7.61747 -29.875,
+                          -15.8 -8.7 -30.5,
+                          -11.2 -8.075 -30.3325,
+                          -15.8 -8.075 -30.3325,
+                          -15.8 -8.075 -30.3325,
+                          -11.2 -7.61747 -29.875,
+                          -15.8 -7.61747 -29.875 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          5.83977e-14 -8.40161e-14 -1,
+                          5.83977e-14 -8.40161e-14 -1,
+                          5.83977e-14 -8.40161e-14 -1,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          1.00147e-12 -1 8.39051e-14,
+                          1.00147e-12 -1 8.39051e-14,
+                          1.00147e-12 -1 8.39051e-14,
+                          1.00147e-12 -1 8.39051e-14,
+                          1.00147e-12 -1 8.39051e-14,
+                          1.00147e-12 -1 8.39051e-14,
+                          -0.707107 0.707107 -1.0078e-13,
+                          -0.707107 0.707107 -1.0078e-13,
+                          -0.707107 0.707107 -1.0078e-13,
+                          5.83977e-14 -8.40161e-14 -1,
+                          5.83977e-14 -8.40161e-14 -1,
+                          5.83977e-14 -8.40161e-14 -1,
+                          5.83977e-14 -8.40161e-14 -1,
+                          5.83977e-14 -8.40161e-14 -1,
+                          5.83977e-14 -8.40161e-14 -1,
+                          5.83977e-14 -8.40161e-14 -1,
+                          5.83977e-14 -8.40161e-14 -1,
+                          5.83977e-14 -8.40161e-14 -1,
+                          5.83977e-14 -8.40161e-14 -1,
+                          5.83977e-14 -8.40161e-14 -1,
+                          5.83977e-14 -8.40161e-14 -1,
+                          -5.83977e-14 8.40161e-14 1,
+                          -5.83977e-14 8.40161e-14 1,
+                          -5.83977e-14 8.40161e-14 1,
+                          -0.707107 0.707107 -1.0078e-13,
+                          -0.707107 0.707107 -1.0078e-13,
+                          -0.707107 0.707107 -1.0078e-13,
+                          -5.83977e-14 8.40161e-14 1,
+                          -5.83977e-14 8.40161e-14 1,
+                          -5.83977e-14 8.40161e-14 1,
+                          -5.83977e-14 8.40161e-14 1,
+                          -5.83977e-14 8.40161e-14 1,
+                          -5.83977e-14 8.40161e-14 1,
+                          -5.83977e-14 8.40161e-14 1,
+                          -5.83977e-14 8.40161e-14 1,
+                          -5.83977e-14 8.40161e-14 1,
+                          1.00147e-12 -1 8.39051e-14,
+                          1.00147e-12 -1 8.39051e-14,
+                          1.00147e-12 -1 8.39051e-14,
+                          -5.83977e-14 8.40161e-14 1,
+                          -5.83977e-14 8.40161e-14 1,
+                          -5.83977e-14 8.40161e-14 1,
+                          1.00147e-12 -1 8.39051e-14,
+                          1.00147e-12 -1 8.39051e-14,
+                          1.00147e-12 -1 8.39051e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -5.83977e-14 8.40161e-14 1,
+                          -5.83977e-14 8.40161e-14 1,
+                          -5.83977e-14 8.40161e-14 1,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          5.83977e-14 -8.40161e-14 -1,
+                          5.83977e-14 -8.40161e-14 -1,
+                          5.83977e-14 -8.40161e-14 -1,
+                          5.83977e-14 -8.40161e-14 -1,
+                          5.83977e-14 -8.40161e-14 -1,
+                          5.83977e-14 -8.40161e-14 -1,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          1.00147e-12 -1 8.39051e-14,
+                          1.00147e-12 -1 8.39051e-14,
+                          1.00147e-12 -1 8.39051e-14,
+                          1.00147e-12 -1 8.39051e-14,
+                          1.00147e-12 -1 8.39051e-14,
+                          1.00147e-12 -1 8.39051e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          5.83977e-14 -8.40161e-14 -1,
+                          5.83977e-14 -8.40161e-14 -1,
+                          5.83977e-14 -8.40161e-14 -1,
+                          0.707107 0.707107 -1.78794e-14,
+                          0.707107 0.707107 -1.78794e-14,
+                          0.707107 0.707107 -1.78794e-14,
+                          0.707107 0.707107 -1.78794e-14,
+                          0.707107 0.707107 -1.78794e-14,
+                          0.707107 0.707107 -1.78794e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          -1.00147e-12 1 -8.39051e-14,
+                          -1.00147e-12 1 -8.39051e-14,
+                          -1.00147e-12 1 -8.39051e-14,
+                          -1.00147e-12 1 -8.39051e-14,
+                          -1.00147e-12 1 -8.39051e-14,
+                          -1.00147e-12 1 -8.39051e-14,
+                          -5.83977e-14 8.40161e-14 1,
+                          -5.83977e-14 8.40161e-14 1,
+                          -5.83977e-14 8.40161e-14 1,
+                          -5.83977e-14 8.40161e-14 1,
+                          -5.83977e-14 8.40161e-14 1,
+                          -5.83977e-14 8.40161e-14 1,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          1 1.0012e-12 5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1 -1.0012e-12 -5.86198e-14,
+                          -1.00147e-12 1 -8.39051e-14,
+                          -1.00147e-12 1 -8.39051e-14,
+                          -8.38102e-13 0.866025 -0.5,
+                          -8.965e-13 0.866025 0.5,
+                          -8.965e-13 0.866025 0.5,
+                          -1.00147e-12 1 -8.36602e-14,
+                          -8.965e-13 0.866025 0.5,
+                          -1.00147e-12 1 -8.36602e-14,
+                          -1.00147e-12 1 -8.36602e-14,
+                          -8.38102e-13 0.866025 -0.5,
+                          -8.38102e-13 0.866025 -0.5,
+                          -4.50163e-13 0.5 -0.866025,
+                          -8.38102e-13 0.866025 -0.5,
+                          -1.00147e-12 1 -8.39051e-14,
+                          -8.38102e-13 0.866025 -0.5,
+                          -4.50163e-13 0.5 -0.866025,
+                          -4.50163e-13 0.5 -0.866025,
+                          5.83977e-14 -8.21785e-14 -1,
+                          -8.38102e-13 0.866025 -0.5,
+                          -4.50163e-13 0.5 -0.866025,
+                          -4.50163e-13 0.5 -0.866025,
+                          5.83977e-14 -8.24006e-14 -1,
+                          5.83977e-14 -8.21785e-14 -1,
+                          5.51311e-13 -0.5 -0.866025,
+                          -4.50163e-13 0.5 -0.866025,
+                          5.83977e-14 -8.21785e-14 -1,
+                          5.83977e-14 -8.24006e-14 -1,
+                          5.51311e-13 -0.5 -0.866025,
+                          5.51311e-13 -0.5 -0.866025,
+                          8.965e-13 -0.866025 -0.5,
+                          5.83977e-14 -8.24006e-14 -1,
+                          5.51311e-13 -0.5 -0.866025,
+                          5.51311e-13 -0.5 -0.866025,
+                          8.965e-13 -0.866025 -0.5,
+                          8.965e-13 -0.866025 -0.5,
+                          1.00147e-12 -1 8.37826e-14,
+                          5.51311e-13 -0.5 -0.866025,
+                          8.965e-13 -0.866025 -0.5,
+                          8.965e-13 -0.866025 -0.5,
+                          1.00147e-12 -1 8.37826e-14,
+                          1.00147e-12 -1 8.37826e-14,
+                          8.38102e-13 -0.866025 0.5,
+                          8.965e-13 -0.866025 -0.5,
+                          1.00147e-12 -1 8.37826e-14,
+                          1.00147e-12 -1 8.37826e-14,
+                          8.38102e-13 -0.866025 0.5,
+                          8.38102e-13 -0.866025 0.5,
+                          4.50163e-13 -0.5 0.866025,
+                          1.00147e-12 -1 8.37826e-14,
+                          8.38102e-13 -0.866025 0.5,
+                          8.38102e-13 -0.866025 0.5,
+                          4.50163e-13 -0.5 0.866025,
+                          4.50163e-13 -0.5 0.866025,
+                          -5.83977e-14 8.20561e-14 1,
+                          8.38102e-13 -0.866025 0.5,
+                          4.50163e-13 -0.5 0.866025,
+                          4.50163e-13 -0.5 0.866025,
+                          -5.83977e-14 8.20561e-14 1,
+                          -5.83977e-14 8.20561e-14 1,
+                          -5.51311e-13 0.5 0.866025,
+                          4.50163e-13 -0.5 0.866025,
+                          -5.83977e-14 8.20561e-14 1,
+                          -5.83977e-14 8.20561e-14 1,
+                          -5.51311e-13 0.5 0.866025,
+                          -5.51311e-13 0.5 0.866025,
+                          -8.965e-13 0.866025 0.5,
+                          -5.83977e-14 8.20561e-14 1,
+                          -5.51311e-13 0.5 0.866025,
+                          -5.51311e-13 0.5 0.866025,
+                          -5.51311e-13 0.5 0.866025,
+                          -8.965e-13 0.866025 0.5,
+                          -8.965e-13 0.866025 0.5 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -5 -15.3 -27,
+                          -5 -15.3 -31.5,
+                          -5 -46.3 -31.5,
+                          -2.3 -46.3 -31.5,
+                          -5 -46.3 -31.5,
+                          -5 -15.3 -31.5,
+                          -5 -46.3 -27,
+                          -5 -15.3 -27,
+                          -5 -46.3 -31.5,
+                          -2.3 -46.3 -27,
+                          -5 -46.3 -27,
+                          -5 -46.3 -31.5,
+                          -2.3 -46.3 -27,
+                          -5 -46.3 -31.5,
+                          -2.3 -46.3 -31.5,
+                          -2 -12.3 -31.5,
+                          -5 -15.3 -31.5,
+                          -5 -15.3 -27,
+                          2.3 -46.3 -31.5,
+                          -2.3 -46.3 -31.5,
+                          -5 -15.3 -31.5,
+                          5 -46.3 -31.5,
+                          2.3 -46.3 -31.5,
+                          -5 -15.3 -31.5,
+                          5 -15.3 -31.5,
+                          5 -46.3 -31.5,
+                          -5 -15.3 -31.5,
+                          -2 -12.3 -31.5,
+                          5 -15.3 -31.5,
+                          -5 -15.3 -31.5,
+                          5 -15.3 -27,
+                          -5 -15.3 -27,
+                          -5 -46.3 -27,
+                          -2 -12.3 -27,
+                          -2 -12.3 -31.5,
+                          -5 -15.3 -27,
+                          2 -12.3 -27,
+                          -2 -12.3 -27,
+                          -5 -15.3 -27,
+                          5 -15.3 -27,
+                          2 -12.3 -27,
+                          -5 -15.3 -27,
+                          -2.3 -46.3 -27,
+                          5 -15.3 -27,
+                          -5 -46.3 -27,
+                          2.3 -50.95 -31.5,
+                          2.3 -50.95 -27,
+                          -2.3 -50.95 -27,
+                          2.3 -46.3 -27,
+                          -2.3 -50.95 -27,
+                          2.3 -50.95 -27,
+                          -2.3 -50.95 -31.5,
+                          2.3 -50.95 -31.5,
+                          -2.3 -50.95 -27,
+                          -2.3 -49.7825 -28.625,
+                          -2.3 -50.95 -31.5,
+                          -2.3 -50.95 -27,
+                          -2.3 -46.3 -27,
+                          -2.3 -50.95 -27,
+                          2.3 -46.3 -27,
+                          -2.3 -49.325 -28.1675,
+                          -2.3 -50.95 -27,
+                          -2.3 -46.3 -27,
+                          -2.3 -49.325 -28.1675,
+                          -2.3 -49.7825 -28.625,
+                          -2.3 -50.95 -27,
+                          2.3 -49.7825 -29.875,
+                          2.3 -50.95 -27,
+                          2.3 -50.95 -31.5,
+                          2.3 -48.075 -28.1675,
+                          2.3 -46.3 -27,
+                          2.3 -50.95 -27,
+                          2.3 -49.7825 -29.875,
+                          2.3 -49.95 -29.25,
+                          2.3 -50.95 -27,
+                          2.3 -49.7825 -28.625,
+                          2.3 -50.95 -27,
+                          2.3 -49.95 -29.25,
+                          2.3 -48.7 -28,
+                          2.3 -48.075 -28.1675,
+                          2.3 -50.95 -27,
+                          2.3 -49.325 -28.1675,
+                          2.3 -48.7 -28,
+                          2.3 -50.95 -27,
+                          2.3 -49.7825 -28.625,
+                          2.3 -49.325 -28.1675,
+                          2.3 -50.95 -27,
+                          -2.3 -46.3 -31.5,
+                          2.3 -50.95 -31.5,
+                          -2.3 -50.95 -31.5,
+                          2.3 -46.3 -31.5,
+                          2.3 -50.95 -31.5,
+                          -2.3 -46.3 -31.5,
+                          2.3 -49.325 -30.3325,
+                          2.3 -50.95 -31.5,
+                          2.3 -46.3 -31.5,
+                          2.3 -49.325 -30.3325,
+                          2.3 -49.7825 -29.875,
+                          2.3 -50.95 -31.5,
+                          -2.3 -48.075 -30.3325,
+                          -2.3 -46.3 -31.5,
+                          -2.3 -50.95 -31.5,
+                          -2.3 -49.7825 -28.625,
+                          -2.3 -49.95 -29.25,
+                          -2.3 -50.95 -31.5,
+                          -2.3 -49.7825 -29.875,
+                          -2.3 -50.95 -31.5,
+                          -2.3 -49.95 -29.25,
+                          -2.3 -48.7 -30.5,
+                          -2.3 -48.075 -30.3325,
+                          -2.3 -50.95 -31.5,
+                          -2.3 -49.325 -30.3325,
+                          -2.3 -48.7 -30.5,
+                          -2.3 -50.95 -31.5,
+                          -2.3 -49.7825 -29.875,
+                          -2.3 -49.325 -30.3325,
+                          -2.3 -50.95 -31.5,
+                          -2.3 -47.6175 -29.875,
+                          -2.3 -46.3 -27,
+                          -2.3 -46.3 -31.5,
+                          -2.3 -48.075 -30.3325,
+                          -2.3 -47.6175 -29.875,
+                          -2.3 -46.3 -31.5,
+                          5 -46.3 -27,
+                          2.3 -46.3 -31.5,
+                          5 -46.3 -31.5,
+                          2.3 -46.3 -27,
+                          2.3 -46.3 -31.5,
+                          5 -46.3 -27,
+                          2.3 -47.6175 -28.625,
+                          2.3 -46.3 -31.5,
+                          2.3 -46.3 -27,
+                          2.3 -48.7 -30.5,
+                          2.3 -49.325 -30.3325,
+                          2.3 -46.3 -31.5,
+                          2.3 -48.075 -30.3325,
+                          2.3 -48.7 -30.5,
+                          2.3 -46.3 -31.5,
+                          2.3 -47.6175 -29.875,
+                          2.3 -48.075 -30.3325,
+                          2.3 -46.3 -31.5,
+                          2.3 -47.45 -29.25,
+                          2.3 -47.6175 -29.875,
+                          2.3 -46.3 -31.5,
+                          2.3 -47.6175 -28.625,
+                          2.3 -47.45 -29.25,
+                          2.3 -46.3 -31.5,
+                          5 -46.3 -27,
+                          5 -46.3 -31.5,
+                          5 -15.3 -31.5,
+                          -2 -12.3 -31.5,
+                          2 -12.3 -31.5,
+                          5 -15.3 -31.5,
+                          2 -12.3 -27,
+                          5 -15.3 -31.5,
+                          2 -12.3 -31.5,
+                          5 -15.3 -27,
+                          5 -15.3 -31.5,
+                          2 -12.3 -27,
+                          5 -46.3 -27,
+                          5 -15.3 -31.5,
+                          5 -15.3 -27,
+                          -2 -12.3 -27,
+                          2 -12.3 -31.5,
+                          -2 -12.3 -31.5,
+                          2 -12.3 -27,
+                          2 -12.3 -31.5,
+                          -2 -12.3 -27,
+                          2.3 -46.3 -27,
+                          5 -46.3 -27,
+                          5 -15.3 -27,
+                          -2.3 -46.3 -27,
+                          2.3 -46.3 -27,
+                          5 -15.3 -27,
+                          2.3 -48.075 -28.1675,
+                          2.3 -47.6175 -28.625,
+                          2.3 -46.3 -27,
+                          -2.3 -48.7 -28,
+                          -2.3 -49.325 -28.1675,
+                          -2.3 -46.3 -27,
+                          -2.3 -48.075 -28.1675,
+                          -2.3 -48.7 -28,
+                          -2.3 -46.3 -27,
+                          -2.3 -47.6175 -28.625,
+                          -2.3 -48.075 -28.1675,
+                          -2.3 -46.3 -27,
+                          -2.3 -47.45 -29.25,
+                          -2.3 -47.6175 -28.625,
+                          -2.3 -46.3 -27,
+                          -2.3 -47.6175 -29.875,
+                          -2.3 -47.45 -29.25,
+                          -2.3 -46.3 -27,
+                          2.3 -49.95 -29.25,
+                          -2.3 -49.95 -29.25,
+                          -2.3 -49.7825 -28.625,
+                          2.3 -49.7825 -29.875,
+                          -2.3 -49.7825 -29.875,
+                          -2.3 -49.95 -29.25,
+                          2.3 -49.7825 -29.875,
+                          -2.3 -49.95 -29.25,
+                          2.3 -49.95 -29.25,
+                          2.3 -49.7825 -28.625,
+                          -2.3 -49.7825 -28.625,
+                          -2.3 -49.325 -28.1675,
+                          2.3 -49.7825 -28.625,
+                          2.3 -49.95 -29.25,
+                          -2.3 -49.7825 -28.625,
+                          2.3 -49.325 -28.1675,
+                          -2.3 -49.325 -28.1675,
+                          -2.3 -48.7 -28,
+                          2.3 -49.7825 -28.625,
+                          -2.3 -49.325 -28.1675,
+                          2.3 -49.325 -28.1675,
+                          2.3 -48.7 -28,
+                          -2.3 -48.7 -28,
+                          -2.3 -48.075 -28.1675,
+                          2.3 -49.325 -28.1675,
+                          -2.3 -48.7 -28,
+                          2.3 -48.7 -28,
+                          2.3 -48.075 -28.1675,
+                          -2.3 -48.075 -28.1675,
+                          -2.3 -47.6175 -28.625,
+                          2.3 -48.7 -28,
+                          -2.3 -48.075 -28.1675,
+                          2.3 -48.075 -28.1675,
+                          2.3 -47.6175 -28.625,
+                          -2.3 -47.6175 -28.625,
+                          -2.3 -47.45 -29.25,
+                          2.3 -48.075 -28.1675,
+                          -2.3 -47.6175 -28.625,
+                          2.3 -47.6175 -28.625,
+                          2.3 -47.45 -29.25,
+                          -2.3 -47.45 -29.25,
+                          -2.3 -47.6175 -29.875,
+                          2.3 -47.6175 -28.625,
+                          -2.3 -47.45 -29.25,
+                          2.3 -47.45 -29.25,
+                          2.3 -47.6175 -29.875,
+                          -2.3 -47.6175 -29.875,
+                          -2.3 -48.075 -30.3325,
+                          2.3 -47.45 -29.25,
+                          -2.3 -47.6175 -29.875,
+                          2.3 -47.6175 -29.875,
+                          2.3 -48.075 -30.3325,
+                          -2.3 -48.075 -30.3325,
+                          -2.3 -48.7 -30.5,
+                          2.3 -47.6175 -29.875,
+                          -2.3 -48.075 -30.3325,
+                          2.3 -48.075 -30.3325,
+                          2.3 -48.7 -30.5,
+                          -2.3 -48.7 -30.5,
+                          -2.3 -49.325 -30.3325,
+                          2.3 -48.075 -30.3325,
+                          -2.3 -48.7 -30.5,
+                          2.3 -48.7 -30.5,
+                          2.3 -49.325 -30.3325,
+                          -2.3 -49.325 -30.3325,
+                          -2.3 -49.7825 -29.875,
+                          2.3 -48.7 -30.5,
+                          -2.3 -49.325 -30.3325,
+                          2.3 -49.325 -30.3325,
+                          2.3 -49.325 -30.3325,
+                          -2.3 -49.7825 -29.875,
+                          2.3 -49.7825 -29.875 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          5.84532e-14 -8.37212e-14 -1,
+                          5.84532e-14 -8.37212e-14 -1,
+                          5.84532e-14 -8.37212e-14 -1,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          -1.00157e-12 1 -8.40265e-14,
+                          -1.00157e-12 1 -8.40265e-14,
+                          -1.00157e-12 1 -8.40265e-14,
+                          -1.00157e-12 1 -8.40265e-14,
+                          -1.00157e-12 1 -8.40265e-14,
+                          -1.00157e-12 1 -8.40265e-14,
+                          0.707107 -0.707107 1.00591e-13,
+                          0.707107 -0.707107 1.00591e-13,
+                          0.707107 -0.707107 1.00591e-13,
+                          5.84532e-14 -8.37212e-14 -1,
+                          5.84532e-14 -8.37212e-14 -1,
+                          5.84532e-14 -8.37212e-14 -1,
+                          5.84532e-14 -8.37212e-14 -1,
+                          5.84532e-14 -8.37212e-14 -1,
+                          5.84532e-14 -8.37212e-14 -1,
+                          5.84532e-14 -8.37212e-14 -1,
+                          5.84532e-14 -8.37212e-14 -1,
+                          5.84532e-14 -8.37212e-14 -1,
+                          5.84532e-14 -8.37212e-14 -1,
+                          5.84532e-14 -8.37212e-14 -1,
+                          5.84532e-14 -8.37212e-14 -1,
+                          -5.84532e-14 8.37212e-14 1,
+                          -5.84532e-14 8.37212e-14 1,
+                          -5.84532e-14 8.37212e-14 1,
+                          0.707107 -0.707107 1.00591e-13,
+                          0.707107 -0.707107 1.00591e-13,
+                          0.707107 -0.707107 1.00591e-13,
+                          -5.84532e-14 8.37212e-14 1,
+                          -5.84532e-14 8.37212e-14 1,
+                          -5.84532e-14 8.37212e-14 1,
+                          -5.84532e-14 8.37212e-14 1,
+                          -5.84532e-14 8.37212e-14 1,
+                          -5.84532e-14 8.37212e-14 1,
+                          -5.84532e-14 8.37212e-14 1,
+                          -5.84532e-14 8.37212e-14 1,
+                          -5.84532e-14 8.37212e-14 1,
+                          -1.00157e-12 1 -8.40265e-14,
+                          -1.00157e-12 1 -8.40265e-14,
+                          -1.00157e-12 1 -8.40265e-14,
+                          -5.84532e-14 8.37212e-14 1,
+                          -5.84532e-14 8.37212e-14 1,
+                          -5.84532e-14 8.37212e-14 1,
+                          -1.00157e-12 1 -8.40265e-14,
+                          -1.00157e-12 1 -8.40265e-14,
+                          -1.00157e-12 1 -8.40265e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          -5.84532e-14 8.37212e-14 1,
+                          -5.84532e-14 8.37212e-14 1,
+                          -5.84532e-14 8.37212e-14 1,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          5.84532e-14 -8.37212e-14 -1,
+                          5.84532e-14 -8.37212e-14 -1,
+                          5.84532e-14 -8.37212e-14 -1,
+                          5.84532e-14 -8.37212e-14 -1,
+                          5.84532e-14 -8.37212e-14 -1,
+                          5.84532e-14 -8.37212e-14 -1,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          -1.00157e-12 1 -8.40265e-14,
+                          -1.00157e-12 1 -8.40265e-14,
+                          -1.00157e-12 1 -8.40265e-14,
+                          -1.00157e-12 1 -8.40265e-14,
+                          -1.00157e-12 1 -8.40265e-14,
+                          -1.00157e-12 1 -8.40265e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          5.84532e-14 -8.37212e-14 -1,
+                          5.84532e-14 -8.37212e-14 -1,
+                          5.84532e-14 -8.37212e-14 -1,
+                          -0.707107 -0.707107 1.82401e-14,
+                          -0.707107 -0.707107 1.82401e-14,
+                          -0.707107 -0.707107 1.82401e-14,
+                          -0.707107 -0.707107 1.82401e-14,
+                          -0.707107 -0.707107 1.82401e-14,
+                          -0.707107 -0.707107 1.82401e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          1.00157e-12 -1 8.40265e-14,
+                          1.00157e-12 -1 8.40265e-14,
+                          1.00157e-12 -1 8.40265e-14,
+                          1.00157e-12 -1 8.40265e-14,
+                          1.00157e-12 -1 8.40265e-14,
+                          1.00157e-12 -1 8.40265e-14,
+                          -5.84532e-14 8.37212e-14 1,
+                          -5.84532e-14 8.37212e-14 1,
+                          -5.84532e-14 8.37212e-14 1,
+                          -5.84532e-14 8.37212e-14 1,
+                          -5.84532e-14 8.37212e-14 1,
+                          -5.84532e-14 8.37212e-14 1,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          -1 -1.00132e-12 -5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1 1.00132e-12 5.82312e-14,
+                          1.00157e-12 -1 8.40265e-14,
+                          1.00157e-12 -1 8.40265e-14,
+                          8.96612e-13 -0.866025 -0.5,
+                          8.38159e-13 -0.866025 0.5,
+                          8.38159e-13 -0.866025 0.5,
+                          1.00157e-12 -1 8.42715e-14,
+                          8.38159e-13 -0.866025 0.5,
+                          1.00157e-12 -1 8.42715e-14,
+                          1.00157e-12 -1 8.42715e-14,
+                          8.96612e-13 -0.866025 -0.5,
+                          8.96612e-13 -0.866025 -0.5,
+                          5.51407e-13 -0.5 -0.866025,
+                          8.96612e-13 -0.866025 -0.5,
+                          1.00157e-12 -1 8.40265e-14,
+                          8.96612e-13 -0.866025 -0.5,
+                          5.51407e-13 -0.5 -0.866025,
+                          5.51407e-13 -0.5 -0.866025,
+                          5.84532e-14 -8.55588e-14 -1,
+                          8.96612e-13 -0.866025 -0.5,
+                          5.51407e-13 -0.5 -0.866025,
+                          5.51407e-13 -0.5 -0.866025,
+                          5.84532e-14 -8.53368e-14 -1,
+                          5.84532e-14 -8.55588e-14 -1,
+                          -4.50163e-13 0.5 -0.866025,
+                          5.51407e-13 -0.5 -0.866025,
+                          5.84532e-14 -8.55588e-14 -1,
+                          5.84532e-14 -8.53368e-14 -1,
+                          -4.50163e-13 0.5 -0.866025,
+                          -4.50163e-13 0.5 -0.866025,
+                          -8.38159e-13 0.866025 -0.5,
+                          5.84532e-14 -8.53368e-14 -1,
+                          -4.50163e-13 0.5 -0.866025,
+                          -4.50163e-13 0.5 -0.866025,
+                          -8.38159e-13 0.866025 -0.5,
+                          -8.38159e-13 0.866025 -0.5,
+                          -1.00157e-12 1 -8.4149e-14,
+                          -4.50163e-13 0.5 -0.866025,
+                          -8.38159e-13 0.866025 -0.5,
+                          -8.38159e-13 0.866025 -0.5,
+                          -1.00157e-12 1 -8.4149e-14,
+                          -1.00157e-12 1 -8.4149e-14,
+                          -8.96612e-13 0.866025 0.5,
+                          -8.38159e-13 0.866025 -0.5,
+                          -1.00157e-12 1 -8.4149e-14,
+                          -1.00157e-12 1 -8.4149e-14,
+                          -8.96612e-13 0.866025 0.5,
+                          -8.96612e-13 0.866025 0.5,
+                          -5.51407e-13 0.5 0.866025,
+                          -1.00157e-12 1 -8.4149e-14,
+                          -8.96612e-13 0.866025 0.5,
+                          -8.96612e-13 0.866025 0.5,
+                          -5.51407e-13 0.5 0.866025,
+                          -5.51407e-13 0.5 0.866025,
+                          -5.84532e-14 8.56813e-14 1,
+                          -8.96612e-13 0.866025 0.5,
+                          -5.51407e-13 0.5 0.866025,
+                          -5.51407e-13 0.5 0.866025,
+                          -5.84532e-14 8.56813e-14 1,
+                          -5.84532e-14 8.56813e-14 1,
+                          4.50163e-13 -0.5 0.866025,
+                          -5.51407e-13 0.5 0.866025,
+                          -5.84532e-14 8.56813e-14 1,
+                          -5.84532e-14 8.56813e-14 1,
+                          4.50163e-13 -0.5 0.866025,
+                          4.50163e-13 -0.5 0.866025,
+                          8.38159e-13 -0.866025 0.5,
+                          -5.84532e-14 8.56813e-14 1,
+                          4.50163e-13 -0.5 0.866025,
+                          4.50163e-13 -0.5 0.866025,
+                          4.50163e-13 -0.5 0.866025,
+                          8.38159e-13 -0.866025 0.5,
+                          8.38159e-13 -0.866025 0.5 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 18.5 -42.1 -27,
+                          18.5 -42.1 -31.5,
+                          18.5 -11.1 -31.5,
+                          15.8 -11.1 -31.5,
+                          18.5 -11.1 -31.5,
+                          18.5 -42.1 -31.5,
+                          18.5 -11.1 -27,
+                          18.5 -42.1 -27,
+                          18.5 -11.1 -31.5,
+                          15.8 -11.1 -27,
+                          18.5 -11.1 -27,
+                          18.5 -11.1 -31.5,
+                          15.8 -11.1 -27,
+                          18.5 -11.1 -31.5,
+                          15.8 -11.1 -31.5,
+                          15.5 -45.1 -31.5,
+                          18.5 -42.1 -31.5,
+                          18.5 -42.1 -27,
+                          11.2 -11.1 -31.5,
+                          15.8 -11.1 -31.5,
+                          18.5 -42.1 -31.5,
+                          8.5 -11.1 -31.5,
+                          11.2 -11.1 -31.5,
+                          18.5 -42.1 -31.5,
+                          8.5 -42.1 -31.5,
+                          8.5 -11.1 -31.5,
+                          18.5 -42.1 -31.5,
+                          15.5 -45.1 -31.5,
+                          8.5 -42.1 -31.5,
+                          18.5 -42.1 -31.5,
+                          8.5 -42.1 -27,
+                          18.5 -42.1 -27,
+                          18.5 -11.1 -27,
+                          15.5 -45.1 -27,
+                          15.5 -45.1 -31.5,
+                          18.5 -42.1 -27,
+                          11.5 -45.1 -27,
+                          15.5 -45.1 -27,
+                          18.5 -42.1 -27,
+                          8.5 -42.1 -27,
+                          11.5 -45.1 -27,
+                          18.5 -42.1 -27,
+                          15.8 -11.1 -27,
+                          8.5 -42.1 -27,
+                          18.5 -11.1 -27,
+                          11.2 -6.45 -31.5,
+                          11.2 -6.45 -27,
+                          15.8 -6.45 -27,
+                          11.2 -11.1 -27,
+                          15.8 -6.45 -27,
+                          11.2 -6.45 -27,
+                          15.8 -6.45 -31.5,
+                          11.2 -6.45 -31.5,
+                          15.8 -6.45 -27,
+                          15.8 -7.61747 -28.625,
+                          15.8 -6.45 -31.5,
+                          15.8 -6.45 -27,
+                          15.8 -11.1 -27,
+                          15.8 -6.45 -27,
+                          11.2 -11.1 -27,
+                          15.8 -8.075 -28.1675,
+                          15.8 -6.45 -27,
+                          15.8 -11.1 -27,
+                          15.8 -8.075 -28.1675,
+                          15.8 -7.61747 -28.625,
+                          15.8 -6.45 -27,
+                          11.2 -7.61747 -29.875,
+                          11.2 -6.45 -27,
+                          11.2 -6.45 -31.5,
+                          11.2 -9.325 -28.1675,
+                          11.2 -11.1 -27,
+                          11.2 -6.45 -27,
+                          11.2 -7.61747 -29.875,
+                          11.2 -7.45 -29.25,
+                          11.2 -6.45 -27,
+                          11.2 -7.61747 -28.625,
+                          11.2 -6.45 -27,
+                          11.2 -7.45 -29.25,
+                          11.2 -8.7 -28,
+                          11.2 -9.325 -28.1675,
+                          11.2 -6.45 -27,
+                          11.2 -8.075 -28.1675,
+                          11.2 -8.7 -28,
+                          11.2 -6.45 -27,
+                          11.2 -7.61747 -28.625,
+                          11.2 -8.075 -28.1675,
+                          11.2 -6.45 -27,
+                          15.8 -11.1 -31.5,
+                          11.2 -6.45 -31.5,
+                          15.8 -6.45 -31.5,
+                          11.2 -11.1 -31.5,
+                          11.2 -6.45 -31.5,
+                          15.8 -11.1 -31.5,
+                          11.2 -8.075 -30.3325,
+                          11.2 -6.45 -31.5,
+                          11.2 -11.1 -31.5,
+                          11.2 -8.075 -30.3325,
+                          11.2 -7.61747 -29.875,
+                          11.2 -6.45 -31.5,
+                          15.8 -9.325 -30.3325,
+                          15.8 -11.1 -31.5,
+                          15.8 -6.45 -31.5,
+                          15.8 -7.61747 -28.625,
+                          15.8 -7.45 -29.25,
+                          15.8 -6.45 -31.5,
+                          15.8 -7.61747 -29.875,
+                          15.8 -6.45 -31.5,
+                          15.8 -7.45 -29.25,
+                          15.8 -8.7 -30.5,
+                          15.8 -9.325 -30.3325,
+                          15.8 -6.45 -31.5,
+                          15.8 -8.075 -30.3325,
+                          15.8 -8.7 -30.5,
+                          15.8 -6.45 -31.5,
+                          15.8 -7.61747 -29.875,
+                          15.8 -8.075 -30.3325,
+                          15.8 -6.45 -31.5,
+                          15.8 -9.78253 -29.875,
+                          15.8 -11.1 -27,
+                          15.8 -11.1 -31.5,
+                          15.8 -9.325 -30.3325,
+                          15.8 -9.78253 -29.875,
+                          15.8 -11.1 -31.5,
+                          8.5 -11.1 -27,
+                          11.2 -11.1 -31.5,
+                          8.5 -11.1 -31.5,
+                          11.2 -11.1 -27,
+                          11.2 -11.1 -31.5,
+                          8.5 -11.1 -27,
+                          11.2 -9.78253 -28.625,
+                          11.2 -11.1 -31.5,
+                          11.2 -11.1 -27,
+                          11.2 -8.7 -30.5,
+                          11.2 -8.075 -30.3325,
+                          11.2 -11.1 -31.5,
+                          11.2 -9.325 -30.3325,
+                          11.2 -8.7 -30.5,
+                          11.2 -11.1 -31.5,
+                          11.2 -9.78253 -29.875,
+                          11.2 -9.325 -30.3325,
+                          11.2 -11.1 -31.5,
+                          11.2 -9.95 -29.25,
+                          11.2 -9.78253 -29.875,
+                          11.2 -11.1 -31.5,
+                          11.2 -9.78253 -28.625,
+                          11.2 -9.95 -29.25,
+                          11.2 -11.1 -31.5,
+                          8.5 -11.1 -27,
+                          8.5 -11.1 -31.5,
+                          8.5 -42.1 -31.5,
+                          15.5 -45.1 -31.5,
+                          11.5 -45.1 -31.5,
+                          8.5 -42.1 -31.5,
+                          11.5 -45.1 -27,
+                          8.5 -42.1 -31.5,
+                          11.5 -45.1 -31.5,
+                          8.5 -42.1 -27,
+                          8.5 -42.1 -31.5,
+                          11.5 -45.1 -27,
+                          8.5 -11.1 -27,
+                          8.5 -42.1 -31.5,
+                          8.5 -42.1 -27,
+                          15.5 -45.1 -27,
+                          11.5 -45.1 -31.5,
+                          15.5 -45.1 -31.5,
+                          11.5 -45.1 -27,
+                          11.5 -45.1 -31.5,
+                          15.5 -45.1 -27,
+                          11.2 -11.1 -27,
+                          8.5 -11.1 -27,
+                          8.5 -42.1 -27,
+                          15.8 -11.1 -27,
+                          11.2 -11.1 -27,
+                          8.5 -42.1 -27,
+                          11.2 -9.325 -28.1675,
+                          11.2 -9.78253 -28.625,
+                          11.2 -11.1 -27,
+                          15.8 -8.7 -28,
+                          15.8 -8.075 -28.1675,
+                          15.8 -11.1 -27,
+                          15.8 -9.325 -28.1675,
+                          15.8 -8.7 -28,
+                          15.8 -11.1 -27,
+                          15.8 -9.78253 -28.625,
+                          15.8 -9.325 -28.1675,
+                          15.8 -11.1 -27,
+                          15.8 -9.95 -29.25,
+                          15.8 -9.78253 -28.625,
+                          15.8 -11.1 -27,
+                          15.8 -9.78253 -29.875,
+                          15.8 -9.95 -29.25,
+                          15.8 -11.1 -27,
+                          11.2 -7.45 -29.25,
+                          15.8 -7.45 -29.25,
+                          15.8 -7.61747 -28.625,
+                          11.2 -7.61747 -29.875,
+                          15.8 -7.61747 -29.875,
+                          15.8 -7.45 -29.25,
+                          11.2 -7.61747 -29.875,
+                          15.8 -7.45 -29.25,
+                          11.2 -7.45 -29.25,
+                          11.2 -7.61747 -28.625,
+                          15.8 -7.61747 -28.625,
+                          15.8 -8.075 -28.1675,
+                          11.2 -7.61747 -28.625,
+                          11.2 -7.45 -29.25,
+                          15.8 -7.61747 -28.625,
+                          11.2 -8.075 -28.1675,
+                          15.8 -8.075 -28.1675,
+                          15.8 -8.7 -28,
+                          11.2 -7.61747 -28.625,
+                          15.8 -8.075 -28.1675,
+                          11.2 -8.075 -28.1675,
+                          11.2 -8.7 -28,
+                          15.8 -8.7 -28,
+                          15.8 -9.325 -28.1675,
+                          11.2 -8.075 -28.1675,
+                          15.8 -8.7 -28,
+                          11.2 -8.7 -28,
+                          11.2 -9.325 -28.1675,
+                          15.8 -9.325 -28.1675,
+                          15.8 -9.78253 -28.625,
+                          11.2 -8.7 -28,
+                          15.8 -9.325 -28.1675,
+                          11.2 -9.325 -28.1675,
+                          11.2 -9.78253 -28.625,
+                          15.8 -9.78253 -28.625,
+                          15.8 -9.95 -29.25,
+                          11.2 -9.325 -28.1675,
+                          15.8 -9.78253 -28.625,
+                          11.2 -9.78253 -28.625,
+                          11.2 -9.95 -29.25,
+                          15.8 -9.95 -29.25,
+                          15.8 -9.78253 -29.875,
+                          11.2 -9.78253 -28.625,
+                          15.8 -9.95 -29.25,
+                          11.2 -9.95 -29.25,
+                          11.2 -9.78253 -29.875,
+                          15.8 -9.78253 -29.875,
+                          15.8 -9.325 -30.3325,
+                          11.2 -9.95 -29.25,
+                          15.8 -9.78253 -29.875,
+                          11.2 -9.78253 -29.875,
+                          11.2 -9.325 -30.3325,
+                          15.8 -9.325 -30.3325,
+                          15.8 -8.7 -30.5,
+                          11.2 -9.78253 -29.875,
+                          15.8 -9.325 -30.3325,
+                          11.2 -9.325 -30.3325,
+                          11.2 -8.7 -30.5,
+                          15.8 -8.7 -30.5,
+                          15.8 -8.075 -30.3325,
+                          11.2 -9.325 -30.3325,
+                          15.8 -8.7 -30.5,
+                          11.2 -8.7 -30.5,
+                          11.2 -8.075 -30.3325,
+                          15.8 -8.075 -30.3325,
+                          15.8 -7.61747 -29.875,
+                          11.2 -8.7 -30.5,
+                          15.8 -8.075 -30.3325,
+                          11.2 -8.075 -30.3325,
+                          11.2 -8.075 -30.3325,
+                          15.8 -7.61747 -29.875,
+                          11.2 -7.61747 -29.875 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.25 0.25 0.25
+    }
+    Separator {
+        Normal {
+            vector      [ -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          1 1.00134e-12 5.83422e-14,
+                          1 1.00134e-12 5.83422e-14,
+                          1 1.00134e-12 5.83422e-14,
+                          0.951057 0.309017 2.95211e-14,
+                          0.951057 0.309017 2.95211e-14,
+                          1 1.0014e-12 5.83422e-14,
+                          1 1.00134e-12 5.83422e-14,
+                          1 1.00134e-12 5.83422e-14,
+                          1 1.00134e-12 5.83422e-14,
+                          0.951057 0.309017 2.95211e-14,
+                          1 1.0014e-12 5.83422e-14,
+                          1 1.0014e-12 5.83422e-14,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          1 1.00157e-12 5.83422e-14,
+                          1 1.00157e-12 5.83422e-14,
+                          0.953128 -0.302569 8.10314e-14,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          0.953128 -0.302569 8.10314e-14,
+                          0.953128 -0.302569 8.10314e-14,
+                          0.816904 -0.576773 9.61243e-14,
+                          1 1.00157e-12 5.83422e-14,
+                          0.953128 -0.302569 8.10314e-14,
+                          0.953128 -0.302569 8.10314e-14,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          0.816904 -0.576773 9.61243e-14,
+                          0.816904 -0.576773 9.61243e-14,
+                          0.604101 -0.796908 1.02206e-13,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          0.953128 -0.302569 8.10314e-14,
+                          0.816904 -0.576773 9.61243e-14,
+                          0.816904 -0.576773 9.61243e-14,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          0.604101 -0.796908 1.02206e-13,
+                          0.604101 -0.796908 1.02206e-13,
+                          0.334666 -0.942337 9.87065e-14,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          0.816904 -0.576773 9.61243e-14,
+                          0.604101 -0.796908 1.02206e-13,
+                          0.604101 -0.796908 1.02206e-13,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          0.334666 -0.942337 9.87065e-14,
+                          0.334666 -0.942337 9.87065e-14,
+                          0.334666 -0.942337 9.87065e-14,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          0.604101 -0.796908 1.02206e-13,
+                          0.334666 -0.942337 9.87065e-14,
+                          0.334666 -0.942337 9.87065e-14,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          0.334666 -0.942337 9.87065e-14,
+                          0.334666 -0.942337 9.87065e-14,
+                          0.169799 -0.985479 9.27128e-14,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          0.334666 -0.942337 9.87065e-14,
+                          0.334666 -0.942337 9.87065e-14,
+                          0.334666 -0.942337 9.87065e-14,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          0.169799 -0.985479 9.27128e-14,
+                          0.169799 -0.985479 9.27128e-14,
+                          1.00134e-12 -1 8.40265e-14,
+                          0.334666 -0.942337 9.87065e-14,
+                          0.169799 -0.985479 9.27128e-14,
+                          0.169799 -0.985479 9.27128e-14,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          1.00134e-12 -1 8.40265e-14,
+                          1.00134e-12 -1 8.40265e-14,
+                          1.00134e-12 -1 8.40265e-14,
+                          0.169799 -0.985479 9.27128e-14,
+                          1.00134e-12 -1 8.40265e-14,
+                          1.00134e-12 -1 8.40265e-14,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          1.00128e-12 -1 8.40265e-14,
+                          1.00128e-12 -1 8.40265e-14,
+                          -0.309017 -0.951057 6.18852e-14,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          1.00134e-12 -1 8.40265e-14,
+                          1.00134e-12 -1 8.40265e-14,
+                          1.00134e-12 -1 8.40265e-14,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -0.309017 -0.951057 6.18852e-14,
+                          -0.309017 -0.951057 6.18852e-14,
+                          -0.587785 -0.809017 3.36862e-14,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          1.00128e-12 -1 8.40265e-14,
+                          -0.309017 -0.951057 6.18852e-14,
+                          -0.309017 -0.951057 6.18852e-14,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -0.587785 -0.809017 3.36862e-14,
+                          -0.587785 -0.809017 3.36862e-14,
+                          -0.809017 -0.587785 2.18971e-15,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -0.309017 -0.951057 6.18852e-14,
+                          -0.587785 -0.809017 3.36862e-14,
+                          -0.587785 -0.809017 3.36862e-14,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -0.809017 -0.587785 2.18971e-15,
+                          -0.809017 -0.587785 2.18971e-15,
+                          -0.951057 -0.309017 -2.95211e-14,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -0.587785 -0.809017 3.36862e-14,
+                          -0.809017 -0.587785 2.18971e-15,
+                          -0.809017 -0.587785 2.18971e-15,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -0.951057 -0.309017 -2.95211e-14,
+                          -0.951057 -0.309017 -2.95211e-14,
+                          -1 -1.00134e-12 -5.83422e-14,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -5.83977e-14 8.39936e-14 1,
+                          -0.809017 -0.587785 2.18971e-15,
+                          -0.951057 -0.309017 -2.95211e-14,
+                          -0.951057 -0.309017 -2.95211e-14,
+                          -1 -1.00134e-12 -5.83422e-14,
+                          -1 -1.00134e-12 -5.83422e-14,
+                          -1 -1.00134e-12 -5.83422e-14,
+                          -0.951057 -0.309017 -2.95211e-14,
+                          -1 -1.00134e-12 -5.83422e-14,
+                          -1 -1.00134e-12 -5.83422e-14,
+                          -1 -1.00128e-12 -5.83422e-14,
+                          -1 -1.00128e-12 -5.83422e-14,
+                          -0.951057 0.309017 -8.14524e-14,
+                          -1 -1.00134e-12 -5.83422e-14,
+                          -1 -1.00134e-12 -5.83422e-14,
+                          -1 -1.00134e-12 -5.83422e-14,
+                          -0.951057 0.309017 -8.14524e-14,
+                          -0.951057 0.309017 -8.14524e-14,
+                          -0.809017 0.587785 -9.65894e-14,
+                          -1 -1.00128e-12 -5.83422e-14,
+                          -0.951057 0.309017 -8.14524e-14,
+                          -0.951057 0.309017 -8.14524e-14,
+                          -0.809017 0.587785 -9.65894e-14,
+                          -0.809017 0.587785 -9.65894e-14,
+                          -0.587785 0.809017 -1.02272e-13,
+                          -0.951057 0.309017 -8.14524e-14,
+                          -0.809017 0.587785 -9.65894e-14,
+                          -0.809017 0.587785 -9.65894e-14,
+                          -0.587785 0.809017 -1.02272e-13,
+                          -0.587785 0.809017 -1.02272e-13,
+                          -0.309017 0.951057 -9.79427e-14,
+                          -0.809017 0.587785 -9.65894e-14,
+                          -0.587785 0.809017 -1.02272e-13,
+                          -0.587785 0.809017 -1.02272e-13,
+                          -0.309017 0.951057 -9.79427e-14,
+                          -0.309017 0.951057 -9.79427e-14,
+                          -1.00134e-12 1 -8.40265e-14,
+                          -0.587785 0.809017 -1.02272e-13,
+                          -0.309017 0.951057 -9.79427e-14,
+                          -0.309017 0.951057 -9.79427e-14,
+                          -1.00134e-12 1 -8.40265e-14,
+                          -1.00134e-12 1 -8.40265e-14,
+                          -1.00134e-12 1 -8.40265e-14,
+                          -0.309017 0.951057 -9.79427e-14,
+                          -1.00134e-12 1 -8.40265e-14,
+                          -1.00134e-12 1 -8.40265e-14,
+                          -1.00112e-12 1 -8.40265e-14,
+                          -1.00134e-12 1 -8.40265e-14,
+                          0.309017 0.951057 -6.18852e-14,
+                          -1.00134e-12 1 -8.40265e-14,
+                          -1.00134e-12 1 -8.40265e-14,
+                          -1.00134e-12 1 -8.40265e-14,
+                          0.309017 0.951057 -6.18852e-14,
+                          0.309017 0.951057 -6.18852e-14,
+                          0.587785 0.809017 -3.36862e-14,
+                          0.309017 0.951057 -6.18852e-14,
+                          -1.00112e-12 1 -8.40265e-14,
+                          0.309017 0.951057 -6.18852e-14,
+                          0.587785 0.809017 -3.36862e-14,
+                          0.587785 0.809017 -3.36862e-14,
+                          0.809017 0.587785 -2.18971e-15,
+                          0.309017 0.951057 -6.18852e-14,
+                          0.587785 0.809017 -3.36862e-14,
+                          0.587785 0.809017 -3.36862e-14,
+                          0.809017 0.587785 -2.18971e-15,
+                          0.809017 0.587785 -2.18971e-15,
+                          0.951057 0.309017 2.95211e-14,
+                          0.587785 0.809017 -3.36862e-14,
+                          0.809017 0.587785 -2.18971e-15,
+                          0.809017 0.587785 -2.18971e-15,
+                          0.809017 0.587785 -2.18971e-15,
+                          0.951057 0.309017 2.95211e-14,
+                          0.951057 0.309017 2.95211e-14,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1,
+                          5.83977e-14 -8.39936e-14 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 65.8042 -19.2639 -31.5,
+                          66 -21.6758 -31.5,
+                          66 -20.5 -31.5,
+                          66 -21.6758 -33.5,
+                          66 -20.5 -31.5,
+                          66 -21.6758 -31.5,
+                          65.8042 -19.2639 -33.5,
+                          65.8042 -19.2639 -31.5,
+                          66 -20.5 -31.5,
+                          66 -20.5 -33.5,
+                          66 -20.5 -31.5,
+                          66 -21.6758 -33.5,
+                          65.8042 -19.2639 -33.5,
+                          66 -20.5 -31.5,
+                          66 -20.5 -33.5,
+                          65.8042 -19.2639 -31.5,
+                          65.8125 -22.8861 -31.5,
+                          66 -21.6758 -31.5,
+                          66 -21.6758 -33.5,
+                          66 -21.6758 -31.5,
+                          65.8125 -22.8861 -31.5,
+                          65.8042 -19.2639 -31.5,
+                          65.2676 -23.9829 -31.5,
+                          65.8125 -22.8861 -31.5,
+                          65.8125 -22.8861 -33.5,
+                          65.8125 -22.8861 -31.5,
+                          65.2676 -23.9829 -31.5,
+                          66 -21.6758 -33.5,
+                          65.8125 -22.8861 -31.5,
+                          65.8125 -22.8861 -33.5,
+                          65.2361 -18.1489 -31.5,
+                          64.4164 -24.8634 -31.5,
+                          65.2676 -23.9829 -31.5,
+                          65.2676 -23.9829 -33.5,
+                          65.2676 -23.9829 -31.5,
+                          64.4164 -24.8634 -31.5,
+                          65.8042 -19.2639 -31.5,
+                          65.2361 -18.1489 -31.5,
+                          65.2676 -23.9829 -31.5,
+                          65.8125 -22.8861 -33.5,
+                          65.2676 -23.9829 -31.5,
+                          65.2676 -23.9829 -33.5,
+                          64.3512 -17.2639 -31.5,
+                          63.3387 -25.4452 -31.5,
+                          64.4164 -24.8634 -31.5,
+                          64.4164 -24.8634 -33.5,
+                          64.4164 -24.8634 -31.5,
+                          63.3387 -25.4452 -31.5,
+                          65.2361 -18.1489 -31.5,
+                          64.3512 -17.2639 -31.5,
+                          64.4164 -24.8634 -31.5,
+                          65.2676 -23.9829 -33.5,
+                          64.4164 -24.8634 -31.5,
+                          64.4164 -24.8634 -33.5,
+                          62 -16.5 -31.5,
+                          20.4711 -40.6693 -31.5,
+                          63.3387 -25.4452 -31.5,
+                          63.3387 -25.4452 -33.5,
+                          63.3387 -25.4452 -31.5,
+                          20.4711 -40.6693 -31.5,
+                          63.2361 -16.6958 -31.5,
+                          62 -16.5 -31.5,
+                          63.3387 -25.4452 -31.5,
+                          64.3512 -17.2639 -31.5,
+                          63.2361 -16.6958 -31.5,
+                          63.3387 -25.4452 -31.5,
+                          64.4164 -24.8634 -33.5,
+                          63.3387 -25.4452 -31.5,
+                          63.3387 -25.4452 -33.5,
+                          -19.5 -16.5 -31.5,
+                          19.8116 -40.8419 -31.5,
+                          20.4711 -40.6693 -31.5,
+                          20.4711 -40.6693 -33.5,
+                          20.4711 -40.6693 -31.5,
+                          19.8116 -40.8419 -31.5,
+                          62 -16.5 -31.5,
+                          -19.5 -16.5 -31.5,
+                          20.4711 -40.6693 -31.5,
+                          63.3387 -25.4452 -33.5,
+                          20.4711 -40.6693 -31.5,
+                          20.4711 -40.6693 -33.5,
+                          -19.5 -16.5 -31.5,
+                          19.1324 -40.9 -31.5,
+                          19.8116 -40.8419 -31.5,
+                          19.8116 -40.8419 -33.5,
+                          19.8116 -40.8419 -31.5,
+                          19.1324 -40.9 -31.5,
+                          20.4711 -40.6693 -33.5,
+                          19.8116 -40.8419 -31.5,
+                          19.8116 -40.8419 -33.5,
+                          -19.5 -16.5 -31.5,
+                          -19.5 -40.9 -31.5,
+                          19.1324 -40.9 -31.5,
+                          19.1324 -40.9 -33.5,
+                          19.1324 -40.9 -31.5,
+                          -19.5 -40.9 -31.5,
+                          19.8116 -40.8419 -33.5,
+                          19.1324 -40.9 -31.5,
+                          19.1324 -40.9 -33.5,
+                          -20.7361 -16.6958 -31.5,
+                          -20.7361 -40.7042 -31.5,
+                          -19.5 -40.9 -31.5,
+                          -19.5 -40.9 -33.5,
+                          -19.5 -40.9 -31.5,
+                          -20.7361 -40.7042 -31.5,
+                          -19.5 -16.5 -31.5,
+                          -20.7361 -16.6958 -31.5,
+                          -19.5 -40.9 -31.5,
+                          19.1324 -40.9 -33.5,
+                          -19.5 -40.9 -31.5,
+                          -19.5 -40.9 -33.5,
+                          -21.8511 -17.2639 -31.5,
+                          -21.8511 -40.1361 -31.5,
+                          -20.7361 -40.7042 -31.5,
+                          -20.7361 -40.7042 -33.5,
+                          -20.7361 -40.7042 -31.5,
+                          -21.8511 -40.1361 -31.5,
+                          -20.7361 -16.6958 -31.5,
+                          -21.8511 -17.2639 -31.5,
+                          -20.7361 -40.7042 -31.5,
+                          -19.5 -40.9 -33.5,
+                          -20.7361 -40.7042 -31.5,
+                          -20.7361 -40.7042 -33.5,
+                          -22.7361 -18.1489 -31.5,
+                          -22.7361 -39.2511 -31.5,
+                          -21.8511 -40.1361 -31.5,
+                          -21.8511 -40.1361 -33.5,
+                          -21.8511 -40.1361 -31.5,
+                          -22.7361 -39.2511 -31.5,
+                          -21.8511 -17.2639 -31.5,
+                          -22.7361 -18.1489 -31.5,
+                          -21.8511 -40.1361 -31.5,
+                          -20.7361 -40.7042 -33.5,
+                          -21.8511 -40.1361 -31.5,
+                          -21.8511 -40.1361 -33.5,
+                          -23.3042 -19.2639 -31.5,
+                          -23.3042 -38.1361 -31.5,
+                          -22.7361 -39.2511 -31.5,
+                          -22.7361 -39.2511 -33.5,
+                          -22.7361 -39.2511 -31.5,
+                          -23.3042 -38.1361 -31.5,
+                          -22.7361 -18.1489 -31.5,
+                          -23.3042 -19.2639 -31.5,
+                          -22.7361 -39.2511 -31.5,
+                          -21.8511 -40.1361 -33.5,
+                          -22.7361 -39.2511 -31.5,
+                          -22.7361 -39.2511 -33.5,
+                          -23.5 -20.5 -31.5,
+                          -23.5 -36.9 -31.5,
+                          -23.3042 -38.1361 -31.5,
+                          -23.3042 -38.1361 -33.5,
+                          -23.3042 -38.1361 -31.5,
+                          -23.5 -36.9 -31.5,
+                          -23.3042 -19.2639 -31.5,
+                          -23.5 -20.5 -31.5,
+                          -23.3042 -38.1361 -31.5,
+                          -22.7361 -39.2511 -33.5,
+                          -23.3042 -38.1361 -31.5,
+                          -23.3042 -38.1361 -33.5,
+                          -23.5 -36.9 -33.5,
+                          -23.5 -36.9 -31.5,
+                          -23.5 -20.5 -31.5,
+                          -23.3042 -38.1361 -33.5,
+                          -23.5 -36.9 -31.5,
+                          -23.5 -36.9 -33.5,
+                          -23.5 -20.5 -33.5,
+                          -23.5 -20.5 -31.5,
+                          -23.3042 -19.2639 -31.5,
+                          -23.5 -36.9 -33.5,
+                          -23.5 -20.5 -31.5,
+                          -23.5 -20.5 -33.5,
+                          -23.3042 -19.2639 -33.5,
+                          -23.3042 -19.2639 -31.5,
+                          -22.7361 -18.1489 -31.5,
+                          -23.5 -20.5 -33.5,
+                          -23.3042 -19.2639 -31.5,
+                          -23.3042 -19.2639 -33.5,
+                          -22.7361 -18.1489 -33.5,
+                          -22.7361 -18.1489 -31.5,
+                          -21.8511 -17.2639 -31.5,
+                          -23.3042 -19.2639 -33.5,
+                          -22.7361 -18.1489 -31.5,
+                          -22.7361 -18.1489 -33.5,
+                          -21.8511 -17.2639 -33.5,
+                          -21.8511 -17.2639 -31.5,
+                          -20.7361 -16.6958 -31.5,
+                          -22.7361 -18.1489 -33.5,
+                          -21.8511 -17.2639 -31.5,
+                          -21.8511 -17.2639 -33.5,
+                          -20.7361 -16.6958 -33.5,
+                          -20.7361 -16.6958 -31.5,
+                          -19.5 -16.5 -31.5,
+                          -21.8511 -17.2639 -33.5,
+                          -20.7361 -16.6958 -31.5,
+                          -20.7361 -16.6958 -33.5,
+                          -19.5 -16.5 -33.5,
+                          -19.5 -16.5 -31.5,
+                          62 -16.5 -31.5,
+                          -20.7361 -16.6958 -33.5,
+                          -19.5 -16.5 -31.5,
+                          -19.5 -16.5 -33.5,
+                          62 -16.5 -33.5,
+                          62 -16.5 -31.5,
+                          63.2361 -16.6958 -31.5,
+                          -19.5 -16.5 -33.5,
+                          62 -16.5 -31.5,
+                          62 -16.5 -33.5,
+                          63.2361 -16.6958 -33.5,
+                          63.2361 -16.6958 -31.5,
+                          64.3512 -17.2639 -31.5,
+                          63.2361 -16.6958 -33.5,
+                          62 -16.5 -33.5,
+                          63.2361 -16.6958 -31.5,
+                          64.3512 -17.2639 -33.5,
+                          64.3512 -17.2639 -31.5,
+                          65.2361 -18.1489 -31.5,
+                          63.2361 -16.6958 -33.5,
+                          64.3512 -17.2639 -31.5,
+                          64.3512 -17.2639 -33.5,
+                          65.2361 -18.1489 -33.5,
+                          65.2361 -18.1489 -31.5,
+                          65.8042 -19.2639 -31.5,
+                          64.3512 -17.2639 -33.5,
+                          65.2361 -18.1489 -31.5,
+                          65.2361 -18.1489 -33.5,
+                          65.2361 -18.1489 -33.5,
+                          65.8042 -19.2639 -31.5,
+                          65.8042 -19.2639 -33.5,
+                          -19.5 -40.9 -33.5,
+                          -19.5 -16.5 -33.5,
+                          62 -16.5 -33.5,
+                          19.1324 -40.9 -33.5,
+                          -19.5 -40.9 -33.5,
+                          62 -16.5 -33.5,
+                          19.8116 -40.8419 -33.5,
+                          19.1324 -40.9 -33.5,
+                          62 -16.5 -33.5,
+                          20.4711 -40.6693 -33.5,
+                          19.8116 -40.8419 -33.5,
+                          62 -16.5 -33.5,
+                          63.2361 -16.6958 -33.5,
+                          20.4711 -40.6693 -33.5,
+                          62 -16.5 -33.5,
+                          -20.7361 -40.7042 -33.5,
+                          -20.7361 -16.6958 -33.5,
+                          -19.5 -16.5 -33.5,
+                          -19.5 -40.9 -33.5,
+                          -20.7361 -40.7042 -33.5,
+                          -19.5 -16.5 -33.5,
+                          -21.8511 -40.1361 -33.5,
+                          -21.8511 -17.2639 -33.5,
+                          -20.7361 -16.6958 -33.5,
+                          -20.7361 -40.7042 -33.5,
+                          -21.8511 -40.1361 -33.5,
+                          -20.7361 -16.6958 -33.5,
+                          -22.7361 -39.2511 -33.5,
+                          -22.7361 -18.1489 -33.5,
+                          -21.8511 -17.2639 -33.5,
+                          -21.8511 -40.1361 -33.5,
+                          -22.7361 -39.2511 -33.5,
+                          -21.8511 -17.2639 -33.5,
+                          -23.3042 -38.1361 -33.5,
+                          -23.3042 -19.2639 -33.5,
+                          -22.7361 -18.1489 -33.5,
+                          -22.7361 -39.2511 -33.5,
+                          -23.3042 -38.1361 -33.5,
+                          -22.7361 -18.1489 -33.5,
+                          -23.5 -36.9 -33.5,
+                          -23.5 -20.5 -33.5,
+                          -23.3042 -19.2639 -33.5,
+                          -23.3042 -38.1361 -33.5,
+                          -23.5 -36.9 -33.5,
+                          -23.3042 -19.2639 -33.5,
+                          63.2361 -16.6958 -33.5,
+                          63.3387 -25.4452 -33.5,
+                          20.4711 -40.6693 -33.5,
+                          64.3512 -17.2639 -33.5,
+                          64.4164 -24.8634 -33.5,
+                          63.3387 -25.4452 -33.5,
+                          63.2361 -16.6958 -33.5,
+                          64.3512 -17.2639 -33.5,
+                          63.3387 -25.4452 -33.5,
+                          65.2361 -18.1489 -33.5,
+                          65.2676 -23.9829 -33.5,
+                          64.4164 -24.8634 -33.5,
+                          64.3512 -17.2639 -33.5,
+                          65.2361 -18.1489 -33.5,
+                          64.4164 -24.8634 -33.5,
+                          65.8042 -19.2639 -33.5,
+                          65.8125 -22.8861 -33.5,
+                          65.2676 -23.9829 -33.5,
+                          65.2361 -18.1489 -33.5,
+                          65.8042 -19.2639 -33.5,
+                          65.2676 -23.9829 -33.5,
+                          66 -20.5 -33.5,
+                          66 -21.6758 -33.5,
+                          65.8125 -22.8861 -33.5,
+                          65.8042 -19.2639 -33.5,
+                          66 -20.5 -33.5,
+                          65.8125 -22.8861 -33.5 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+    Separator {
+        Normal {
+            vector      [ -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          0.549454 0.835524 0,
+                          0.549454 0.835524 0,
+                          0.711163 0.703028 1.73121e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          0.363732 0.931504 -1.73121e-17,
+                          0.363732 0.931504 -1.73121e-17,
+                          0.549454 0.835524 0,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          0.363732 0.931504 -1.73121e-17,
+                          0.549454 0.835524 0,
+                          0.549454 0.835524 0,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          0.711163 0.703028 1.73121e-17,
+                          0.711163 0.703028 1.73121e-17,
+                          0.84179 0.539806 3.38676e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          0.711163 0.703028 1.73121e-17,
+                          0.549454 0.835524 0,
+                          0.711163 0.703028 1.73121e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          0.84179 0.539806 3.38676e-17,
+                          0.84179 0.539806 3.38676e-17,
+                          0.935626 0.352992 4.8943e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          0.711163 0.703028 1.73121e-17,
+                          0.84179 0.539806 3.38676e-17,
+                          0.84179 0.539806 3.38676e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          0.935626 0.352992 4.8943e-17,
+                          0.935626 0.352992 4.8943e-17,
+                          0.988572 0.15075 6.18792e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          0.84179 0.539806 3.38676e-17,
+                          0.935626 0.352992 4.8943e-17,
+                          0.935626 0.352992 4.8943e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          0.988572 0.15075 6.18792e-17,
+                          0.988572 0.15075 6.18792e-17,
+                          0.998312 -0.0580795 7.21111e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          0.935626 0.352992 4.8943e-17,
+                          0.988572 0.15075 6.18792e-17,
+                          0.988572 0.15075 6.18792e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          0.998312 -0.0580795 7.21111e-17,
+                          0.998312 -0.0580795 7.21111e-17,
+                          0.964421 -0.264371 7.91914e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          0.988572 0.15075 6.18792e-17,
+                          0.998312 -0.0580795 7.21111e-17,
+                          0.998312 -0.0580795 7.21111e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          0.964421 -0.264371 7.91914e-17,
+                          0.964421 -0.264371 7.91914e-17,
+                          0.88838 -0.459108 8.28106e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          0.998312 -0.0580795 7.21111e-17,
+                          0.964421 -0.264371 7.91914e-17,
+                          0.964421 -0.264371 7.91914e-17,
+                          0.88838 -0.459108 8.28106e-17,
+                          0.88838 -0.459108 8.28106e-17,
+                          0.773513 -0.63378 8.28106e-17,
+                          0.964421 -0.264371 7.91914e-17,
+                          0.88838 -0.459108 8.28106e-17,
+                          0.88838 -0.459108 8.28106e-17,
+                          0.773513 -0.63378 8.28106e-17,
+                          0.773513 -0.63378 8.28106e-17,
+                          0.62484 -0.780753 7.91914e-17,
+                          0.88838 -0.459108 8.28106e-17,
+                          0.773513 -0.63378 8.28106e-17,
+                          0.773513 -0.63378 8.28106e-17,
+                          0.62484 -0.780753 7.91914e-17,
+                          0.62484 -0.780753 7.91914e-17,
+                          0.448858 -0.893603 7.21111e-17,
+                          0.773513 -0.63378 8.28106e-17,
+                          0.62484 -0.780753 7.91914e-17,
+                          0.62484 -0.780753 7.91914e-17,
+                          0.448858 -0.893603 7.21111e-17,
+                          0.448858 -0.893603 7.21111e-17,
+                          0.253258 -0.967399 6.18792e-17,
+                          0.62484 -0.780753 7.91914e-17,
+                          0.448858 -0.893603 7.21111e-17,
+                          0.448858 -0.893603 7.21111e-17,
+                          0.253258 -0.967399 6.18792e-17,
+                          0.253258 -0.967399 6.18792e-17,
+                          0.0465907 -0.998914 4.8943e-17,
+                          0.448858 -0.893603 7.21111e-17,
+                          0.253258 -0.967399 6.18792e-17,
+                          0.253258 -0.967399 6.18792e-17,
+                          0.0465907 -0.998914 4.8943e-17,
+                          0.0465907 -0.998914 4.8943e-17,
+                          -0.162113 -0.986772 3.38676e-17,
+                          0.253258 -0.967399 6.18792e-17,
+                          0.0465907 -0.998914 4.8943e-17,
+                          0.0465907 -0.998914 4.8943e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -0.162113 -0.986772 3.38676e-17,
+                          -0.162113 -0.986772 3.38676e-17,
+                          -0.363732 -0.931504 1.73121e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          0.0465907 -0.998914 4.8943e-17,
+                          -0.162113 -0.986772 3.38676e-17,
+                          -0.162113 -0.986772 3.38676e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -0.363732 -0.931504 1.73121e-17,
+                          -0.363732 -0.931504 1.73121e-17,
+                          -0.549454 -0.835524 0,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -0.162113 -0.986772 3.38676e-17,
+                          -0.363732 -0.931504 1.73121e-17,
+                          -0.363732 -0.931504 1.73121e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -0.549454 -0.835524 0,
+                          -0.549454 -0.835524 0,
+                          -0.711163 -0.703028 -1.73121e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -0.363732 -0.931504 1.73121e-17,
+                          -0.549454 -0.835524 0,
+                          -0.549454 -0.835524 0,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -0.711163 -0.703028 -1.73121e-17,
+                          -0.711163 -0.703028 -1.73121e-17,
+                          -0.84179 -0.539806 -3.38676e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -0.549454 -0.835524 0,
+                          -0.711163 -0.703028 -1.73121e-17,
+                          -0.711163 -0.703028 -1.73121e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -0.84179 -0.539806 -3.38676e-17,
+                          -0.84179 -0.539806 -3.38676e-17,
+                          -0.935626 -0.352992 -4.8943e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -0.711163 -0.703028 -1.73121e-17,
+                          -0.84179 -0.539806 -3.38676e-17,
+                          -0.84179 -0.539806 -3.38676e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -0.935626 -0.352992 -4.8943e-17,
+                          -0.935626 -0.352992 -4.8943e-17,
+                          -0.988572 -0.15075 -6.18792e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -0.84179 -0.539806 -3.38676e-17,
+                          -0.935626 -0.352992 -4.8943e-17,
+                          -0.935626 -0.352992 -4.8943e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -0.988572 -0.15075 -6.18792e-17,
+                          -0.988572 -0.15075 -6.18792e-17,
+                          -0.998312 0.0580795 -7.21111e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -0.935626 -0.352992 -4.8943e-17,
+                          -0.988572 -0.15075 -6.18792e-17,
+                          -0.988572 -0.15075 -6.18792e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -0.998312 0.0580795 -7.21111e-17,
+                          -0.998312 0.0580795 -7.21111e-17,
+                          -0.964421 0.264371 -7.91914e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -0.988572 -0.15075 -6.18792e-17,
+                          -0.998312 0.0580795 -7.21111e-17,
+                          -0.998312 0.0580795 -7.21111e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -0.964421 0.264371 -7.91914e-17,
+                          -0.964421 0.264371 -7.91914e-17,
+                          -0.88838 0.459108 -8.28106e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -0.998312 0.0580795 -7.21111e-17,
+                          -0.964421 0.264371 -7.91914e-17,
+                          -0.964421 0.264371 -7.91914e-17,
+                          -0.88838 0.459108 -8.28106e-17,
+                          -0.88838 0.459108 -8.28106e-17,
+                          -0.773513 0.63378 -8.28106e-17,
+                          -0.964421 0.264371 -7.91914e-17,
+                          -0.88838 0.459108 -8.28106e-17,
+                          -0.88838 0.459108 -8.28106e-17,
+                          -0.773513 0.63378 -8.28106e-17,
+                          -0.773513 0.63378 -8.28106e-17,
+                          -0.62484 0.780753 -7.91914e-17,
+                          -0.88838 0.459108 -8.28106e-17,
+                          -0.773513 0.63378 -8.28106e-17,
+                          -0.773513 0.63378 -8.28106e-17,
+                          -0.62484 0.780753 -7.91914e-17,
+                          -0.62484 0.780753 -7.91914e-17,
+                          -0.448858 0.893603 -7.21111e-17,
+                          -0.773513 0.63378 -8.28106e-17,
+                          -0.62484 0.780753 -7.91914e-17,
+                          -0.62484 0.780753 -7.91914e-17,
+                          -0.448858 0.893603 -7.21111e-17,
+                          -0.448858 0.893603 -7.21111e-17,
+                          -0.253258 0.967399 -6.18792e-17,
+                          -0.62484 0.780753 -7.91914e-17,
+                          -0.448858 0.893603 -7.21111e-17,
+                          -0.448858 0.893603 -7.21111e-17,
+                          -0.253258 0.967399 -6.18792e-17,
+                          -0.253258 0.967399 -6.18792e-17,
+                          -0.0465907 0.998914 -4.8943e-17,
+                          -0.448858 0.893603 -7.21111e-17,
+                          -0.253258 0.967399 -6.18792e-17,
+                          -0.253258 0.967399 -6.18792e-17,
+                          -0.0465907 0.998914 -4.8943e-17,
+                          -0.0465907 0.998914 -4.8943e-17,
+                          0.162113 0.986772 -3.38676e-17,
+                          -0.253258 0.967399 -6.18792e-17,
+                          -0.0465907 0.998914 -4.8943e-17,
+                          -0.0465907 0.998914 -4.8943e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          0.162113 0.986772 -3.38676e-17,
+                          0.162113 0.986772 -3.38676e-17,
+                          0.363732 0.931504 -1.73121e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -0.0465907 0.998914 -4.8943e-17,
+                          0.162113 0.986772 -3.38676e-17,
+                          0.162113 0.986772 -3.38676e-17,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          0.162113 0.986772 -3.38676e-17,
+                          0.363732 0.931504 -1.73121e-17,
+                          0.363732 0.931504 -1.73121e-17,
+                          0.835524 -0.549454 8.32667e-17,
+                          0.835524 -0.549454 8.32667e-17,
+                          0.98219 -0.187888 7.69284e-17,
+                          0.561656 -0.827371 7.69284e-17,
+                          0.561656 -0.827371 7.69284e-17,
+                          0.835524 -0.549454 8.32667e-17,
+                          0.835524 -0.549454 8.32667e-17,
+                          0.561656 -0.827371 7.69284e-17,
+                          0.835524 -0.549454 8.32667e-17,
+                          0.98219 -0.187888 7.69284e-17,
+                          0.98219 -0.187888 7.69284e-17,
+                          0.979327 0.202282 5.88785e-17,
+                          0.98219 -0.187888 7.69284e-17,
+                          0.835524 -0.549454 8.32667e-17,
+                          0.98219 -0.187888 7.69284e-17,
+                          0.979327 0.202282 5.88785e-17,
+                          0.979327 0.202282 5.88785e-17,
+                          0.827371 0.561656 3.18648e-17,
+                          0.98219 -0.187888 7.69284e-17,
+                          0.979327 0.202282 5.88785e-17,
+                          0.979327 0.202282 5.88785e-17,
+                          0.827371 0.561656 3.18648e-17,
+                          0.827371 0.561656 3.18648e-17,
+                          0.549454 0.835524 0,
+                          0.979327 0.202282 5.88785e-17,
+                          0.827371 0.561656 3.18648e-17,
+                          0.827371 0.561656 3.18648e-17,
+                          0.549454 0.835524 0,
+                          0.549454 0.835524 0,
+                          0.187888 0.98219 -3.18648e-17,
+                          0.827371 0.561656 3.18648e-17,
+                          0.549454 0.835524 0,
+                          0.549454 0.835524 0,
+                          0.187888 0.98219 -3.18648e-17,
+                          0.187888 0.98219 -3.18648e-17,
+                          -0.202282 0.979327 -5.88785e-17,
+                          0.549454 0.835524 0,
+                          0.187888 0.98219 -3.18648e-17,
+                          0.187888 0.98219 -3.18648e-17,
+                          -0.202282 0.979327 -5.88785e-17,
+                          -0.202282 0.979327 -5.88785e-17,
+                          -0.561656 0.827371 -7.69284e-17,
+                          0.187888 0.98219 -3.18648e-17,
+                          -0.202282 0.979327 -5.88785e-17,
+                          -0.202282 0.979327 -5.88785e-17,
+                          -0.561656 0.827371 -7.69284e-17,
+                          -0.561656 0.827371 -7.69284e-17,
+                          -0.835524 0.549454 -8.32667e-17,
+                          -0.202282 0.979327 -5.88785e-17,
+                          -0.561656 0.827371 -7.69284e-17,
+                          -0.561656 0.827371 -7.69284e-17,
+                          -0.835524 0.549454 -8.32667e-17,
+                          -0.835524 0.549454 -8.32667e-17,
+                          -0.98219 0.187888 -7.69284e-17,
+                          -0.561656 0.827371 -7.69284e-17,
+                          -0.835524 0.549454 -8.32667e-17,
+                          -0.835524 0.549454 -8.32667e-17,
+                          -0.98219 0.187888 -7.69284e-17,
+                          -0.98219 0.187888 -7.69284e-17,
+                          -0.979327 -0.202282 -5.88785e-17,
+                          -0.98219 0.187888 -7.69284e-17,
+                          -0.835524 0.549454 -8.32667e-17,
+                          -0.98219 0.187888 -7.69284e-17,
+                          -0.979327 -0.202282 -5.88785e-17,
+                          -0.979327 -0.202282 -5.88785e-17,
+                          -0.827371 -0.561656 -3.18648e-17,
+                          -0.979327 -0.202282 -5.88785e-17,
+                          -0.98219 0.187888 -7.69284e-17,
+                          -0.979327 -0.202282 -5.88785e-17,
+                          -0.827371 -0.561656 -3.18648e-17,
+                          -0.827371 -0.561656 -3.18648e-17,
+                          -0.549454 -0.835524 0,
+                          -0.827371 -0.561656 -3.18648e-17,
+                          -0.979327 -0.202282 -5.88785e-17,
+                          -0.827371 -0.561656 -3.18648e-17,
+                          -0.549454 -0.835524 0,
+                          -0.549454 -0.835524 0,
+                          -0.187888 -0.98219 3.18648e-17,
+                          -0.549454 -0.835524 0,
+                          -0.827371 -0.561656 -3.18648e-17,
+                          -0.549454 -0.835524 0,
+                          -0.187888 -0.98219 3.18648e-17,
+                          -0.187888 -0.98219 3.18648e-17,
+                          0.202282 -0.979327 5.88785e-17,
+                          -0.187888 -0.98219 3.18648e-17,
+                          -0.549454 -0.835524 0,
+                          -0.187888 -0.98219 3.18648e-17,
+                          0.202282 -0.979327 5.88785e-17,
+                          0.202282 -0.979327 5.88785e-17,
+                          0.561656 -0.827371 7.69284e-17,
+                          0.202282 -0.979327 5.88785e-17,
+                          -0.187888 -0.98219 3.18648e-17,
+                          0.202282 -0.979327 5.88785e-17,
+                          0.561656 -0.827371 7.69284e-17,
+                          0.202282 -0.979327 5.88785e-17,
+                          0.561656 -0.827371 7.69284e-17,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          5.85643e-14 -8.40073e-14 -1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1,
+                          -5.85643e-14 8.40073e-14 1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 3.91731 0.809138 5,
+                          12.4453 12.303 5,
+                          9.61545 14.6217 5,
+                          9.61545 14.6217 -5.32907e-15,
+                          9.61545 14.6217 5,
+                          12.4453 12.303 5,
+                          2.19782 3.34209 5,
+                          9.61545 14.6217 5,
+                          6.36533 16.3013 5,
+                          6.36533 16.3013 -5.32907e-15,
+                          6.36533 16.3013 5,
+                          9.61545 14.6217 5,
+                          3.30948 2.24663 5,
+                          3.91731 0.809138 5,
+                          9.61545 14.6217 5,
+                          2.19782 3.34209 5,
+                          3.30948 2.24663 5,
+                          9.61545 14.6217 5,
+                          6.36533 16.3013 -5.32907e-15,
+                          9.61545 14.6217 5,
+                          9.61545 14.6217 -5.32907e-15,
+                          -2.83699 -17.2685 5,
+                          14.7313 9.44661 5,
+                          12.4453 12.303 5,
+                          12.4453 12.303 -5.32907e-15,
+                          12.4453 12.303 5,
+                          14.7313 9.44661 5,
+                          3.3421 -2.19782 5,
+                          -2.83699 -17.2685 5,
+                          12.4453 12.303 5,
+                          3.92876 -0.751544 5,
+                          3.3421 -2.19782 5,
+                          12.4453 12.303 5,
+                          3.91731 0.809138 5,
+                          3.92876 -0.751544 5,
+                          12.4453 12.303 5,
+                          12.4453 12.303 -5.32907e-15,
+                          9.61545 14.6217 -5.32907e-15,
+                          12.4453 12.303 5,
+                          0.815346 -17.481 5,
+                          16.3735 6.17735 5,
+                          14.7313 9.44661 5,
+                          14.7313 9.44661 -4.44089e-15,
+                          14.7313 9.44661 5,
+                          16.3735 6.17735 5,
+                          -2.83699 -17.2685 5,
+                          0.815346 -17.481 5,
+                          14.7313 9.44661 5,
+                          12.4453 12.303 -5.32907e-15,
+                          14.7313 9.44661 5,
+                          14.7313 9.44661 -4.44089e-15,
+                          4.43204 -16.9295 5,
+                          17.3 2.63811 5,
+                          16.3735 6.17735 5,
+                          16.3735 6.17735 -4.44089e-15,
+                          16.3735 6.17735 5,
+                          17.3 2.63811 5,
+                          0.815346 -17.481 5,
+                          4.43204 -16.9295 5,
+                          16.3735 6.17735 5,
+                          14.7313 9.44661 -4.44089e-15,
+                          16.3735 6.17735 5,
+                          16.3735 6.17735 -4.44089e-15,
+                          7.85501 -15.6381 5,
+                          17.4705 -1.01639 5,
+                          17.3 2.63811 5,
+                          17.3 2.63811 -4.44089e-15,
+                          17.3 2.63811 5,
+                          17.4705 -1.01639 5,
+                          4.43204 -16.9295 5,
+                          7.85501 -15.6381 5,
+                          17.3 2.63811 5,
+                          16.3735 6.17735 -4.44089e-15,
+                          17.3 2.63811 5,
+                          17.3 2.63811 -4.44089e-15,
+                          10.9347 -13.6632 5,
+                          16.8774 -4.62648 5,
+                          17.4705 -1.01639 5,
+                          17.4705 -1.01639 -4.44089e-15,
+                          17.4705 -1.01639 5,
+                          16.8774 -4.62648 5,
+                          7.85501 -15.6381 5,
+                          10.9347 -13.6632 5,
+                          17.4705 -1.01639 5,
+                          17.3 2.63811 -4.44089e-15,
+                          17.4705 -1.01639 5,
+                          17.4705 -1.01639 -4.44089e-15,
+                          13.5365 -11.0912 5,
+                          15.5467 -8.03439 5,
+                          16.8774 -4.62648 5,
+                          16.8774 -4.62648 -3.55271e-15,
+                          16.8774 -4.62648 5,
+                          15.5467 -8.03439 5,
+                          10.9347 -13.6632 5,
+                          13.5365 -11.0912 5,
+                          16.8774 -4.62648 5,
+                          17.4705 -1.01639 -4.44089e-15,
+                          16.8774 -4.62648 5,
+                          16.8774 -4.62648 -3.55271e-15,
+                          15.5467 -8.03439 -3.55271e-15,
+                          15.5467 -8.03439 5,
+                          13.5365 -11.0912 5,
+                          16.8774 -4.62648 -3.55271e-15,
+                          15.5467 -8.03439 5,
+                          15.5467 -8.03439 -3.55271e-15,
+                          13.5365 -11.0912 -3.55271e-15,
+                          13.5365 -11.0912 5,
+                          10.9347 -13.6632 5,
+                          15.5467 -8.03439 -3.55271e-15,
+                          13.5365 -11.0912 5,
+                          13.5365 -11.0912 -3.55271e-15,
+                          10.9347 -13.6632 -3.55271e-15,
+                          10.9347 -13.6632 5,
+                          7.85501 -15.6381 5,
+                          13.5365 -11.0912 -3.55271e-15,
+                          10.9347 -13.6632 5,
+                          10.9347 -13.6632 -3.55271e-15,
+                          7.85501 -15.6381 -4.44089e-15,
+                          7.85501 -15.6381 5,
+                          4.43204 -16.9295 5,
+                          10.9347 -13.6632 -3.55271e-15,
+                          7.85501 -15.6381 5,
+                          7.85501 -15.6381 -4.44089e-15,
+                          4.43204 -16.9295 -4.44089e-15,
+                          4.43204 -16.9295 5,
+                          0.815346 -17.481 5,
+                          7.85501 -15.6381 -4.44089e-15,
+                          4.43204 -16.9295 5,
+                          4.43204 -16.9295 -4.44089e-15,
+                          0.815346 -17.481 -4.44089e-15,
+                          0.815346 -17.481 5,
+                          -2.83699 -17.2685 5,
+                          4.43204 -16.9295 -4.44089e-15,
+                          0.815346 -17.481 5,
+                          0.815346 -17.481 -4.44089e-15,
+                          2.24662 -3.30949 5,
+                          -6.36533 -16.3013 5,
+                          -2.83699 -17.2685 5,
+                          -2.83699 -17.2685 -4.44089e-15,
+                          -2.83699 -17.2685 5,
+                          -6.36533 -16.3013 5,
+                          2.24662 -3.30949 5,
+                          -2.83699 -17.2685 5,
+                          3.3421 -2.19782 5,
+                          0.815346 -17.481 -4.44089e-15,
+                          -2.83699 -17.2685 5,
+                          -2.83699 -17.2685 -4.44089e-15,
+                          -2.19782 -3.34209 5,
+                          -9.61545 -14.6217 5,
+                          -6.36533 -16.3013 5,
+                          -6.36533 -16.3013 -5.32907e-15,
+                          -6.36533 -16.3013 5,
+                          -9.61545 -14.6217 5,
+                          -0.751561 -3.92876 5,
+                          -2.19782 -3.34209 5,
+                          -6.36533 -16.3013 5,
+                          0.809115 -3.91731 5,
+                          -0.751561 -3.92876 5,
+                          -6.36533 -16.3013 5,
+                          2.24662 -3.30949 5,
+                          0.809115 -3.91731 5,
+                          -6.36533 -16.3013 5,
+                          -2.83699 -17.2685 -4.44089e-15,
+                          -6.36533 -16.3013 5,
+                          -6.36533 -16.3013 -5.32907e-15,
+                          -3.91731 -0.809138 5,
+                          -12.4453 -12.303 5,
+                          -9.61545 -14.6217 5,
+                          -9.61545 -14.6217 -5.32907e-15,
+                          -9.61545 -14.6217 5,
+                          -12.4453 -12.303 5,
+                          -3.30948 -2.24663 5,
+                          -3.91731 -0.809138 5,
+                          -9.61545 -14.6217 5,
+                          -2.19782 -3.34209 5,
+                          -3.30948 -2.24663 5,
+                          -9.61545 -14.6217 5,
+                          -6.36533 -16.3013 -5.32907e-15,
+                          -9.61545 -14.6217 5,
+                          -9.61545 -14.6217 -5.32907e-15,
+                          2.83699 17.2685 5,
+                          -14.7313 -9.44661 5,
+                          -12.4453 -12.303 5,
+                          -12.4453 -12.303 -5.32907e-15,
+                          -12.4453 -12.303 5,
+                          -14.7313 -9.44661 5,
+                          -3.3421 2.19782 5,
+                          2.83699 17.2685 5,
+                          -12.4453 -12.303 5,
+                          -3.92876 0.751544 5,
+                          -3.3421 2.19782 5,
+                          -12.4453 -12.303 5,
+                          -3.91731 -0.809138 5,
+                          -3.92876 0.751544 5,
+                          -12.4453 -12.303 5,
+                          -9.61545 -14.6217 -5.32907e-15,
+                          -12.4453 -12.303 5,
+                          -12.4453 -12.303 -5.32907e-15,
+                          -0.815346 17.481 5,
+                          -16.3735 -6.17735 5,
+                          -14.7313 -9.44661 5,
+                          -14.7313 -9.44661 -6.21725e-15,
+                          -14.7313 -9.44661 5,
+                          -16.3735 -6.17735 5,
+                          2.83699 17.2685 5,
+                          -0.815346 17.481 5,
+                          -14.7313 -9.44661 5,
+                          -12.4453 -12.303 -5.32907e-15,
+                          -14.7313 -9.44661 5,
+                          -14.7313 -9.44661 -6.21725e-15,
+                          -4.43204 16.9295 5,
+                          -17.3 -2.63811 5,
+                          -16.3735 -6.17735 5,
+                          -16.3735 -6.17735 -6.21725e-15,
+                          -16.3735 -6.17735 5,
+                          -17.3 -2.63811 5,
+                          -0.815346 17.481 5,
+                          -4.43204 16.9295 5,
+                          -16.3735 -6.17735 5,
+                          -14.7313 -9.44661 -6.21725e-15,
+                          -16.3735 -6.17735 5,
+                          -16.3735 -6.17735 -6.21725e-15,
+                          -7.85501 15.6381 5,
+                          -17.4705 1.01639 5,
+                          -17.3 -2.63811 5,
+                          -17.3 -2.63811 -6.21725e-15,
+                          -17.3 -2.63811 5,
+                          -17.4705 1.01639 5,
+                          -4.43204 16.9295 5,
+                          -7.85501 15.6381 5,
+                          -17.3 -2.63811 5,
+                          -16.3735 -6.17735 -6.21725e-15,
+                          -17.3 -2.63811 5,
+                          -17.3 -2.63811 -6.21725e-15,
+                          -10.9347 13.6632 5,
+                          -16.8774 4.62648 5,
+                          -17.4705 1.01639 5,
+                          -17.4705 1.01639 -6.21725e-15,
+                          -17.4705 1.01639 5,
+                          -16.8774 4.62648 5,
+                          -7.85501 15.6381 5,
+                          -10.9347 13.6632 5,
+                          -17.4705 1.01639 5,
+                          -17.3 -2.63811 -6.21725e-15,
+                          -17.4705 1.01639 5,
+                          -17.4705 1.01639 -6.21725e-15,
+                          -13.5365 11.0912 5,
+                          -15.5467 8.03439 5,
+                          -16.8774 4.62648 5,
+                          -16.8774 4.62648 -7.10543e-15,
+                          -16.8774 4.62648 5,
+                          -15.5467 8.03439 5,
+                          -10.9347 13.6632 5,
+                          -13.5365 11.0912 5,
+                          -16.8774 4.62648 5,
+                          -17.4705 1.01639 -6.21725e-15,
+                          -16.8774 4.62648 5,
+                          -16.8774 4.62648 -7.10543e-15,
+                          -15.5467 8.03439 -7.10543e-15,
+                          -15.5467 8.03439 5,
+                          -13.5365 11.0912 5,
+                          -16.8774 4.62648 -7.10543e-15,
+                          -15.5467 8.03439 5,
+                          -15.5467 8.03439 -7.10543e-15,
+                          -13.5365 11.0912 -7.10543e-15,
+                          -13.5365 11.0912 5,
+                          -10.9347 13.6632 5,
+                          -15.5467 8.03439 -7.10543e-15,
+                          -13.5365 11.0912 5,
+                          -13.5365 11.0912 -7.10543e-15,
+                          -10.9347 13.6632 -7.10543e-15,
+                          -10.9347 13.6632 5,
+                          -7.85501 15.6381 5,
+                          -13.5365 11.0912 -7.10543e-15,
+                          -10.9347 13.6632 5,
+                          -10.9347 13.6632 -7.10543e-15,
+                          -7.85501 15.6381 -6.21725e-15,
+                          -7.85501 15.6381 5,
+                          -4.43204 16.9295 5,
+                          -10.9347 13.6632 -7.10543e-15,
+                          -7.85501 15.6381 5,
+                          -7.85501 15.6381 -6.21725e-15,
+                          -4.43204 16.9295 -6.21725e-15,
+                          -4.43204 16.9295 5,
+                          -0.815346 17.481 5,
+                          -7.85501 15.6381 -6.21725e-15,
+                          -4.43204 16.9295 5,
+                          -4.43204 16.9295 -6.21725e-15,
+                          -0.815346 17.481 -6.21725e-15,
+                          -0.815346 17.481 5,
+                          2.83699 17.2685 5,
+                          -4.43204 16.9295 -6.21725e-15,
+                          -0.815346 17.481 5,
+                          -0.815346 17.481 -6.21725e-15,
+                          -2.24662 3.30949 5,
+                          6.36533 16.3013 5,
+                          2.83699 17.2685 5,
+                          2.83699 17.2685 -6.21725e-15,
+                          2.83699 17.2685 5,
+                          6.36533 16.3013 5,
+                          -3.3421 2.19782 5,
+                          -2.24662 3.30949 5,
+                          2.83699 17.2685 5,
+                          -0.815346 17.481 -6.21725e-15,
+                          2.83699 17.2685 5,
+                          2.83699 17.2685 -6.21725e-15,
+                          0.751561 3.92876 5,
+                          2.19782 3.34209 5,
+                          6.36533 16.3013 5,
+                          -0.809115 3.91731 5,
+                          0.751561 3.92876 5,
+                          6.36533 16.3013 5,
+                          -2.24662 3.30949 5,
+                          -0.809115 3.91731 5,
+                          6.36533 16.3013 5,
+                          2.83699 17.2685 -6.21725e-15,
+                          6.36533 16.3013 5,
+                          6.36533 16.3013 -5.32907e-15,
+                          3.3421 -2.19782 10.8,
+                          3.3421 -2.19782 5,
+                          3.92876 -0.751544 5,
+                          2.24661 -3.30949 10.8,
+                          2.24662 -3.30949 5,
+                          3.3421 -2.19782 5,
+                          3.3421 -2.19782 10.8,
+                          2.24661 -3.30949 10.8,
+                          3.3421 -2.19782 5,
+                          3.92876 -0.751542 10.8,
+                          3.92876 -0.751544 5,
+                          3.91731 0.809138 5,
+                          3.92876 -0.751542 10.8,
+                          3.3421 -2.19782 10.8,
+                          3.92876 -0.751544 5,
+                          3.91731 0.809126 10.8,
+                          3.91731 0.809138 5,
+                          3.30948 2.24663 5,
+                          3.92876 -0.751542 10.8,
+                          3.91731 0.809138 5,
+                          3.91731 0.809126 10.8,
+                          3.30949 2.24661 10.8,
+                          3.30948 2.24663 5,
+                          2.19782 3.34209 5,
+                          3.91731 0.809126 10.8,
+                          3.30948 2.24663 5,
+                          3.30949 2.24661 10.8,
+                          2.19782 3.3421 10.8,
+                          2.19782 3.34209 5,
+                          0.751561 3.92876 5,
+                          3.30949 2.24661 10.8,
+                          2.19782 3.34209 5,
+                          2.19782 3.3421 10.8,
+                          0.751542 3.92876 10.8,
+                          0.751561 3.92876 5,
+                          -0.809115 3.91731 5,
+                          2.19782 3.3421 10.8,
+                          0.751561 3.92876 5,
+                          0.751542 3.92876 10.8,
+                          -0.809126 3.91731 10.8,
+                          -0.809115 3.91731 5,
+                          -2.24662 3.30949 5,
+                          0.751542 3.92876 10.8,
+                          -0.809115 3.91731 5,
+                          -0.809126 3.91731 10.8,
+                          -2.24661 3.30949 10.8,
+                          -2.24662 3.30949 5,
+                          -3.3421 2.19782 5,
+                          -0.809126 3.91731 10.8,
+                          -2.24662 3.30949 5,
+                          -2.24661 3.30949 10.8,
+                          -3.3421 2.19782 10.8,
+                          -3.3421 2.19782 5,
+                          -3.92876 0.751544 5,
+                          -2.24661 3.30949 10.8,
+                          -3.3421 2.19782 5,
+                          -3.3421 2.19782 10.8,
+                          -3.92876 0.751542 10.8,
+                          -3.92876 0.751544 5,
+                          -3.91731 -0.809138 5,
+                          -3.92876 0.751542 10.8,
+                          -3.3421 2.19782 10.8,
+                          -3.92876 0.751544 5,
+                          -3.91731 -0.809126 10.8,
+                          -3.91731 -0.809138 5,
+                          -3.30948 -2.24663 5,
+                          -3.91731 -0.809126 10.8,
+                          -3.92876 0.751542 10.8,
+                          -3.91731 -0.809138 5,
+                          -3.30949 -2.24661 10.8,
+                          -3.30948 -2.24663 5,
+                          -2.19782 -3.34209 5,
+                          -3.30949 -2.24661 10.8,
+                          -3.91731 -0.809126 10.8,
+                          -3.30948 -2.24663 5,
+                          -2.19782 -3.3421 10.8,
+                          -2.19782 -3.34209 5,
+                          -0.751561 -3.92876 5,
+                          -2.19782 -3.3421 10.8,
+                          -3.30949 -2.24661 10.8,
+                          -2.19782 -3.34209 5,
+                          -0.751542 -3.92876 10.8,
+                          -0.751561 -3.92876 5,
+                          0.809115 -3.91731 5,
+                          -0.751542 -3.92876 10.8,
+                          -2.19782 -3.3421 10.8,
+                          -0.751561 -3.92876 5,
+                          0.809126 -3.91731 10.8,
+                          0.809115 -3.91731 5,
+                          2.24662 -3.30949 5,
+                          0.809126 -3.91731 10.8,
+                          -0.751542 -3.92876 10.8,
+                          0.809115 -3.91731 5,
+                          2.24661 -3.30949 10.8,
+                          0.809126 -3.91731 10.8,
+                          2.24662 -3.30949 5,
+                          -12.4453 -12.303 -5.32907e-15,
+                          6.36533 16.3013 -5.32907e-15,
+                          9.61545 14.6217 -5.32907e-15,
+                          -9.61545 -14.6217 -5.32907e-15,
+                          -12.4453 -12.303 -5.32907e-15,
+                          9.61545 14.6217 -5.32907e-15,
+                          12.4453 12.303 -5.32907e-15,
+                          -9.61545 -14.6217 -5.32907e-15,
+                          9.61545 14.6217 -5.32907e-15,
+                          -14.7313 -9.44661 -6.21725e-15,
+                          2.83699 17.2685 -6.21725e-15,
+                          6.36533 16.3013 -5.32907e-15,
+                          -12.4453 -12.303 -5.32907e-15,
+                          -14.7313 -9.44661 -6.21725e-15,
+                          6.36533 16.3013 -5.32907e-15,
+                          -16.3735 -6.17735 -6.21725e-15,
+                          -0.815346 17.481 -6.21725e-15,
+                          2.83699 17.2685 -6.21725e-15,
+                          -14.7313 -9.44661 -6.21725e-15,
+                          -16.3735 -6.17735 -6.21725e-15,
+                          2.83699 17.2685 -6.21725e-15,
+                          -17.3 -2.63811 -6.21725e-15,
+                          -4.43204 16.9295 -6.21725e-15,
+                          -0.815346 17.481 -6.21725e-15,
+                          -16.3735 -6.17735 -6.21725e-15,
+                          -17.3 -2.63811 -6.21725e-15,
+                          -0.815346 17.481 -6.21725e-15,
+                          -17.4705 1.01639 -6.21725e-15,
+                          -7.85501 15.6381 -6.21725e-15,
+                          -4.43204 16.9295 -6.21725e-15,
+                          -17.3 -2.63811 -6.21725e-15,
+                          -17.4705 1.01639 -6.21725e-15,
+                          -4.43204 16.9295 -6.21725e-15,
+                          -16.8774 4.62648 -7.10543e-15,
+                          -10.9347 13.6632 -7.10543e-15,
+                          -7.85501 15.6381 -6.21725e-15,
+                          -17.4705 1.01639 -6.21725e-15,
+                          -16.8774 4.62648 -7.10543e-15,
+                          -7.85501 15.6381 -6.21725e-15,
+                          -15.5467 8.03439 -7.10543e-15,
+                          -13.5365 11.0912 -7.10543e-15,
+                          -10.9347 13.6632 -7.10543e-15,
+                          -16.8774 4.62648 -7.10543e-15,
+                          -15.5467 8.03439 -7.10543e-15,
+                          -10.9347 13.6632 -7.10543e-15,
+                          12.4453 12.303 -5.32907e-15,
+                          -6.36533 -16.3013 -5.32907e-15,
+                          -9.61545 -14.6217 -5.32907e-15,
+                          14.7313 9.44661 -4.44089e-15,
+                          -2.83699 -17.2685 -4.44089e-15,
+                          -6.36533 -16.3013 -5.32907e-15,
+                          12.4453 12.303 -5.32907e-15,
+                          14.7313 9.44661 -4.44089e-15,
+                          -6.36533 -16.3013 -5.32907e-15,
+                          16.3735 6.17735 -4.44089e-15,
+                          0.815346 -17.481 -4.44089e-15,
+                          -2.83699 -17.2685 -4.44089e-15,
+                          14.7313 9.44661 -4.44089e-15,
+                          16.3735 6.17735 -4.44089e-15,
+                          -2.83699 -17.2685 -4.44089e-15,
+                          17.3 2.63811 -4.44089e-15,
+                          4.43204 -16.9295 -4.44089e-15,
+                          0.815346 -17.481 -4.44089e-15,
+                          16.3735 6.17735 -4.44089e-15,
+                          17.3 2.63811 -4.44089e-15,
+                          0.815346 -17.481 -4.44089e-15,
+                          17.4705 -1.01639 -4.44089e-15,
+                          7.85501 -15.6381 -4.44089e-15,
+                          4.43204 -16.9295 -4.44089e-15,
+                          17.3 2.63811 -4.44089e-15,
+                          17.4705 -1.01639 -4.44089e-15,
+                          4.43204 -16.9295 -4.44089e-15,
+                          16.8774 -4.62648 -3.55271e-15,
+                          10.9347 -13.6632 -3.55271e-15,
+                          7.85501 -15.6381 -4.44089e-15,
+                          17.4705 -1.01639 -4.44089e-15,
+                          16.8774 -4.62648 -3.55271e-15,
+                          7.85501 -15.6381 -4.44089e-15,
+                          15.5467 -8.03439 -3.55271e-15,
+                          13.5365 -11.0912 -3.55271e-15,
+                          10.9347 -13.6632 -3.55271e-15,
+                          16.8774 -4.62648 -3.55271e-15,
+                          15.5467 -8.03439 -3.55271e-15,
+                          10.9347 -13.6632 -3.55271e-15,
+                          3.3421 -2.19782 10.8,
+                          -3.3421 2.19782 10.8,
+                          -3.92876 0.751542 10.8,
+                          3.92876 -0.751542 10.8,
+                          -3.3421 2.19782 10.8,
+                          3.3421 -2.19782 10.8,
+                          3.92876 -0.751542 10.8,
+                          -2.24661 3.30949 10.8,
+                          -3.3421 2.19782 10.8,
+                          2.24661 -3.30949 10.8,
+                          -3.92876 0.751542 10.8,
+                          -3.91731 -0.809126 10.8,
+                          3.3421 -2.19782 10.8,
+                          -3.92876 0.751542 10.8,
+                          2.24661 -3.30949 10.8,
+                          0.809126 -3.91731 10.8,
+                          -3.91731 -0.809126 10.8,
+                          -3.30949 -2.24661 10.8,
+                          2.24661 -3.30949 10.8,
+                          -3.91731 -0.809126 10.8,
+                          0.809126 -3.91731 10.8,
+                          -0.751542 -3.92876 10.8,
+                          -3.30949 -2.24661 10.8,
+                          -2.19782 -3.3421 10.8,
+                          0.809126 -3.91731 10.8,
+                          -3.30949 -2.24661 10.8,
+                          -0.751542 -3.92876 10.8,
+                          3.91731 0.809126 10.8,
+                          -0.809126 3.91731 10.8,
+                          -2.24661 3.30949 10.8,
+                          3.92876 -0.751542 10.8,
+                          3.91731 0.809126 10.8,
+                          -2.24661 3.30949 10.8,
+                          3.30949 2.24661 10.8,
+                          0.751542 3.92876 10.8,
+                          -0.809126 3.91731 10.8,
+                          3.91731 0.809126 10.8,
+                          3.30949 2.24661 10.8,
+                          -0.809126 3.91731 10.8,
+                          3.30949 2.24661 10.8,
+                          2.19782 3.3421 10.8,
+                          0.751542 3.92876 10.8 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.25 0.25 0.25
+    }
+    Separator {
+        Normal {
+            vector      [ 5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          1 1.92767e-16 0,
+                          1 1.92767e-16 0,
+                          0.980785 0.19509 0,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          1 7.03024e-17 0,
+                          1 7.03024e-17 0,
+                          1 7.03024e-17 0,
+                          1 7.03024e-17 0,
+                          1 7.03024e-17 0,
+                          1 7.03024e-17 0,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          0.980785 0.19509 0,
+                          0.980785 0.19509 0,
+                          0.92388 0.382683 0,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          1 1.92767e-16 0,
+                          0.980785 0.19509 0,
+                          0.980785 0.19509 0,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          0.92388 0.382683 0,
+                          0.92388 0.382683 0,
+                          0.83147 0.55557 0,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          0.980785 0.19509 0,
+                          0.92388 0.382683 0,
+                          0.92388 0.382683 0,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          0.83147 0.55557 0,
+                          0.83147 0.55557 0,
+                          0.707107 0.707107 0,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          0.92388 0.382683 0,
+                          0.83147 0.55557 0,
+                          0.83147 0.55557 0,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          0.707107 0.707107 0,
+                          0.707107 0.707107 0,
+                          0.55557 0.83147 0,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          0.83147 0.55557 0,
+                          0.707107 0.707107 0,
+                          0.707107 0.707107 0,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          0.55557 0.83147 0,
+                          0.55557 0.83147 0,
+                          0.382683 0.92388 0,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          0.707107 0.707107 0,
+                          0.55557 0.83147 0,
+                          0.55557 0.83147 0,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          0.382683 0.92388 0,
+                          0.382683 0.92388 0,
+                          0.19509 0.980785 0,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          0.55557 0.83147 0,
+                          0.382683 0.92388 0,
+                          0.382683 0.92388 0,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          0.19509 0.980785 0,
+                          0.19509 0.980785 0,
+                          -2.13888e-16 1 0,
+                          0.382683 0.92388 0,
+                          0.19509 0.980785 0,
+                          0.19509 0.980785 0,
+                          1.34042e-15 1 0,
+                          -2.13888e-16 1 0,
+                          -0.19509 0.980785 0,
+                          0.19509 0.980785 0,
+                          -2.13888e-16 1 0,
+                          1.34042e-15 1 0,
+                          -0.19509 0.980785 0,
+                          -0.19509 0.980785 0,
+                          -0.382683 0.92388 0,
+                          1.34042e-15 1 0,
+                          -0.19509 0.980785 0,
+                          -0.19509 0.980785 0,
+                          -0.382683 0.92388 0,
+                          -0.382683 0.92388 0,
+                          -0.55557 0.83147 0,
+                          -0.19509 0.980785 0,
+                          -0.382683 0.92388 0,
+                          -0.382683 0.92388 0,
+                          -0.55557 0.83147 0,
+                          -0.55557 0.83147 0,
+                          -0.707107 0.707107 0,
+                          -0.382683 0.92388 0,
+                          -0.55557 0.83147 0,
+                          -0.55557 0.83147 0,
+                          -0.707107 0.707107 0,
+                          -0.707107 0.707107 0,
+                          -0.83147 0.55557 0,
+                          -0.55557 0.83147 0,
+                          -0.707107 0.707107 0,
+                          -0.707107 0.707107 0,
+                          -0.83147 0.55557 0,
+                          -0.83147 0.55557 0,
+                          -0.92388 0.382683 0,
+                          -0.707107 0.707107 0,
+                          -0.83147 0.55557 0,
+                          -0.83147 0.55557 0,
+                          -0.92388 0.382683 0,
+                          -0.92388 0.382683 0,
+                          -0.980785 0.19509 0,
+                          -0.83147 0.55557 0,
+                          -0.92388 0.382683 0,
+                          -0.92388 0.382683 0,
+                          -0.980785 0.19509 0,
+                          -0.980785 0.19509 0,
+                          -1 -7.03024e-17 0,
+                          -0.92388 0.382683 0,
+                          -0.980785 0.19509 0,
+                          -0.980785 0.19509 0,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          -1 -7.03024e-17 0,
+                          -1 -7.03024e-17 0,
+                          -1 -7.03024e-17 0,
+                          -0.980785 0.19509 0,
+                          -1 -7.03024e-17 0,
+                          -1 -7.03024e-17 0,
+                          -6.93889e-17 -1 0,
+                          -6.93889e-17 -1 0,
+                          -6.93889e-17 -1 0,
+                          -1 -7.03024e-17 0,
+                          -1 -7.03024e-17 0,
+                          -1 -7.03024e-17 0,
+                          -6.93889e-17 -1 0,
+                          -6.93889e-17 -1 0,
+                          -6.93889e-17 -1 0,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -18.1445 3.60918 -2,
+                          18.1445 3.60918 -2,
+                          18.5 -1.49214e-13 -2,
+                          18.5 2.13163e-14 -4.44089e-16,
+                          18.5 -1.49214e-13 -2,
+                          18.1445 3.60918 -2,
+                          -18.5 -1.49214e-13 -2,
+                          -18.1445 3.60918 -2,
+                          18.5 -1.49214e-13 -2,
+                          18.5 -38.5 -2,
+                          -18.5 -1.49214e-13 -2,
+                          18.5 -1.49214e-13 -2,
+                          18.5 -38.5 -4.44089e-16,
+                          18.5 -38.5 -2,
+                          18.5 -1.49214e-13 -2,
+                          18.5 -38.5 -4.44089e-16,
+                          18.5 -1.49214e-13 -2,
+                          18.5 2.13163e-14 -4.44089e-16,
+                          -17.0918 7.07962 -2,
+                          17.0918 7.07962 -2,
+                          18.1445 3.60918 -2,
+                          18.1445 3.60918 -4.44089e-16,
+                          18.1445 3.60918 -2,
+                          17.0918 7.07962 -2,
+                          -18.1445 3.60918 -2,
+                          -17.0918 7.07962 -2,
+                          18.1445 3.60918 -2,
+                          18.5 2.13163e-14 -4.44089e-16,
+                          18.1445 3.60918 -2,
+                          18.1445 3.60918 -4.44089e-16,
+                          -15.3822 10.2781 -2,
+                          15.3822 10.2781 -2,
+                          17.0918 7.07962 -2,
+                          17.0918 7.07962 -4.44089e-16,
+                          17.0918 7.07962 -2,
+                          15.3822 10.2781 -2,
+                          -17.0918 7.07962 -2,
+                          -15.3822 10.2781 -2,
+                          17.0918 7.07962 -2,
+                          18.1445 3.60918 -4.44089e-16,
+                          17.0918 7.07962 -2,
+                          17.0918 7.07962 -4.44089e-16,
+                          -13.0815 13.0815 -2,
+                          13.0815 13.0815 -2,
+                          15.3822 10.2781 -2,
+                          15.3822 10.2781 -4.44089e-16,
+                          15.3822 10.2781 -2,
+                          13.0815 13.0815 -2,
+                          -15.3822 10.2781 -2,
+                          -13.0815 13.0815 -2,
+                          15.3822 10.2781 -2,
+                          17.0918 7.07962 -4.44089e-16,
+                          15.3822 10.2781 -2,
+                          15.3822 10.2781 -4.44089e-16,
+                          -10.2781 15.3822 -2,
+                          10.2781 15.3822 -2,
+                          13.0815 13.0815 -2,
+                          13.0815 13.0815 -4.44089e-16,
+                          13.0815 13.0815 -2,
+                          10.2781 15.3822 -2,
+                          -13.0815 13.0815 -2,
+                          -10.2781 15.3822 -2,
+                          13.0815 13.0815 -2,
+                          15.3822 10.2781 -4.44089e-16,
+                          13.0815 13.0815 -2,
+                          13.0815 13.0815 -4.44089e-16,
+                          -7.07962 17.0918 -2,
+                          7.07962 17.0918 -2,
+                          10.2781 15.3822 -2,
+                          10.2781 15.3822 -4.44089e-16,
+                          10.2781 15.3822 -2,
+                          7.07962 17.0918 -2,
+                          -10.2781 15.3822 -2,
+                          -7.07962 17.0918 -2,
+                          10.2781 15.3822 -2,
+                          13.0815 13.0815 -4.44089e-16,
+                          10.2781 15.3822 -2,
+                          10.2781 15.3822 -4.44089e-16,
+                          -3.60918 18.1445 -2,
+                          3.60918 18.1445 -2,
+                          7.07962 17.0918 -2,
+                          7.07962 17.0918 -4.44089e-16,
+                          7.07962 17.0918 -2,
+                          3.60918 18.1445 -2,
+                          -7.07962 17.0918 -2,
+                          -3.60918 18.1445 -2,
+                          7.07962 17.0918 -2,
+                          10.2781 15.3822 -4.44089e-16,
+                          7.07962 17.0918 -2,
+                          7.07962 17.0918 -4.44089e-16,
+                          -3.60918 18.1445 -2,
+                          1.38556e-13 18.5 -2,
+                          3.60918 18.1445 -2,
+                          3.60918 18.1445 -4.44089e-16,
+                          3.60918 18.1445 -2,
+                          1.38556e-13 18.5 -2,
+                          7.07962 17.0918 -4.44089e-16,
+                          3.60918 18.1445 -2,
+                          3.60918 18.1445 -4.44089e-16,
+                          4.26326e-14 18.5 -4.44089e-16,
+                          1.38556e-13 18.5 -2,
+                          -3.60918 18.1445 -2,
+                          3.60918 18.1445 -4.44089e-16,
+                          1.38556e-13 18.5 -2,
+                          4.26326e-14 18.5 -4.44089e-16,
+                          -3.60918 18.1445 -4.44089e-16,
+                          -3.60918 18.1445 -2,
+                          -7.07962 17.0918 -2,
+                          4.26326e-14 18.5 -4.44089e-16,
+                          -3.60918 18.1445 -2,
+                          -3.60918 18.1445 -4.44089e-16,
+                          -7.07962 17.0918 -4.44089e-16,
+                          -7.07962 17.0918 -2,
+                          -10.2781 15.3822 -2,
+                          -3.60918 18.1445 -4.44089e-16,
+                          -7.07962 17.0918 -2,
+                          -7.07962 17.0918 -4.44089e-16,
+                          -10.2781 15.3822 -4.44089e-16,
+                          -10.2781 15.3822 -2,
+                          -13.0815 13.0815 -2,
+                          -7.07962 17.0918 -4.44089e-16,
+                          -10.2781 15.3822 -2,
+                          -10.2781 15.3822 -4.44089e-16,
+                          -13.0815 13.0815 -4.44089e-16,
+                          -13.0815 13.0815 -2,
+                          -15.3822 10.2781 -2,
+                          -10.2781 15.3822 -4.44089e-16,
+                          -13.0815 13.0815 -2,
+                          -13.0815 13.0815 -4.44089e-16,
+                          -15.3822 10.2781 -4.44089e-16,
+                          -15.3822 10.2781 -2,
+                          -17.0918 7.07962 -2,
+                          -13.0815 13.0815 -4.44089e-16,
+                          -15.3822 10.2781 -2,
+                          -15.3822 10.2781 -4.44089e-16,
+                          -17.0918 7.07962 -4.44089e-16,
+                          -17.0918 7.07962 -2,
+                          -18.1445 3.60918 -2,
+                          -15.3822 10.2781 -4.44089e-16,
+                          -17.0918 7.07962 -2,
+                          -17.0918 7.07962 -4.44089e-16,
+                          -18.1445 3.60918 -4.44089e-16,
+                          -18.1445 3.60918 -2,
+                          -18.5 -1.49214e-13 -2,
+                          -17.0918 7.07962 -4.44089e-16,
+                          -18.1445 3.60918 -2,
+                          -18.1445 3.60918 -4.44089e-16,
+                          18.5 -38.5 -2,
+                          -18.5 -38.5 -2,
+                          -18.5 -1.49214e-13 -2,
+                          -18.5 2.13163e-14 -4.44089e-16,
+                          -18.5 -1.49214e-13 -2,
+                          -18.5 -38.5 -2,
+                          -18.1445 3.60918 -4.44089e-16,
+                          -18.5 -1.49214e-13 -2,
+                          -18.5 2.13163e-14 -4.44089e-16,
+                          -18.5 -38.5 -4.44089e-16,
+                          -18.5 -38.5 -2,
+                          18.5 -38.5 -2,
+                          -18.5 -38.5 -4.44089e-16,
+                          -18.5 2.13163e-14 -4.44089e-16,
+                          -18.5 -38.5 -2,
+                          -18.5 -38.5 -4.44089e-16,
+                          18.5 -38.5 -2,
+                          18.5 -38.5 -4.44089e-16,
+                          18.1445 3.60918 -4.44089e-16,
+                          -18.1445 3.60918 -4.44089e-16,
+                          -18.5 2.13163e-14 -4.44089e-16,
+                          18.5 2.13163e-14 -4.44089e-16,
+                          18.1445 3.60918 -4.44089e-16,
+                          -18.5 2.13163e-14 -4.44089e-16,
+                          -18.5 -38.5 -4.44089e-16,
+                          18.5 2.13163e-14 -4.44089e-16,
+                          -18.5 2.13163e-14 -4.44089e-16,
+                          17.0918 7.07962 -4.44089e-16,
+                          -17.0918 7.07962 -4.44089e-16,
+                          -18.1445 3.60918 -4.44089e-16,
+                          18.1445 3.60918 -4.44089e-16,
+                          17.0918 7.07962 -4.44089e-16,
+                          -18.1445 3.60918 -4.44089e-16,
+                          15.3822 10.2781 -4.44089e-16,
+                          -15.3822 10.2781 -4.44089e-16,
+                          -17.0918 7.07962 -4.44089e-16,
+                          17.0918 7.07962 -4.44089e-16,
+                          15.3822 10.2781 -4.44089e-16,
+                          -17.0918 7.07962 -4.44089e-16,
+                          13.0815 13.0815 -4.44089e-16,
+                          -13.0815 13.0815 -4.44089e-16,
+                          -15.3822 10.2781 -4.44089e-16,
+                          15.3822 10.2781 -4.44089e-16,
+                          13.0815 13.0815 -4.44089e-16,
+                          -15.3822 10.2781 -4.44089e-16,
+                          10.2781 15.3822 -4.44089e-16,
+                          -10.2781 15.3822 -4.44089e-16,
+                          -13.0815 13.0815 -4.44089e-16,
+                          13.0815 13.0815 -4.44089e-16,
+                          10.2781 15.3822 -4.44089e-16,
+                          -13.0815 13.0815 -4.44089e-16,
+                          7.07962 17.0918 -4.44089e-16,
+                          -7.07962 17.0918 -4.44089e-16,
+                          -10.2781 15.3822 -4.44089e-16,
+                          10.2781 15.3822 -4.44089e-16,
+                          7.07962 17.0918 -4.44089e-16,
+                          -10.2781 15.3822 -4.44089e-16,
+                          3.60918 18.1445 -4.44089e-16,
+                          -3.60918 18.1445 -4.44089e-16,
+                          -7.07962 17.0918 -4.44089e-16,
+                          7.07962 17.0918 -4.44089e-16,
+                          3.60918 18.1445 -4.44089e-16,
+                          -7.07962 17.0918 -4.44089e-16,
+                          3.60918 18.1445 -4.44089e-16,
+                          4.26326e-14 18.5 -4.44089e-16,
+                          -3.60918 18.1445 -4.44089e-16,
+                          -18.5 -38.5 -4.44089e-16,
+                          18.5 -38.5 -4.44089e-16,
+                          18.5 2.13163e-14 -4.44089e-16 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+    Separator {
+        Normal {
+            vector      [ -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          6.93889e-17 1 0,
+                          6.93889e-17 1 0,
+                          6.93889e-17 1 0,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -0.866025 0.5 0,
+                          -0.866025 0.5 0,
+                          -0.866025 0.5 0,
+                          6.93889e-17 1 0,
+                          6.93889e-17 1 0,
+                          6.93889e-17 1 0,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          -5.85088e-14 8.39518e-14 1,
+                          0.866025 0.5 0,
+                          0.866025 0.5 0,
+                          0.866025 0.5 0,
+                          0.866025 0.5 0,
+                          0.866025 0.5 0,
+                          0.866025 0.5 0,
+                          0.866025 -0.5 0,
+                          0.866025 -0.5 0,
+                          0.866025 -0.5 0,
+                          0.866025 -0.5 0,
+                          0.866025 -0.5 0,
+                          0.866025 -0.5 0,
+                          -6.93889e-17 -1 0,
+                          -6.93889e-17 -1 0,
+                          -6.93889e-17 -1 0,
+                          -6.93889e-17 -1 0,
+                          -6.93889e-17 -1 0,
+                          -6.93889e-17 -1 0,
+                          -0.866025 -0.5 0,
+                          -0.866025 -0.5 0,
+                          -0.866025 -0.5 0,
+                          -0.866025 -0.5 0,
+                          -0.866025 -0.5 0,
+                          -0.866025 -0.5 0,
+                          -0.866025 0.5 0,
+                          -0.866025 0.5 0,
+                          -0.866025 0.5 0,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1,
+                          5.85088e-14 -8.39518e-14 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 14.875 -35.8816 -2,
+                          14.875 -31.1184 -2,
+                          12.125 -31.1184 -2,
+                          14.875 -31.1184 -27,
+                          12.125 -31.1184 -2,
+                          14.875 -31.1184 -2,
+                          12.125 -35.8816 -2,
+                          14.875 -35.8816 -2,
+                          12.125 -31.1184 -2,
+                          10.75 -33.5 -2,
+                          12.125 -35.8816 -2,
+                          12.125 -31.1184 -2,
+                          12.125 -31.1184 -27,
+                          10.75 -33.5 -2,
+                          12.125 -31.1184 -2,
+                          14.875 -31.1184 -27,
+                          12.125 -31.1184 -27,
+                          12.125 -31.1184 -2,
+                          14.875 -35.8816 -2,
+                          16.25 -33.5 -2,
+                          14.875 -31.1184 -2,
+                          16.25 -33.5 -27,
+                          14.875 -31.1184 -2,
+                          16.25 -33.5 -2,
+                          14.875 -31.1184 -27,
+                          14.875 -31.1184 -2,
+                          16.25 -33.5 -27,
+                          14.875 -35.8816 -27,
+                          16.25 -33.5 -2,
+                          14.875 -35.8816 -2,
+                          16.25 -33.5 -27,
+                          16.25 -33.5 -2,
+                          14.875 -35.8816 -27,
+                          12.125 -35.8816 -27,
+                          14.875 -35.8816 -2,
+                          12.125 -35.8816 -2,
+                          14.875 -35.8816 -27,
+                          14.875 -35.8816 -2,
+                          12.125 -35.8816 -27,
+                          10.75 -33.5 -27,
+                          12.125 -35.8816 -2,
+                          10.75 -33.5 -2,
+                          12.125 -35.8816 -27,
+                          12.125 -35.8816 -2,
+                          10.75 -33.5 -27,
+                          10.75 -33.5 -27,
+                          10.75 -33.5 -2,
+                          12.125 -31.1184 -27,
+                          12.125 -35.8816 -27,
+                          10.75 -33.5 -27,
+                          12.125 -31.1184 -27,
+                          14.875 -31.1184 -27,
+                          12.125 -35.8816 -27,
+                          12.125 -31.1184 -27,
+                          14.875 -31.1184 -27,
+                          14.875 -35.8816 -27,
+                          12.125 -35.8816 -27,
+                          14.875 -31.1184 -27,
+                          16.25 -33.5 -27,
+                          14.875 -35.8816 -27 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ -1.17018e-13 1.67904e-13 1,
+                          -1.17018e-13 1.67904e-13 1,
+                          -1.17018e-13 1.67904e-13 1,
+                          2.0908e-16 1 8.39518e-14,
+                          2.0908e-16 1 8.39518e-14,
+                          2.0908e-16 1 8.39518e-14,
+                          -1.17018e-13 1.67904e-13 1,
+                          -1.17018e-13 1.67904e-13 1,
+                          -1.17018e-13 1.67904e-13 1,
+                          -1.17018e-13 1.67904e-13 1,
+                          -1.17018e-13 1.67904e-13 1,
+                          -1.17018e-13 1.67904e-13 1,
+                          -0.866025 0.5 9.2646e-14,
+                          -0.866025 0.5 9.2646e-14,
+                          -0.866025 0.5 9.2646e-14,
+                          2.0908e-16 1 8.39518e-14,
+                          2.0908e-16 1 8.39518e-14,
+                          2.0908e-16 1 8.39518e-14,
+                          -1.17018e-13 1.67904e-13 1,
+                          -1.17018e-13 1.67904e-13 1,
+                          -1.17018e-13 1.67904e-13 1,
+                          0.866025 0.5 -8.69415e-15,
+                          0.866025 0.5 -8.69415e-15,
+                          0.866025 0.5 -8.69415e-15,
+                          0.866025 0.5 -8.69415e-15,
+                          0.866025 0.5 -8.69415e-15,
+                          0.866025 0.5 -8.69415e-15,
+                          0.866025 -0.5 -9.2646e-14,
+                          0.866025 -0.5 -9.2646e-14,
+                          0.866025 -0.5 -9.2646e-14,
+                          0.866025 -0.5 -9.2646e-14,
+                          0.866025 -0.5 -9.2646e-14,
+                          0.866025 -0.5 -9.2646e-14,
+                          -2.0908e-16 -1 -8.39518e-14,
+                          -2.0908e-16 -1 -8.39518e-14,
+                          -2.0908e-16 -1 -8.39518e-14,
+                          -2.0908e-16 -1 -8.39518e-14,
+                          -2.0908e-16 -1 -8.39518e-14,
+                          -2.0908e-16 -1 -8.39518e-14,
+                          -0.866025 -0.5 8.69415e-15,
+                          -0.866025 -0.5 8.69415e-15,
+                          -0.866025 -0.5 8.69415e-15,
+                          -0.866025 -0.5 8.69415e-15,
+                          -0.866025 -0.5 8.69415e-15,
+                          -0.866025 -0.5 8.69415e-15,
+                          -0.866025 0.5 9.2646e-14,
+                          -0.866025 0.5 9.2646e-14,
+                          -0.866025 0.5 9.2646e-14,
+                          1.17018e-13 -1.67904e-13 -1,
+                          1.17018e-13 -1.67904e-13 -1,
+                          1.17018e-13 -1.67904e-13 -1,
+                          1.17018e-13 -1.67904e-13 -1,
+                          1.17018e-13 -1.67904e-13 -1,
+                          1.17018e-13 -1.67904e-13 -1,
+                          1.17018e-13 -1.67904e-13 -1,
+                          1.17018e-13 -1.67904e-13 -1,
+                          1.17018e-13 -1.67904e-13 -1,
+                          1.17018e-13 -1.67904e-13 -1,
+                          1.17018e-13 -1.67904e-13 -1,
+                          1.17018e-13 -1.67904e-13 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -12.125 -35.8816 -2,
+                          -12.125 -31.1184 -2,
+                          -14.875 -31.1184 -2,
+                          -12.125 -31.1184 -27,
+                          -14.875 -31.1184 -2,
+                          -12.125 -31.1184 -2,
+                          -14.875 -35.8816 -2,
+                          -12.125 -35.8816 -2,
+                          -14.875 -31.1184 -2,
+                          -16.25 -33.5 -2,
+                          -14.875 -35.8816 -2,
+                          -14.875 -31.1184 -2,
+                          -14.875 -31.1184 -27,
+                          -16.25 -33.5 -2,
+                          -14.875 -31.1184 -2,
+                          -12.125 -31.1184 -27,
+                          -14.875 -31.1184 -27,
+                          -14.875 -31.1184 -2,
+                          -12.125 -35.8816 -2,
+                          -10.75 -33.5 -2,
+                          -12.125 -31.1184 -2,
+                          -10.75 -33.5 -27,
+                          -12.125 -31.1184 -2,
+                          -10.75 -33.5 -2,
+                          -12.125 -31.1184 -27,
+                          -12.125 -31.1184 -2,
+                          -10.75 -33.5 -27,
+                          -12.125 -35.8816 -27,
+                          -10.75 -33.5 -2,
+                          -12.125 -35.8816 -2,
+                          -10.75 -33.5 -27,
+                          -10.75 -33.5 -2,
+                          -12.125 -35.8816 -27,
+                          -14.875 -35.8816 -27,
+                          -12.125 -35.8816 -2,
+                          -14.875 -35.8816 -2,
+                          -12.125 -35.8816 -27,
+                          -12.125 -35.8816 -2,
+                          -14.875 -35.8816 -27,
+                          -16.25 -33.5 -27,
+                          -14.875 -35.8816 -2,
+                          -16.25 -33.5 -2,
+                          -14.875 -35.8816 -27,
+                          -14.875 -35.8816 -2,
+                          -16.25 -33.5 -27,
+                          -16.25 -33.5 -27,
+                          -16.25 -33.5 -2,
+                          -14.875 -31.1184 -27,
+                          -14.875 -35.8816 -27,
+                          -16.25 -33.5 -27,
+                          -14.875 -31.1184 -27,
+                          -12.125 -31.1184 -27,
+                          -14.875 -35.8816 -27,
+                          -14.875 -31.1184 -27,
+                          -12.125 -31.1184 -27,
+                          -12.125 -35.8816 -27,
+                          -14.875 -35.8816 -27,
+                          -12.125 -31.1184 -27,
+                          -10.75 -33.5 -27,
+                          -12.125 -35.8816 -27 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ -5.85643e-14 -2.51856e-13 -1,
+                          -5.85643e-14 -2.51856e-13 -1,
+                          -5.85643e-14 -2.51856e-13 -1,
+                          2.09994e-16 -1 -1.67959e-13,
+                          2.09994e-16 -1 -1.67959e-13,
+                          2.09994e-16 -1 -1.67959e-13,
+                          -5.85643e-14 -2.51856e-13 -1,
+                          -5.85643e-14 -2.51856e-13 -1,
+                          -5.85643e-14 -2.51856e-13 -1,
+                          -5.85643e-14 -2.51856e-13 -1,
+                          -5.85643e-14 -2.51856e-13 -1,
+                          -5.85643e-14 -2.51856e-13 -1,
+                          -0.866025 -0.5 -1.85272e-13,
+                          -0.866025 -0.5 -1.85272e-13,
+                          -0.866025 -0.5 -1.85272e-13,
+                          2.09994e-16 -1 -1.67959e-13,
+                          2.09994e-16 -1 -1.67959e-13,
+                          2.09994e-16 -1 -1.67959e-13,
+                          -5.85643e-14 -2.51856e-13 -1,
+                          -5.85643e-14 -2.51856e-13 -1,
+                          -5.85643e-14 -2.51856e-13 -1,
+                          0.866025 -0.5 1.73125e-14,
+                          0.866025 -0.5 1.73125e-14,
+                          0.866025 -0.5 1.73125e-14,
+                          0.866025 -0.5 1.73125e-14,
+                          0.866025 -0.5 1.73125e-14,
+                          0.866025 -0.5 1.73125e-14,
+                          0.866025 0.5 1.85272e-13,
+                          0.866025 0.5 1.85272e-13,
+                          0.866025 0.5 1.85272e-13,
+                          0.866025 0.5 1.85272e-13,
+                          0.866025 0.5 1.85272e-13,
+                          0.866025 0.5 1.85272e-13,
+                          -2.09994e-16 1 1.67959e-13,
+                          -2.09994e-16 1 1.67959e-13,
+                          -2.09994e-16 1 1.67959e-13,
+                          -2.09994e-16 1 1.67959e-13,
+                          -2.09994e-16 1 1.67959e-13,
+                          -2.09994e-16 1 1.67959e-13,
+                          -0.866025 0.5 -1.73125e-14,
+                          -0.866025 0.5 -1.73125e-14,
+                          -0.866025 0.5 -1.73125e-14,
+                          -0.866025 0.5 -1.73125e-14,
+                          -0.866025 0.5 -1.73125e-14,
+                          -0.866025 0.5 -1.73125e-14,
+                          -0.866025 -0.5 -1.85272e-13,
+                          -0.866025 -0.5 -1.85272e-13,
+                          -0.866025 -0.5 -1.85272e-13,
+                          5.85643e-14 2.51856e-13 1,
+                          5.85643e-14 2.51856e-13 1,
+                          5.85643e-14 2.51856e-13 1,
+                          5.85643e-14 2.51856e-13 1,
+                          5.85643e-14 2.51856e-13 1,
+                          5.85643e-14 2.51856e-13 1,
+                          5.85643e-14 2.51856e-13 1,
+                          5.85643e-14 2.51856e-13 1,
+                          5.85643e-14 2.51856e-13 1,
+                          5.85643e-14 2.51856e-13 1,
+                          5.85643e-14 2.51856e-13 1,
+                          5.85643e-14 2.51856e-13 1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 1.375 -12.1184 -27,
+                          1.375 -16.8816 -27,
+                          -1.375 -16.8816 -27,
+                          1.375 -16.8816 -2,
+                          -1.375 -16.8816 -27,
+                          1.375 -16.8816 -27,
+                          -1.375 -12.1184 -27,
+                          1.375 -12.1184 -27,
+                          -1.375 -16.8816 -27,
+                          -2.75 -14.5 -27,
+                          -1.375 -12.1184 -27,
+                          -1.375 -16.8816 -27,
+                          -1.375 -16.8816 -2,
+                          -2.75 -14.5 -27,
+                          -1.375 -16.8816 -27,
+                          1.375 -16.8816 -2,
+                          -1.375 -16.8816 -2,
+                          -1.375 -16.8816 -27,
+                          1.375 -12.1184 -27,
+                          2.75 -14.5 -27,
+                          1.375 -16.8816 -27,
+                          2.75 -14.5 -2,
+                          1.375 -16.8816 -27,
+                          2.75 -14.5 -27,
+                          1.375 -16.8816 -2,
+                          1.375 -16.8816 -27,
+                          2.75 -14.5 -2,
+                          1.375 -12.1184 -2,
+                          2.75 -14.5 -27,
+                          1.375 -12.1184 -27,
+                          2.75 -14.5 -2,
+                          2.75 -14.5 -27,
+                          1.375 -12.1184 -2,
+                          -1.375 -12.1184 -2,
+                          1.375 -12.1184 -27,
+                          -1.375 -12.1184 -27,
+                          1.375 -12.1184 -2,
+                          1.375 -12.1184 -27,
+                          -1.375 -12.1184 -2,
+                          -2.75 -14.5 -2,
+                          -1.375 -12.1184 -27,
+                          -2.75 -14.5 -27,
+                          -1.375 -12.1184 -2,
+                          -1.375 -12.1184 -27,
+                          -2.75 -14.5 -2,
+                          -2.75 -14.5 -2,
+                          -2.75 -14.5 -27,
+                          -1.375 -16.8816 -2,
+                          -1.375 -12.1184 -2,
+                          -2.75 -14.5 -2,
+                          -1.375 -16.8816 -2,
+                          1.375 -16.8816 -2,
+                          -1.375 -12.1184 -2,
+                          -1.375 -16.8816 -2,
+                          1.375 -16.8816 -2,
+                          1.375 -12.1184 -2,
+                          -1.375 -12.1184 -2,
+                          1.375 -16.8816 -2,
+                          2.75 -14.5 -2,
+                          1.375 -12.1184 -2 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/palm2_l.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/palm2_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..540dc92bdfb18b6a75ef49744481bd48309e43ff
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/palm2_l.iv
@@ -0,0 +1,4359 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+    Separator {
+        Normal {
+            vector      [ 8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          -1 1.38778e-16 -1.0842e-17,
+                          -1 1.38778e-16 -1.0842e-17,
+                          -0.809017 -0.587785 1.97787e-17,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          -0.809017 0.587785 -3.73214e-17,
+                          -0.809017 0.587785 -3.73214e-17,
+                          -1 3.83707e-16 -1.0842e-17,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          -0.809017 0.587785 -3.73214e-17,
+                          -1 3.83707e-16 -1.0842e-17,
+                          -1 3.83707e-16 -1.0842e-17,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          -0.809017 -0.587785 1.97787e-17,
+                          -0.809017 -0.587785 1.97787e-17,
+                          -0.309017 -0.951057 4.28446e-17,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          -0.809017 -0.587785 1.97787e-17,
+                          -1 1.38778e-16 -1.0842e-17,
+                          -0.809017 -0.587785 1.97787e-17,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          -0.309017 -0.951057 4.28446e-17,
+                          -0.309017 -0.951057 4.28446e-17,
+                          0.309017 -0.951057 4.95453e-17,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          -0.809017 -0.587785 1.97787e-17,
+                          -0.309017 -0.951057 4.28446e-17,
+                          -0.309017 -0.951057 4.28446e-17,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          0.309017 -0.951057 4.95453e-17,
+                          0.309017 -0.951057 4.95453e-17,
+                          0.809017 -0.587785 3.73214e-17,
+                          -0.309017 -0.951057 4.28446e-17,
+                          0.309017 -0.951057 4.95453e-17,
+                          0.309017 -0.951057 4.95453e-17,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          0.809017 -0.587785 3.73214e-17,
+                          0.809017 -0.587785 3.73214e-17,
+                          1 -2.61243e-16 1.0842e-17,
+                          0.309017 -0.951057 4.95453e-17,
+                          0.809017 -0.587785 3.73214e-17,
+                          0.809017 -0.587785 3.73214e-17,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          1 -2.61243e-16 1.0842e-17,
+                          1 -2.61243e-16 1.0842e-17,
+                          0.809017 0.587785 -1.97787e-17,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          0.809017 -0.587785 3.73214e-17,
+                          1 -2.61243e-16 1.0842e-17,
+                          1 -2.61243e-16 1.0842e-17,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          0.809017 0.587785 -1.97787e-17,
+                          0.809017 0.587785 -1.97787e-17,
+                          0.309017 0.951057 -4.28446e-17,
+                          1 -2.61243e-16 1.0842e-17,
+                          0.809017 0.587785 -1.97787e-17,
+                          0.809017 0.587785 -1.97787e-17,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          0.309017 0.951057 -4.28446e-17,
+                          0.309017 0.951057 -4.28446e-17,
+                          -0.309017 0.951057 -4.95453e-17,
+                          0.809017 0.587785 -1.97787e-17,
+                          0.309017 0.951057 -4.28446e-17,
+                          0.309017 0.951057 -4.28446e-17,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          -0.309017 0.951057 -4.95453e-17,
+                          -0.309017 0.951057 -4.95453e-17,
+                          -0.809017 0.587785 -3.73214e-17,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          0.309017 0.951057 -4.28446e-17,
+                          -0.309017 0.951057 -4.95453e-17,
+                          -0.309017 0.951057 -4.95453e-17,
+                          -0.309017 0.951057 -4.95453e-17,
+                          -0.809017 0.587785 -3.73214e-17,
+                          -0.809017 0.587785 -3.73214e-17,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          -1 1.38778e-16 -1.0842e-17,
+                          -1 1.38778e-16 -1.0842e-17,
+                          -1 1.38778e-16 -1.0842e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          -1.38778e-17 1 -4.85723e-17,
+                          -1.38778e-17 1 -4.85723e-17,
+                          -1.38778e-17 1 -4.85723e-17,
+                          -1 1.38778e-16 -1.0842e-17,
+                          -1 1.38778e-16 -1.0842e-17,
+                          -1 1.38778e-16 -1.0842e-17,
+                          1 -1.38778e-16 1.0842e-17,
+                          1 -1.38778e-16 1.0842e-17,
+                          1 -1.38778e-16 1.0842e-17,
+                          -1.38778e-17 1 -4.85723e-17,
+                          -1.38778e-17 1 -4.85723e-17,
+                          -1.38778e-17 1 -4.85723e-17,
+                          -1.38778e-17 1 -4.85723e-17,
+                          -1.38778e-17 1 -4.85723e-17,
+                          -1.38778e-17 1 -4.85723e-17,
+                          1 -1.38778e-16 1.0842e-17,
+                          1 -1.38778e-16 1.0842e-17,
+                          1 -1.38778e-16 1.0842e-17,
+                          -1.38778e-17 1 -4.85723e-17,
+                          -1.38778e-17 1 -4.85723e-17,
+                          -1.38778e-17 1 -4.85723e-17,
+                          -1.38778e-17 1 -4.85723e-17,
+                          -1.38778e-17 1 -4.85723e-17,
+                          -1.38778e-17 1 -4.85723e-17,
+                          1 -3.83707e-16 1.0842e-17,
+                          1 -3.83707e-16 1.0842e-17,
+                          0.92388 -0.382683 2.86045e-17,
+                          0.92388 -0.382683 2.86045e-17,
+                          0.92388 -0.382683 2.86045e-17,
+                          0.707107 -0.707107 4.20122e-17,
+                          0.92388 -0.382683 2.86045e-17,
+                          1 -3.83707e-16 1.0842e-17,
+                          0.92388 -0.382683 2.86045e-17,
+                          0.707107 -0.707107 4.20122e-17,
+                          0.707107 -0.707107 4.20122e-17,
+                          0.382683 -0.92388 4.9024e-17,
+                          0.92388 -0.382683 2.86045e-17,
+                          0.707107 -0.707107 4.20122e-17,
+                          0.707107 -0.707107 4.20122e-17,
+                          0.382683 -0.92388 4.9024e-17,
+                          0.382683 -0.92388 4.9024e-17,
+                          -1.69819e-16 -1 4.85723e-17,
+                          0.707107 -0.707107 4.20122e-17,
+                          0.382683 -0.92388 4.9024e-17,
+                          0.382683 -0.92388 4.9024e-17,
+                          0.382683 -0.92388 4.9024e-17,
+                          -1.69819e-16 -1 4.85723e-17,
+                          -1.69819e-16 -1 4.85723e-17,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          1 -1.38778e-16 1.0842e-17,
+                          1 -1.38778e-16 1.0842e-17,
+                          0.809017 -0.587785 3.73214e-17,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          0.809017 0.587785 -1.97787e-17,
+                          0.809017 0.587785 -1.97787e-17,
+                          1 1.06151e-16 1.0842e-17,
+                          0.809017 0.587785 -1.97787e-17,
+                          1 1.06151e-16 1.0842e-17,
+                          1 1.06151e-16 1.0842e-17,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          0.809017 -0.587785 3.73214e-17,
+                          0.809017 -0.587785 3.73214e-17,
+                          0.309017 -0.951057 4.95453e-17,
+                          0.809017 -0.587785 3.73214e-17,
+                          1 -1.38778e-16 1.0842e-17,
+                          0.809017 -0.587785 3.73214e-17,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          0.309017 -0.951057 4.95453e-17,
+                          0.309017 -0.951057 4.95453e-17,
+                          -0.309017 -0.951057 4.28446e-17,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          0.809017 -0.587785 3.73214e-17,
+                          0.309017 -0.951057 4.95453e-17,
+                          0.309017 -0.951057 4.95453e-17,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -0.309017 -0.951057 4.28446e-17,
+                          -0.309017 -0.951057 4.28446e-17,
+                          -0.809017 -0.587785 1.97787e-17,
+                          0.309017 -0.951057 4.95453e-17,
+                          -0.309017 -0.951057 4.28446e-17,
+                          -0.309017 -0.951057 4.28446e-17,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -0.809017 -0.587785 1.97787e-17,
+                          -0.809017 -0.587785 1.97787e-17,
+                          -1 1.63132e-17 -1.0842e-17,
+                          -0.309017 -0.951057 4.28446e-17,
+                          -0.809017 -0.587785 1.97787e-17,
+                          -0.809017 -0.587785 1.97787e-17,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -1 1.63132e-17 -1.0842e-17,
+                          -1 1.63132e-17 -1.0842e-17,
+                          -0.809017 0.587785 -3.73214e-17,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -0.809017 -0.587785 1.97787e-17,
+                          -1 1.63132e-17 -1.0842e-17,
+                          -1 1.63132e-17 -1.0842e-17,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -0.809017 0.587785 -3.73214e-17,
+                          -0.809017 0.587785 -3.73214e-17,
+                          -0.309017 0.951057 -4.95453e-17,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -1 1.63132e-17 -1.0842e-17,
+                          -0.809017 0.587785 -3.73214e-17,
+                          -0.809017 0.587785 -3.73214e-17,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -0.309017 0.951057 -4.95453e-17,
+                          -0.309017 0.951057 -4.95453e-17,
+                          0.309017 0.951057 -4.28446e-17,
+                          -0.809017 0.587785 -3.73214e-17,
+                          -0.309017 0.951057 -4.95453e-17,
+                          -0.309017 0.951057 -4.95453e-17,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          0.309017 0.951057 -4.28446e-17,
+                          0.309017 0.951057 -4.28446e-17,
+                          0.809017 0.587785 -1.97787e-17,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -0.309017 0.951057 -4.95453e-17,
+                          0.309017 0.951057 -4.28446e-17,
+                          0.309017 0.951057 -4.28446e-17,
+                          0.309017 0.951057 -4.28446e-17,
+                          0.809017 0.587785 -1.97787e-17,
+                          0.809017 0.587785 -1.97787e-17,
+                          -1.69819e-16 -1 4.85723e-17,
+                          -1.69819e-16 -1 4.85723e-17,
+                          0.382683 -0.92388 4.9024e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          0.382683 -0.92388 4.9024e-17,
+                          0.382683 -0.92388 4.9024e-17,
+                          0.707107 -0.707107 4.20122e-17,
+                          0.382683 -0.92388 4.9024e-17,
+                          -1.69819e-16 -1 4.85723e-17,
+                          0.382683 -0.92388 4.9024e-17,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          0.707107 -0.707107 4.20122e-17,
+                          0.707107 -0.707107 4.20122e-17,
+                          0.92388 -0.382683 2.86045e-17,
+                          0.382683 -0.92388 4.9024e-17,
+                          0.707107 -0.707107 4.20122e-17,
+                          0.707107 -0.707107 4.20122e-17,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          0.92388 -0.382683 2.86045e-17,
+                          0.92388 -0.382683 2.86045e-17,
+                          1 -3.83707e-16 1.0842e-17,
+                          0.707107 -0.707107 4.20122e-17,
+                          0.92388 -0.382683 2.86045e-17,
+                          0.92388 -0.382683 2.86045e-17,
+                          1 -1.38778e-16 1.0842e-17,
+                          1 -1.38778e-16 1.0842e-17,
+                          1 -1.38778e-16 1.0842e-17,
+                          1 -1.38778e-16 1.0842e-17,
+                          1 -1.38778e-16 1.0842e-17,
+                          1 -1.38778e-16 1.0842e-17,
+                          0.92388 -0.382683 2.86045e-17,
+                          1 -3.83707e-16 1.0842e-17,
+                          1 -3.83707e-16 1.0842e-17,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -1.38778e-17 1 -4.85723e-17,
+                          -1.38778e-17 1 -4.85723e-17,
+                          -1.38778e-17 1 -4.85723e-17,
+                          -1 1.38778e-16 -1.0842e-17,
+                          -1 1.38778e-16 -1.0842e-17,
+                          -1 1.38778e-16 -1.0842e-17,
+                          -1.38778e-17 1 -4.85723e-17,
+                          -1.38778e-17 1 -4.85723e-17,
+                          -1.38778e-17 1 -4.85723e-17,
+                          -1.38778e-17 1 -4.85723e-17,
+                          -1.38778e-17 1 -4.85723e-17,
+                          -1.38778e-17 1 -4.85723e-17,
+                          -1 1.38778e-16 -1.0842e-17,
+                          -1 1.38778e-16 -1.0842e-17,
+                          -1 1.38778e-16 -1.0842e-17,
+                          -1 1.38778e-16 -1.0842e-17,
+                          -1 1.38778e-16 -1.0842e-17,
+                          -1 1.38778e-16 -1.0842e-17,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          -1.38778e-17 1 -4.85723e-17,
+                          -1.38778e-17 1 -4.85723e-17,
+                          -1.38778e-17 1 -4.85723e-17,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          -1 1.38778e-16 -1.0842e-17,
+                          -1 1.38778e-16 -1.0842e-17,
+                          -1 1.38778e-16 -1.0842e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          1.38778e-17 -1 4.85723e-17,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -1.38778e-17 1 -4.85723e-17,
+                          -1.38778e-17 1 -4.85723e-17,
+                          -1.38778e-17 1 -4.85723e-17,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          1 -1.38778e-16 1.0842e-17,
+                          1 -1.38778e-16 1.0842e-17,
+                          1 -1.38778e-16 1.0842e-17,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          1 -1.38778e-16 1.0842e-17,
+                          1 -1.38778e-16 1.0842e-17,
+                          1 -1.38778e-16 1.0842e-17,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          -8.97719e-17 -6.93889e-18 -1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          8.97719e-17 6.93889e-18 1,
+                          1 1.06151e-16 1.0842e-17,
+                          1 1.06151e-16 1.0842e-17,
+                          0.866025 0.5 -1.48967e-17,
+                          0.866025 -0.5 3.36756e-17,
+                          0.866025 -0.5 3.36756e-17,
+                          1 -1.38778e-16 1.0842e-17,
+                          0.866025 -0.5 3.36756e-17,
+                          1 -1.38778e-16 1.0842e-17,
+                          1 -1.38778e-16 1.0842e-17,
+                          0.866025 0.5 -1.48967e-17,
+                          0.866025 0.5 -1.48967e-17,
+                          0.5 0.866025 -3.66438e-17,
+                          0.866025 0.5 -1.48967e-17,
+                          1 1.06151e-16 1.0842e-17,
+                          0.866025 0.5 -1.48967e-17,
+                          0.5 0.866025 -3.66438e-17,
+                          0.5 0.866025 -3.66438e-17,
+                          1.57878e-15 1 -4.85723e-17,
+                          0.866025 0.5 -1.48967e-17,
+                          0.5 0.866025 -3.66438e-17,
+                          0.5 0.866025 -3.66438e-17,
+                          1.57878e-15 1 -4.85723e-17,
+                          1.57878e-15 1 -4.85723e-17,
+                          -0.5 0.866025 -4.74858e-17,
+                          0.5 0.866025 -3.66438e-17,
+                          1.57878e-15 1 -4.85723e-17,
+                          1.57878e-15 1 -4.85723e-17,
+                          -0.5 0.866025 -4.74858e-17,
+                          -0.5 0.866025 -4.74858e-17,
+                          -0.866025 0.5 -3.36756e-17,
+                          1.57878e-15 1 -4.85723e-17,
+                          -0.5 0.866025 -4.74858e-17,
+                          -0.5 0.866025 -4.74858e-17,
+                          -0.866025 0.5 -3.36756e-17,
+                          -0.866025 0.5 -3.36756e-17,
+                          -1 1.63132e-17 -1.0842e-17,
+                          -0.5 0.866025 -4.74858e-17,
+                          -0.866025 0.5 -3.36756e-17,
+                          -0.866025 0.5 -3.36756e-17,
+                          -1 1.63132e-17 -1.0842e-17,
+                          -1 1.63132e-17 -1.0842e-17,
+                          -0.866025 -0.5 1.48967e-17,
+                          -0.866025 0.5 -3.36756e-17,
+                          -1 1.63132e-17 -1.0842e-17,
+                          -1 1.63132e-17 -1.0842e-17,
+                          -0.866025 -0.5 1.48967e-17,
+                          -0.866025 -0.5 1.48967e-17,
+                          -0.5 -0.866025 3.66438e-17,
+                          -1 1.63132e-17 -1.0842e-17,
+                          -0.866025 -0.5 1.48967e-17,
+                          -0.866025 -0.5 1.48967e-17,
+                          -0.5 -0.866025 3.66438e-17,
+                          -0.5 -0.866025 3.66438e-17,
+                          -4.80987e-15 -1 4.85723e-17,
+                          -0.866025 -0.5 1.48967e-17,
+                          -0.5 -0.866025 3.66438e-17,
+                          -0.5 -0.866025 3.66438e-17,
+                          -4.80987e-15 -1 4.85723e-17,
+                          -4.80987e-15 -1 4.85723e-17,
+                          0.5 -0.866025 4.74858e-17,
+                          -0.5 -0.866025 3.66438e-17,
+                          -4.80987e-15 -1 4.85723e-17,
+                          -4.80987e-15 -1 4.85723e-17,
+                          0.5 -0.866025 4.74858e-17,
+                          0.5 -0.866025 4.74858e-17,
+                          0.866025 -0.5 3.36756e-17,
+                          -4.80987e-15 -1 4.85723e-17,
+                          0.5 -0.866025 4.74858e-17,
+                          0.5 -0.866025 4.74858e-17,
+                          0.5 -0.866025 4.74858e-17,
+                          0.866025 -0.5 3.36756e-17,
+                          0.866025 -0.5 3.36756e-17 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 1.66777 -1.51777 5,
+                          0.598674 0.434958 5,
+                          0.74 -1.42109e-14 5,
+                          0.74 -1.42109e-14 2.8,
+                          0.74 -1.42109e-14 5,
+                          0.598674 0.434958 5,
+                          0.856699 -2.0597 5,
+                          0.74 -1.42109e-14 5,
+                          0.598674 -0.434958 5,
+                          0.598674 -0.434958 2.8,
+                          0.598674 -0.434958 5,
+                          0.74 -1.42109e-14 5,
+                          0.856699 -2.0597 5,
+                          1.66777 -1.51777 5,
+                          0.74 -1.42109e-14 5,
+                          0.598674 -0.434958 2.8,
+                          0.74 -1.42109e-14 5,
+                          0.74 -1.42109e-14 2.8,
+                          2.2097 -0.706699 5,
+                          0.228666 0.703784 5,
+                          0.598674 0.434958 5,
+                          0.598674 0.434958 2.8,
+                          0.598674 0.434958 5,
+                          0.228666 0.703784 5,
+                          1.66777 -1.51777 5,
+                          2.2097 -0.706699 5,
+                          0.598674 0.434958 5,
+                          0.598674 0.434958 2.8,
+                          0.74 -1.42109e-14 2.8,
+                          0.598674 0.434958 5,
+                          -37.6 2.25 5,
+                          -0.228666 0.703784 5,
+                          0.228666 0.703784 5,
+                          0.228666 0.703784 2.8,
+                          0.228666 0.703784 5,
+                          -0.228666 0.703784 5,
+                          2.4 2.25 5,
+                          -37.6 2.25 5,
+                          0.228666 0.703784 5,
+                          2.4 0.25 5,
+                          2.4 2.25 5,
+                          0.228666 0.703784 5,
+                          2.2097 -0.706699 5,
+                          2.4 0.25 5,
+                          0.228666 0.703784 5,
+                          0.598674 0.434958 2.8,
+                          0.228666 0.703784 5,
+                          0.228666 0.703784 2.8,
+                          -37.6 2.25 5,
+                          -0.598674 0.434958 5,
+                          -0.228666 0.703784 5,
+                          -0.228666 0.703784 2.8,
+                          -0.228666 0.703784 5,
+                          -0.598674 0.434958 5,
+                          0.228666 0.703784 2.8,
+                          -0.228666 0.703784 5,
+                          -0.228666 0.703784 2.8,
+                          -37.6 2.25 5,
+                          -0.74 -1.42109e-14 5,
+                          -0.598674 0.434958 5,
+                          -0.598674 0.434958 2.8,
+                          -0.598674 0.434958 5,
+                          -0.74 -1.42109e-14 5,
+                          -0.228666 0.703784 2.8,
+                          -0.598674 0.434958 5,
+                          -0.598674 0.434958 2.8,
+                          -0.1 -2.25 5,
+                          -0.598674 -0.434958 5,
+                          -0.74 -1.42109e-14 5,
+                          -0.74 -1.42109e-14 2.8,
+                          -0.74 -1.42109e-14 5,
+                          -0.598674 -0.434958 5,
+                          -0.1 -2.25 5,
+                          -0.74 -1.42109e-14 5,
+                          -37.6 2.25 5,
+                          -0.598674 0.434958 2.8,
+                          -0.74 -1.42109e-14 5,
+                          -0.74 -1.42109e-14 2.8,
+                          -0.1 -2.25 5,
+                          -0.228666 -0.703784 5,
+                          -0.598674 -0.434958 5,
+                          -0.598674 -0.434958 2.8,
+                          -0.598674 -0.434958 5,
+                          -0.228666 -0.703784 5,
+                          -0.74 -1.42109e-14 2.8,
+                          -0.598674 -0.434958 5,
+                          -0.598674 -0.434958 2.8,
+                          -0.1 -2.25 5,
+                          0.228666 -0.703784 5,
+                          -0.228666 -0.703784 5,
+                          -0.228666 -0.703784 2.8,
+                          -0.228666 -0.703784 5,
+                          0.228666 -0.703784 5,
+                          -0.598674 -0.434958 2.8,
+                          -0.228666 -0.703784 5,
+                          -0.228666 -0.703784 2.8,
+                          0.856699 -2.0597 5,
+                          0.598674 -0.434958 5,
+                          0.228666 -0.703784 5,
+                          0.228666 -0.703784 2.8,
+                          0.228666 -0.703784 5,
+                          0.598674 -0.434958 5,
+                          -0.1 -2.25 5,
+                          0.856699 -2.0597 5,
+                          0.228666 -0.703784 5,
+                          -0.228666 -0.703784 2.8,
+                          0.228666 -0.703784 5,
+                          0.228666 -0.703784 2.8,
+                          0.228666 -0.703784 2.8,
+                          0.598674 -0.434958 5,
+                          0.598674 -0.434958 2.8,
+                          -0.1 -2.25 5,
+                          -37.6 2.25 5,
+                          -37.6 -2.25 5,
+                          -37.6 -2.25 2.5,
+                          -37.6 -2.25 5,
+                          -37.6 2.25 5,
+                          -0.1 -2.25 2.8,
+                          -0.1 -2.25 5,
+                          -37.6 -2.25 5,
+                          -2.25 -2.25 -2.8,
+                          -37.6 -2.25 5,
+                          -0.1 -2.25 -5,
+                          -37.6 -2.25 2.5,
+                          -0.1 -2.25 -5,
+                          -37.6 -2.25 5,
+                          -2.25 -2.25 2.8,
+                          -0.1 -2.25 2.8,
+                          -37.6 -2.25 5,
+                          -2.25 -2.25 -2.8,
+                          -2.25 -2.25 2.8,
+                          -37.6 -2.25 5,
+                          -37.6 2.25 2.5,
+                          -37.6 2.25 5,
+                          2.4 2.25 5,
+                          -37.6 2.25 2.5,
+                          -37.6 -2.25 2.5,
+                          -37.6 2.25 5,
+                          2.4 0.25 2.8,
+                          2.4 2.25 5,
+                          2.4 0.25 5,
+                          -37.6 2.25 -2.5,
+                          2.4 2.25 5,
+                          -37.6 2.25 -5,
+                          -2.25 2.25 2.8,
+                          -37.6 2.25 -5,
+                          2.4 2.25 5,
+                          2.4 0.25 2.8,
+                          2.4 2.25 2.8,
+                          2.4 2.25 5,
+                          -2.25 2.25 2.8,
+                          2.4 2.25 5,
+                          2.4 2.25 2.8,
+                          -37.6 2.25 -2.5,
+                          -37.6 2.25 2.5,
+                          2.4 2.25 5,
+                          2.4 0.25 2.8,
+                          2.4 0.25 5,
+                          2.2097 -0.706699 5,
+                          2.2097 -0.706699 2.8,
+                          2.2097 -0.706699 5,
+                          1.66777 -1.51777 5,
+                          2.2097 -0.706699 2.8,
+                          2.4 0.25 2.8,
+                          2.2097 -0.706699 5,
+                          1.66777 -1.51777 2.8,
+                          1.66777 -1.51777 5,
+                          0.856699 -2.0597 5,
+                          2.2097 -0.706699 2.8,
+                          1.66777 -1.51777 5,
+                          1.66777 -1.51777 2.8,
+                          0.856699 -2.0597 2.8,
+                          0.856699 -2.0597 5,
+                          -0.1 -2.25 5,
+                          1.66777 -1.51777 2.8,
+                          0.856699 -2.0597 5,
+                          0.856699 -2.0597 2.8,
+                          0.856699 -2.0597 2.8,
+                          -0.1 -2.25 5,
+                          -0.1 -2.25 2.8,
+                          -37.6 -2.25 -5,
+                          -0.606764 0.440835 -5,
+                          -0.75 -1.42109e-14 -5,
+                          -0.75 -1.42109e-14 -2.8,
+                          -0.75 -1.42109e-14 -5,
+                          -0.606764 0.440835 -5,
+                          -37.6 -2.25 -5,
+                          -0.75 -1.42109e-14 -5,
+                          -0.606764 -0.440835 -5,
+                          -0.606764 -0.440835 -2.8,
+                          -0.606764 -0.440835 -5,
+                          -0.75 -1.42109e-14 -5,
+                          -0.606764 -0.440835 -2.8,
+                          -0.75 -1.42109e-14 -5,
+                          -0.75 -1.42109e-14 -2.8,
+                          -37.6 -2.25 -5,
+                          -0.231756 0.713294 -5,
+                          -0.606764 0.440835 -5,
+                          -0.606764 0.440835 -2.8,
+                          -0.606764 0.440835 -5,
+                          -0.231756 0.713294 -5,
+                          -0.606764 0.440835 -2.8,
+                          -0.75 -1.42109e-14 -2.8,
+                          -0.606764 0.440835 -5,
+                          2.4 2.25 -5,
+                          0.231756 0.713294 -5,
+                          -0.231756 0.713294 -5,
+                          -0.231756 0.713294 -2.8,
+                          -0.231756 0.713294 -5,
+                          0.231756 0.713294 -5,
+                          -37.6 -2.25 -5,
+                          2.4 2.25 -5,
+                          -0.231756 0.713294 -5,
+                          -0.606764 0.440835 -2.8,
+                          -0.231756 0.713294 -5,
+                          -0.231756 0.713294 -2.8,
+                          2.4 2.25 -5,
+                          0.606764 0.440835 -5,
+                          0.231756 0.713294 -5,
+                          0.231756 0.713294 -2.8,
+                          0.231756 0.713294 -5,
+                          0.606764 0.440835 -5,
+                          -0.231756 0.713294 -2.8,
+                          0.231756 0.713294 -5,
+                          0.231756 0.713294 -2.8,
+                          2.4 2.25 -5,
+                          0.75 -1.42109e-14 -5,
+                          0.606764 0.440835 -5,
+                          0.606764 0.440835 -2.8,
+                          0.606764 0.440835 -5,
+                          0.75 -1.42109e-14 -5,
+                          0.231756 0.713294 -2.8,
+                          0.606764 0.440835 -5,
+                          0.606764 0.440835 -2.8,
+                          0.856699 -2.0597 -5,
+                          0.606764 -0.440835 -5,
+                          0.75 -1.42109e-14 -5,
+                          0.75 -1.42109e-14 -2.8,
+                          0.75 -1.42109e-14 -5,
+                          0.606764 -0.440835 -5,
+                          2.4 2.25 -5,
+                          0.856699 -2.0597 -5,
+                          0.75 -1.42109e-14 -5,
+                          0.606764 0.440835 -2.8,
+                          0.75 -1.42109e-14 -5,
+                          0.75 -1.42109e-14 -2.8,
+                          -0.1 -2.25 -5,
+                          0.231756 -0.713294 -5,
+                          0.606764 -0.440835 -5,
+                          0.606764 -0.440835 -2.8,
+                          0.606764 -0.440835 -5,
+                          0.231756 -0.713294 -5,
+                          0.856699 -2.0597 -5,
+                          -0.1 -2.25 -5,
+                          0.606764 -0.440835 -5,
+                          0.75 -1.42109e-14 -2.8,
+                          0.606764 -0.440835 -5,
+                          0.606764 -0.440835 -2.8,
+                          -0.1 -2.25 -5,
+                          -0.231756 -0.713294 -5,
+                          0.231756 -0.713294 -5,
+                          0.231756 -0.713294 -2.8,
+                          0.231756 -0.713294 -5,
+                          -0.231756 -0.713294 -5,
+                          0.606764 -0.440835 -2.8,
+                          0.231756 -0.713294 -5,
+                          0.231756 -0.713294 -2.8,
+                          -37.6 -2.25 -5,
+                          -0.606764 -0.440835 -5,
+                          -0.231756 -0.713294 -5,
+                          -0.231756 -0.713294 -2.8,
+                          -0.231756 -0.713294 -5,
+                          -0.606764 -0.440835 -5,
+                          -37.6 -2.25 -5,
+                          -0.231756 -0.713294 -5,
+                          -0.1 -2.25 -5,
+                          0.231756 -0.713294 -2.8,
+                          -0.231756 -0.713294 -5,
+                          -0.231756 -0.713294 -2.8,
+                          -0.231756 -0.713294 -2.8,
+                          -0.606764 -0.440835 -5,
+                          -0.606764 -0.440835 -2.8,
+                          -0.1 -2.25 -2.8,
+                          -0.1 -2.25 -5,
+                          0.856699 -2.0597 -5,
+                          -37.6 -2.25 -2.5,
+                          -37.6 -2.25 -5,
+                          -0.1 -2.25 -5,
+                          -0.1 -2.25 -2.8,
+                          -2.25 -2.25 -2.8,
+                          -0.1 -2.25 -5,
+                          -37.6 -2.25 2.5,
+                          -37.6 -2.25 -2.5,
+                          -0.1 -2.25 -5,
+                          2.4 2.25 -5,
+                          1.66777 -1.51777 -5,
+                          0.856699 -2.0597 -5,
+                          0.856699 -2.0597 -2.8,
+                          0.856699 -2.0597 -5,
+                          1.66777 -1.51777 -5,
+                          0.856699 -2.0597 -2.8,
+                          -0.1 -2.25 -2.8,
+                          0.856699 -2.0597 -5,
+                          2.4 2.25 -5,
+                          2.2097 -0.706699 -5,
+                          1.66777 -1.51777 -5,
+                          1.66777 -1.51777 -2.8,
+                          1.66777 -1.51777 -5,
+                          2.2097 -0.706699 -5,
+                          0.856699 -2.0597 -2.8,
+                          1.66777 -1.51777 -5,
+                          1.66777 -1.51777 -2.8,
+                          2.4 2.25 -5,
+                          2.4 0.25 -5,
+                          2.2097 -0.706699 -5,
+                          2.2097 -0.706699 -2.8,
+                          2.2097 -0.706699 -5,
+                          2.4 0.25 -5,
+                          1.66777 -1.51777 -2.8,
+                          2.2097 -0.706699 -5,
+                          2.2097 -0.706699 -2.8,
+                          2.4 2.25 -2.8,
+                          2.4 0.25 -5,
+                          2.4 2.25 -5,
+                          2.4 2.25 -2.8,
+                          2.4 0.25 -2.8,
+                          2.4 0.25 -5,
+                          2.2097 -0.706699 -2.8,
+                          2.4 0.25 -5,
+                          2.4 0.25 -2.8,
+                          -37.6 -2.25 -5,
+                          -37.6 2.25 -5,
+                          2.4 2.25 -5,
+                          2.4 2.25 -2.8,
+                          2.4 2.25 -5,
+                          -37.6 2.25 -5,
+                          -37.6 2.25 -2.5,
+                          -37.6 2.25 -5,
+                          -37.6 -2.25 -5,
+                          -2.25 2.25 -2.8,
+                          2.4 2.25 -2.8,
+                          -37.6 2.25 -5,
+                          -2.25 2.25 2.8,
+                          -2.25 2.25 -2.8,
+                          -37.6 2.25 -5,
+                          -37.6 2.25 -2.5,
+                          -37.6 -2.25 -5,
+                          -37.6 -2.25 -2.5,
+                          -42.25 2.25 -2.5,
+                          -42.25 -2.25 2.5,
+                          -42.25 2.25 2.5,
+                          -40.9093 -0.525005 2.5,
+                          -42.25 2.25 2.5,
+                          -42.25 -2.25 2.5,
+                          -37.6 2.25 2.5,
+                          -42.25 2.25 -2.5,
+                          -42.25 2.25 2.5,
+                          -39.475 0.909323 2.5,
+                          -37.6 2.25 2.5,
+                          -42.25 2.25 2.5,
+                          -40.9093 -0.525005 2.5,
+                          -41.05 -7.10543e-15 2.5,
+                          -42.25 2.25 2.5,
+                          -40.9093 0.525005 2.5,
+                          -42.25 2.25 2.5,
+                          -41.05 -7.10543e-15 2.5,
+                          -40 1.05 2.5,
+                          -39.475 0.909323 2.5,
+                          -42.25 2.25 2.5,
+                          -40.525 0.909323 2.5,
+                          -40 1.05 2.5,
+                          -42.25 2.25 2.5,
+                          -40.9093 0.525005 2.5,
+                          -40.525 0.909323 2.5,
+                          -42.25 2.25 2.5,
+                          -42.25 2.25 -2.5,
+                          -42.25 -2.25 -2.5,
+                          -42.25 -2.25 2.5,
+                          -37.6 -2.25 -2.5,
+                          -42.25 -2.25 2.5,
+                          -42.25 -2.25 -2.5,
+                          -37.6 -2.25 2.5,
+                          -42.25 -2.25 2.5,
+                          -37.6 -2.25 -2.5,
+                          -40.525 -0.909323 2.5,
+                          -42.25 -2.25 2.5,
+                          -37.6 -2.25 2.5,
+                          -40.525 -0.909323 2.5,
+                          -40.9093 -0.525005 2.5,
+                          -42.25 -2.25 2.5,
+                          -40.9093 0.525005 -2.5,
+                          -42.25 -2.25 -2.5,
+                          -42.25 2.25 -2.5,
+                          -39.475 -0.909323 -2.5,
+                          -37.6 -2.25 -2.5,
+                          -42.25 -2.25 -2.5,
+                          -40.9093 0.525005 -2.5,
+                          -41.05 -7.10543e-15 -2.5,
+                          -42.25 -2.25 -2.5,
+                          -40.9093 -0.525005 -2.5,
+                          -42.25 -2.25 -2.5,
+                          -41.05 -7.10543e-15 -2.5,
+                          -40 -1.05 -2.5,
+                          -39.475 -0.909323 -2.5,
+                          -42.25 -2.25 -2.5,
+                          -40.525 -0.909323 -2.5,
+                          -40 -1.05 -2.5,
+                          -42.25 -2.25 -2.5,
+                          -40.9093 -0.525005 -2.5,
+                          -40.525 -0.909323 -2.5,
+                          -42.25 -2.25 -2.5,
+                          -37.6 2.25 -2.5,
+                          -42.25 2.25 -2.5,
+                          -37.6 2.25 2.5,
+                          -40.525 0.909323 -2.5,
+                          -42.25 2.25 -2.5,
+                          -37.6 2.25 -2.5,
+                          -40.525 0.909323 -2.5,
+                          -40.9093 0.525005 -2.5,
+                          -42.25 2.25 -2.5,
+                          -0.228666 -0.703784 2.8,
+                          -0.1 -2.25 2.8,
+                          -2.25 -2.25 2.8,
+                          0.228666 -0.703784 2.8,
+                          0.598674 -0.434958 2.8,
+                          -0.1 -2.25 2.8,
+                          0.856699 -2.0597 2.8,
+                          -0.1 -2.25 2.8,
+                          0.598674 -0.434958 2.8,
+                          -0.228666 -0.703784 2.8,
+                          0.228666 -0.703784 2.8,
+                          -0.1 -2.25 2.8,
+                          -2.25 2.25 2.8,
+                          -2.25 -2.25 2.8,
+                          -2.25 -2.25 -2.8,
+                          -0.598674 0.434958 2.8,
+                          -2.25 -2.25 2.8,
+                          -2.25 2.25 2.8,
+                          -0.598674 -0.434958 2.8,
+                          -0.228666 -0.703784 2.8,
+                          -2.25 -2.25 2.8,
+                          -0.74 -1.42109e-14 2.8,
+                          -0.598674 -0.434958 2.8,
+                          -2.25 -2.25 2.8,
+                          -0.598674 0.434958 2.8,
+                          -0.74 -1.42109e-14 2.8,
+                          -2.25 -2.25 2.8,
+                          -2.25 2.25 -2.8,
+                          -2.25 -2.25 -2.8,
+                          -0.1 -2.25 -2.8,
+                          -2.25 2.25 2.8,
+                          -2.25 -2.25 -2.8,
+                          -2.25 2.25 -2.8,
+                          -0.75 -1.42109e-14 -2.8,
+                          -2.25 2.25 -2.8,
+                          -0.1 -2.25 -2.8,
+                          -0.606764 -0.440835 -2.8,
+                          -0.75 -1.42109e-14 -2.8,
+                          -0.1 -2.25 -2.8,
+                          -0.231756 -0.713294 -2.8,
+                          -0.606764 -0.440835 -2.8,
+                          -0.1 -2.25 -2.8,
+                          0.231756 -0.713294 -2.8,
+                          -0.231756 -0.713294 -2.8,
+                          -0.1 -2.25 -2.8,
+                          0.856699 -2.0597 -2.8,
+                          0.231756 -0.713294 -2.8,
+                          -0.1 -2.25 -2.8,
+                          -39.0907 -0.525005 -2.5,
+                          -37.6 2.25 -2.5,
+                          -37.6 -2.25 -2.5,
+                          -39.475 -0.909323 -2.5,
+                          -39.0907 -0.525005 -2.5,
+                          -37.6 -2.25 -2.5,
+                          -39.0907 0.525005 2.5,
+                          -37.6 -2.25 2.5,
+                          -37.6 2.25 2.5,
+                          -40 -1.05 2.5,
+                          -40.525 -0.909323 2.5,
+                          -37.6 -2.25 2.5,
+                          -39.475 -0.909323 2.5,
+                          -40 -1.05 2.5,
+                          -37.6 -2.25 2.5,
+                          -39.0907 -0.525005 2.5,
+                          -39.475 -0.909323 2.5,
+                          -37.6 -2.25 2.5,
+                          -38.95 -7.10543e-15 2.5,
+                          -39.0907 -0.525005 2.5,
+                          -37.6 -2.25 2.5,
+                          -39.0907 0.525005 2.5,
+                          -38.95 -7.10543e-15 2.5,
+                          -37.6 -2.25 2.5,
+                          2.2097 -0.706699 2.8,
+                          2.4 2.25 2.8,
+                          2.4 0.25 2.8,
+                          -0.228666 0.703784 2.8,
+                          -2.25 2.25 2.8,
+                          2.4 2.25 2.8,
+                          0.598674 0.434958 2.8,
+                          2.4 2.25 2.8,
+                          0.74 -1.42109e-14 2.8,
+                          0.856699 -2.0597 2.8,
+                          0.74 -1.42109e-14 2.8,
+                          2.4 2.25 2.8,
+                          0.228666 0.703784 2.8,
+                          -0.228666 0.703784 2.8,
+                          2.4 2.25 2.8,
+                          0.598674 0.434958 2.8,
+                          0.228666 0.703784 2.8,
+                          2.4 2.25 2.8,
+                          1.66777 -1.51777 2.8,
+                          0.856699 -2.0597 2.8,
+                          2.4 2.25 2.8,
+                          2.2097 -0.706699 2.8,
+                          1.66777 -1.51777 2.8,
+                          2.4 2.25 2.8,
+                          -2.25 2.25 -2.8,
+                          2.4 0.25 -2.8,
+                          2.4 2.25 -2.8,
+                          0.231756 0.713294 -2.8,
+                          2.4 0.25 -2.8,
+                          -2.25 2.25 -2.8,
+                          2.2097 -0.706699 -2.8,
+                          2.4 0.25 -2.8,
+                          0.231756 0.713294 -2.8,
+                          -39.475 0.909323 2.5,
+                          -39.0907 0.525005 2.5,
+                          -37.6 2.25 2.5,
+                          -40 1.05 -2.5,
+                          -40.525 0.909323 -2.5,
+                          -37.6 2.25 -2.5,
+                          -39.475 0.909323 -2.5,
+                          -40 1.05 -2.5,
+                          -37.6 2.25 -2.5,
+                          -39.0907 0.525005 -2.5,
+                          -39.475 0.909323 -2.5,
+                          -37.6 2.25 -2.5,
+                          -38.95 -7.10543e-15 -2.5,
+                          -39.0907 0.525005 -2.5,
+                          -37.6 2.25 -2.5,
+                          -39.0907 -0.525005 -2.5,
+                          -38.95 -7.10543e-15 -2.5,
+                          -37.6 2.25 -2.5,
+                          -0.606764 0.440835 -2.8,
+                          -2.25 2.25 -2.8,
+                          -0.75 -1.42109e-14 -2.8,
+                          -0.231756 0.713294 -2.8,
+                          0.231756 0.713294 -2.8,
+                          -2.25 2.25 -2.8,
+                          -0.606764 0.440835 -2.8,
+                          -0.231756 0.713294 -2.8,
+                          -2.25 2.25 -2.8,
+                          -0.228666 0.703784 2.8,
+                          -0.598674 0.434958 2.8,
+                          -2.25 2.25 2.8,
+                          0.856699 -2.0597 2.8,
+                          0.598674 -0.434958 2.8,
+                          0.74 -1.42109e-14 2.8,
+                          0.856699 -2.0597 -2.8,
+                          0.606764 -0.440835 -2.8,
+                          0.231756 -0.713294 -2.8,
+                          0.856699 -2.0597 -2.8,
+                          0.75 -1.42109e-14 -2.8,
+                          0.606764 -0.440835 -2.8,
+                          1.66777 -1.51777 -2.8,
+                          0.606764 0.440835 -2.8,
+                          0.75 -1.42109e-14 -2.8,
+                          0.856699 -2.0597 -2.8,
+                          1.66777 -1.51777 -2.8,
+                          0.75 -1.42109e-14 -2.8,
+                          2.2097 -0.706699 -2.8,
+                          0.231756 0.713294 -2.8,
+                          0.606764 0.440835 -2.8,
+                          1.66777 -1.51777 -2.8,
+                          2.2097 -0.706699 -2.8,
+                          0.606764 0.440835 -2.8,
+                          -41.05 -7.10543e-15 -2.5,
+                          -41.05 -7.10543e-15 2.5,
+                          -40.9093 -0.525005 2.5,
+                          -40.9093 0.525005 -2.5,
+                          -40.9093 0.525005 2.5,
+                          -41.05 -7.10543e-15 2.5,
+                          -40.9093 0.525005 -2.5,
+                          -41.05 -7.10543e-15 2.5,
+                          -41.05 -7.10543e-15 -2.5,
+                          -40.9093 -0.525005 -2.5,
+                          -40.9093 -0.525005 2.5,
+                          -40.525 -0.909323 2.5,
+                          -40.9093 -0.525005 -2.5,
+                          -41.05 -7.10543e-15 -2.5,
+                          -40.9093 -0.525005 2.5,
+                          -40.525 -0.909323 -2.5,
+                          -40.525 -0.909323 2.5,
+                          -40 -1.05 2.5,
+                          -40.9093 -0.525005 -2.5,
+                          -40.525 -0.909323 2.5,
+                          -40.525 -0.909323 -2.5,
+                          -40 -1.05 -2.5,
+                          -40 -1.05 2.5,
+                          -39.475 -0.909323 2.5,
+                          -40.525 -0.909323 -2.5,
+                          -40 -1.05 2.5,
+                          -40 -1.05 -2.5,
+                          -39.475 -0.909323 -2.5,
+                          -39.475 -0.909323 2.5,
+                          -39.0907 -0.525005 2.5,
+                          -40 -1.05 -2.5,
+                          -39.475 -0.909323 2.5,
+                          -39.475 -0.909323 -2.5,
+                          -39.0907 -0.525005 -2.5,
+                          -39.0907 -0.525005 2.5,
+                          -38.95 -7.10543e-15 2.5,
+                          -39.475 -0.909323 -2.5,
+                          -39.0907 -0.525005 2.5,
+                          -39.0907 -0.525005 -2.5,
+                          -38.95 -7.10543e-15 -2.5,
+                          -38.95 -7.10543e-15 2.5,
+                          -39.0907 0.525005 2.5,
+                          -39.0907 -0.525005 -2.5,
+                          -38.95 -7.10543e-15 2.5,
+                          -38.95 -7.10543e-15 -2.5,
+                          -39.0907 0.525005 -2.5,
+                          -39.0907 0.525005 2.5,
+                          -39.475 0.909323 2.5,
+                          -38.95 -7.10543e-15 -2.5,
+                          -39.0907 0.525005 2.5,
+                          -39.0907 0.525005 -2.5,
+                          -39.475 0.909323 -2.5,
+                          -39.475 0.909323 2.5,
+                          -40 1.05 2.5,
+                          -39.0907 0.525005 -2.5,
+                          -39.475 0.909323 2.5,
+                          -39.475 0.909323 -2.5,
+                          -40 1.05 -2.5,
+                          -40 1.05 2.5,
+                          -40.525 0.909323 2.5,
+                          -39.475 0.909323 -2.5,
+                          -40 1.05 2.5,
+                          -40 1.05 -2.5,
+                          -40.525 0.909323 -2.5,
+                          -40.525 0.909323 2.5,
+                          -40.9093 0.525005 2.5,
+                          -40 1.05 -2.5,
+                          -40.525 0.909323 2.5,
+                          -40.525 0.909323 -2.5,
+                          -40.525 0.909323 -2.5,
+                          -40.9093 0.525005 2.5,
+                          -40.9093 0.525005 -2.5 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          -1 2.91434e-16 -1.1666e-16,
+                          -1 2.91434e-16 -1.1666e-16,
+                          -0.809017 -0.587785 -2.09656e-17,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          -0.809017 0.587785 -1.67794e-16,
+                          -0.809017 0.587785 -1.67794e-16,
+                          -1 5.36363e-16 -1.1666e-16,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          -0.809017 0.587785 -1.67794e-16,
+                          -1 5.36363e-16 -1.1666e-16,
+                          -1 5.36363e-16 -1.1666e-16,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          -0.809017 -0.587785 -2.09656e-17,
+                          -0.809017 -0.587785 -2.09656e-17,
+                          -0.309017 -0.951057 8.27371e-17,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          -0.809017 -0.587785 -2.09656e-17,
+                          -1 2.91434e-16 -1.1666e-16,
+                          -0.809017 -0.587785 -2.09656e-17,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          -0.309017 -0.951057 8.27371e-17,
+                          -0.309017 -0.951057 8.27371e-17,
+                          0.309017 -0.951057 1.54837e-16,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          -0.809017 -0.587785 -2.09656e-17,
+                          -0.309017 -0.951057 8.27371e-17,
+                          -0.309017 -0.951057 8.27371e-17,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          0.309017 -0.951057 1.54837e-16,
+                          0.309017 -0.951057 1.54837e-16,
+                          0.809017 -0.587785 1.67794e-16,
+                          -0.309017 -0.951057 8.27371e-17,
+                          0.309017 -0.951057 1.54837e-16,
+                          0.309017 -0.951057 1.54837e-16,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          0.809017 -0.587785 1.67794e-16,
+                          0.809017 -0.587785 1.67794e-16,
+                          1 -4.13898e-16 1.1666e-16,
+                          0.309017 -0.951057 1.54837e-16,
+                          0.809017 -0.587785 1.67794e-16,
+                          0.809017 -0.587785 1.67794e-16,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1 -4.13898e-16 1.1666e-16,
+                          1 -4.13898e-16 1.1666e-16,
+                          0.809017 0.587785 2.09656e-17,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          0.809017 -0.587785 1.67794e-16,
+                          1 -4.13898e-16 1.1666e-16,
+                          1 -4.13898e-16 1.1666e-16,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          0.809017 0.587785 2.09656e-17,
+                          0.809017 0.587785 2.09656e-17,
+                          0.309017 0.951057 -8.27371e-17,
+                          1 -4.13898e-16 1.1666e-16,
+                          0.809017 0.587785 2.09656e-17,
+                          0.809017 0.587785 2.09656e-17,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          0.309017 0.951057 -8.27371e-17,
+                          0.309017 0.951057 -8.27371e-17,
+                          -0.309017 0.951057 -1.54837e-16,
+                          0.809017 0.587785 2.09656e-17,
+                          0.309017 0.951057 -8.27371e-17,
+                          0.309017 0.951057 -8.27371e-17,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          -0.309017 0.951057 -1.54837e-16,
+                          -0.309017 0.951057 -1.54837e-16,
+                          -0.809017 0.587785 -1.67794e-16,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          0.309017 0.951057 -8.27371e-17,
+                          -0.309017 0.951057 -1.54837e-16,
+                          -0.309017 0.951057 -1.54837e-16,
+                          -0.309017 0.951057 -1.54837e-16,
+                          -0.809017 0.587785 -1.67794e-16,
+                          -0.809017 0.587785 -1.67794e-16,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          -1 2.91434e-16 -1.1666e-16,
+                          -1 2.91434e-16 -1.1666e-16,
+                          -1 2.91434e-16 -1.1666e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          -2.98372e-16 1 -1.249e-16,
+                          -2.98372e-16 1 -1.249e-16,
+                          -2.98372e-16 1 -1.249e-16,
+                          -1 2.91434e-16 -1.1666e-16,
+                          -1 2.91434e-16 -1.1666e-16,
+                          -1 2.91434e-16 -1.1666e-16,
+                          1 -2.91434e-16 1.1666e-16,
+                          1 -2.91434e-16 1.1666e-16,
+                          1 -2.91434e-16 1.1666e-16,
+                          -2.98372e-16 1 -1.249e-16,
+                          -2.98372e-16 1 -1.249e-16,
+                          -2.98372e-16 1 -1.249e-16,
+                          -2.98372e-16 1 -1.249e-16,
+                          -2.98372e-16 1 -1.249e-16,
+                          -2.98372e-16 1 -1.249e-16,
+                          1 -2.91434e-16 1.1666e-16,
+                          1 -2.91434e-16 1.1666e-16,
+                          1 -2.91434e-16 1.1666e-16,
+                          -2.98372e-16 1 -1.249e-16,
+                          -2.98372e-16 1 -1.249e-16,
+                          -2.98372e-16 1 -1.249e-16,
+                          -2.98372e-16 1 -1.249e-16,
+                          -2.98372e-16 1 -1.249e-16,
+                          -2.98372e-16 1 -1.249e-16,
+                          1 -5.36363e-16 1.1666e-16,
+                          1 -5.36363e-16 1.1666e-16,
+                          0.92388 -0.382683 1.55577e-16,
+                          0.92388 -0.382683 1.55577e-16,
+                          0.92388 -0.382683 1.55577e-16,
+                          0.707107 -0.707107 1.70809e-16,
+                          0.92388 -0.382683 1.55577e-16,
+                          1 -5.36363e-16 1.1666e-16,
+                          0.92388 -0.382683 1.55577e-16,
+                          0.707107 -0.707107 1.70809e-16,
+                          0.707107 -0.707107 1.70809e-16,
+                          0.382683 -0.92388 1.60037e-16,
+                          0.92388 -0.382683 1.55577e-16,
+                          0.707107 -0.707107 1.70809e-16,
+                          0.707107 -0.707107 1.70809e-16,
+                          0.382683 -0.92388 1.60037e-16,
+                          0.382683 -0.92388 1.60037e-16,
+                          1.14675e-16 -1 1.249e-16,
+                          0.707107 -0.707107 1.70809e-16,
+                          0.382683 -0.92388 1.60037e-16,
+                          0.382683 -0.92388 1.60037e-16,
+                          0.382683 -0.92388 1.60037e-16,
+                          1.14675e-16 -1 1.249e-16,
+                          1.14675e-16 -1 1.249e-16,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          1 -2.91434e-16 1.1666e-16,
+                          1 -2.91434e-16 1.1666e-16,
+                          0.809017 -0.587785 1.67794e-16,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          0.809017 0.587785 2.09656e-17,
+                          0.809017 0.587785 2.09656e-17,
+                          1 -4.65042e-17 1.1666e-16,
+                          0.809017 0.587785 2.09656e-17,
+                          1 -4.65042e-17 1.1666e-16,
+                          1 -4.65042e-17 1.1666e-16,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          0.809017 -0.587785 1.67794e-16,
+                          0.809017 -0.587785 1.67794e-16,
+                          0.309017 -0.951057 1.54837e-16,
+                          0.809017 -0.587785 1.67794e-16,
+                          1 -2.91434e-16 1.1666e-16,
+                          0.809017 -0.587785 1.67794e-16,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          0.309017 -0.951057 1.54837e-16,
+                          0.309017 -0.951057 1.54837e-16,
+                          -0.309017 -0.951057 8.27371e-17,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          0.809017 -0.587785 1.67794e-16,
+                          0.309017 -0.951057 1.54837e-16,
+                          0.309017 -0.951057 1.54837e-16,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -0.309017 -0.951057 8.27371e-17,
+                          -0.309017 -0.951057 8.27371e-17,
+                          -0.809017 -0.587785 -2.09656e-17,
+                          0.309017 -0.951057 1.54837e-16,
+                          -0.309017 -0.951057 8.27371e-17,
+                          -0.309017 -0.951057 8.27371e-17,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -0.809017 -0.587785 -2.09656e-17,
+                          -0.809017 -0.587785 -2.09656e-17,
+                          -1 1.68969e-16 -1.1666e-16,
+                          -0.309017 -0.951057 8.27371e-17,
+                          -0.809017 -0.587785 -2.09656e-17,
+                          -0.809017 -0.587785 -2.09656e-17,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1 1.68969e-16 -1.1666e-16,
+                          -1 1.68969e-16 -1.1666e-16,
+                          -0.809017 0.587785 -1.67794e-16,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -0.809017 -0.587785 -2.09656e-17,
+                          -1 1.68969e-16 -1.1666e-16,
+                          -1 1.68969e-16 -1.1666e-16,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -0.809017 0.587785 -1.67794e-16,
+                          -0.809017 0.587785 -1.67794e-16,
+                          -0.309017 0.951057 -1.54837e-16,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1 1.68969e-16 -1.1666e-16,
+                          -0.809017 0.587785 -1.67794e-16,
+                          -0.809017 0.587785 -1.67794e-16,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -0.309017 0.951057 -1.54837e-16,
+                          -0.309017 0.951057 -1.54837e-16,
+                          0.309017 0.951057 -8.27371e-17,
+                          -0.809017 0.587785 -1.67794e-16,
+                          -0.309017 0.951057 -1.54837e-16,
+                          -0.309017 0.951057 -1.54837e-16,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          0.309017 0.951057 -8.27371e-17,
+                          0.309017 0.951057 -8.27371e-17,
+                          0.809017 0.587785 2.09656e-17,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -0.309017 0.951057 -1.54837e-16,
+                          0.309017 0.951057 -8.27371e-17,
+                          0.309017 0.951057 -8.27371e-17,
+                          0.309017 0.951057 -8.27371e-17,
+                          0.809017 0.587785 2.09656e-17,
+                          0.809017 0.587785 2.09656e-17,
+                          1.14675e-16 -1 1.249e-16,
+                          1.14675e-16 -1 1.249e-16,
+                          0.382683 -0.92388 1.60037e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          0.382683 -0.92388 1.60037e-16,
+                          0.382683 -0.92388 1.60037e-16,
+                          0.707107 -0.707107 1.70809e-16,
+                          0.382683 -0.92388 1.60037e-16,
+                          1.14675e-16 -1 1.249e-16,
+                          0.382683 -0.92388 1.60037e-16,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          0.707107 -0.707107 1.70809e-16,
+                          0.707107 -0.707107 1.70809e-16,
+                          0.92388 -0.382683 1.55577e-16,
+                          0.382683 -0.92388 1.60037e-16,
+                          0.707107 -0.707107 1.70809e-16,
+                          0.707107 -0.707107 1.70809e-16,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          0.92388 -0.382683 1.55577e-16,
+                          0.92388 -0.382683 1.55577e-16,
+                          1 -5.36363e-16 1.1666e-16,
+                          0.707107 -0.707107 1.70809e-16,
+                          0.92388 -0.382683 1.55577e-16,
+                          0.92388 -0.382683 1.55577e-16,
+                          1 -2.91434e-16 1.1666e-16,
+                          1 -2.91434e-16 1.1666e-16,
+                          1 -2.91434e-16 1.1666e-16,
+                          1 -2.91434e-16 1.1666e-16,
+                          1 -2.91434e-16 1.1666e-16,
+                          1 -2.91434e-16 1.1666e-16,
+                          0.92388 -0.382683 1.55577e-16,
+                          1 -5.36363e-16 1.1666e-16,
+                          1 -5.36363e-16 1.1666e-16,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -2.98372e-16 1 -1.249e-16,
+                          -2.98372e-16 1 -1.249e-16,
+                          -2.98372e-16 1 -1.249e-16,
+                          -1 2.91434e-16 -1.1666e-16,
+                          -1 2.91434e-16 -1.1666e-16,
+                          -1 2.91434e-16 -1.1666e-16,
+                          -2.98372e-16 1 -1.249e-16,
+                          -2.98372e-16 1 -1.249e-16,
+                          -2.98372e-16 1 -1.249e-16,
+                          -2.98372e-16 1 -1.249e-16,
+                          -2.98372e-16 1 -1.249e-16,
+                          -2.98372e-16 1 -1.249e-16,
+                          -1 2.91434e-16 -1.1666e-16,
+                          -1 2.91434e-16 -1.1666e-16,
+                          -1 2.91434e-16 -1.1666e-16,
+                          -1 2.91434e-16 -1.1666e-16,
+                          -1 2.91434e-16 -1.1666e-16,
+                          -1 2.91434e-16 -1.1666e-16,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          -2.98372e-16 1 -1.249e-16,
+                          -2.98372e-16 1 -1.249e-16,
+                          -2.98372e-16 1 -1.249e-16,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          -1 2.91434e-16 -1.1666e-16,
+                          -1 2.91434e-16 -1.1666e-16,
+                          -1 2.91434e-16 -1.1666e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          2.98372e-16 -1 1.249e-16,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -2.98372e-16 1 -1.249e-16,
+                          -2.98372e-16 1 -1.249e-16,
+                          -2.98372e-16 1 -1.249e-16,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          1 -2.91434e-16 1.1666e-16,
+                          1 -2.91434e-16 1.1666e-16,
+                          1 -2.91434e-16 1.1666e-16,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1 -2.91434e-16 1.1666e-16,
+                          1 -2.91434e-16 1.1666e-16,
+                          1 -2.91434e-16 1.1666e-16,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          -1.34007e-16 -2.08167e-17 -1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1.34007e-16 2.08167e-17 1,
+                          1 -4.65042e-17 1.1666e-16,
+                          1 -4.65042e-17 1.1666e-16,
+                          0.866025 0.5 3.85806e-17,
+                          0.866025 -0.5 1.63481e-16,
+                          0.866025 -0.5 1.63481e-16,
+                          1 -2.91434e-16 1.1666e-16,
+                          0.866025 -0.5 1.63481e-16,
+                          1 -2.91434e-16 1.1666e-16,
+                          1 -2.91434e-16 1.1666e-16,
+                          0.866025 0.5 3.85806e-17,
+                          0.866025 0.5 3.85806e-17,
+                          0.5 0.866025 -4.98366e-17,
+                          0.866025 0.5 3.85806e-17,
+                          1 -4.65042e-17 1.1666e-16,
+                          0.866025 0.5 3.85806e-17,
+                          0.5 0.866025 -4.98366e-17,
+                          0.5 0.866025 -4.98366e-17,
+                          1.29429e-15 1 -1.249e-16,
+                          0.866025 0.5 3.85806e-17,
+                          0.5 0.866025 -4.98366e-17,
+                          0.5 0.866025 -4.98366e-17,
+                          1.29429e-15 1 -1.249e-16,
+                          1.29429e-15 1 -1.249e-16,
+                          -0.5 0.866025 -1.66497e-16,
+                          0.5 0.866025 -4.98366e-17,
+                          1.29429e-15 1 -1.249e-16,
+                          1.29429e-15 1 -1.249e-16,
+                          -0.5 0.866025 -1.66497e-16,
+                          -0.5 0.866025 -1.66497e-16,
+                          -0.866025 0.5 -1.63481e-16,
+                          1.29429e-15 1 -1.249e-16,
+                          -0.5 0.866025 -1.66497e-16,
+                          -0.5 0.866025 -1.66497e-16,
+                          -0.866025 0.5 -1.63481e-16,
+                          -0.866025 0.5 -1.63481e-16,
+                          -1 1.68969e-16 -1.1666e-16,
+                          -0.5 0.866025 -1.66497e-16,
+                          -0.866025 0.5 -1.63481e-16,
+                          -0.866025 0.5 -1.63481e-16,
+                          -1 1.68969e-16 -1.1666e-16,
+                          -1 1.68969e-16 -1.1666e-16,
+                          -0.866025 -0.5 -3.85806e-17,
+                          -0.866025 0.5 -1.63481e-16,
+                          -1 1.68969e-16 -1.1666e-16,
+                          -1 1.68969e-16 -1.1666e-16,
+                          -0.866025 -0.5 -3.85806e-17,
+                          -0.866025 -0.5 -3.85806e-17,
+                          -0.5 -0.866025 4.98366e-17,
+                          -1 1.68969e-16 -1.1666e-16,
+                          -0.866025 -0.5 -3.85806e-17,
+                          -0.866025 -0.5 -3.85806e-17,
+                          -0.5 -0.866025 4.98366e-17,
+                          -0.5 -0.866025 4.98366e-17,
+                          -4.52538e-15 -1 1.249e-16,
+                          -0.866025 -0.5 -3.85806e-17,
+                          -0.5 -0.866025 4.98366e-17,
+                          -0.5 -0.866025 4.98366e-17,
+                          -4.52538e-15 -1 1.249e-16,
+                          -4.52538e-15 -1 1.249e-16,
+                          0.5 -0.866025 1.66497e-16,
+                          -0.5 -0.866025 4.98366e-17,
+                          -4.52538e-15 -1 1.249e-16,
+                          -4.52538e-15 -1 1.249e-16,
+                          0.5 -0.866025 1.66497e-16,
+                          0.5 -0.866025 1.66497e-16,
+                          0.866025 -0.5 1.63481e-16,
+                          -4.52538e-15 -1 1.249e-16,
+                          0.5 -0.866025 1.66497e-16,
+                          0.5 -0.866025 1.66497e-16,
+                          0.5 -0.866025 1.66497e-16,
+                          0.866025 -0.5 1.63481e-16,
+                          0.866025 -0.5 1.63481e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 1.66777 -1.51777 32,
+                          0.598674 0.434958 32,
+                          0.74 7.06185e-15 32,
+                          0.74 7.03132e-15 29.8,
+                          0.74 7.06185e-15 32,
+                          0.598674 0.434958 32,
+                          0.856699 -2.0597 32,
+                          0.74 7.06185e-15 32,
+                          0.598674 -0.434958 32,
+                          0.598674 -0.434958 29.8,
+                          0.598674 -0.434958 32,
+                          0.74 7.06185e-15 32,
+                          0.856699 -2.0597 32,
+                          1.66777 -1.51777 32,
+                          0.74 7.06185e-15 32,
+                          0.598674 -0.434958 29.8,
+                          0.74 7.06185e-15 32,
+                          0.74 7.03132e-15 29.8,
+                          2.2097 -0.706699 32,
+                          0.228666 0.703784 32,
+                          0.598674 0.434958 32,
+                          0.598674 0.434958 29.8,
+                          0.598674 0.434958 32,
+                          0.228666 0.703784 32,
+                          1.66777 -1.51777 32,
+                          2.2097 -0.706699 32,
+                          0.598674 0.434958 32,
+                          0.598674 0.434958 29.8,
+                          0.74 7.03132e-15 29.8,
+                          0.598674 0.434958 32,
+                          -37.6 2.25 32,
+                          -0.228666 0.703784 32,
+                          0.228666 0.703784 32,
+                          0.228666 0.703784 29.8,
+                          0.228666 0.703784 32,
+                          -0.228666 0.703784 32,
+                          2.4 2.25 32,
+                          -37.6 2.25 32,
+                          0.228666 0.703784 32,
+                          2.4 0.25 32,
+                          2.4 2.25 32,
+                          0.228666 0.703784 32,
+                          2.2097 -0.706699 32,
+                          2.4 0.25 32,
+                          0.228666 0.703784 32,
+                          0.598674 0.434958 29.8,
+                          0.228666 0.703784 32,
+                          0.228666 0.703784 29.8,
+                          -37.6 2.25 32,
+                          -0.598674 0.434958 32,
+                          -0.228666 0.703784 32,
+                          -0.228666 0.703784 29.8,
+                          -0.228666 0.703784 32,
+                          -0.598674 0.434958 32,
+                          0.228666 0.703784 29.8,
+                          -0.228666 0.703784 32,
+                          -0.228666 0.703784 29.8,
+                          -37.6 2.25 32,
+                          -0.74 7.28778e-15 32,
+                          -0.598674 0.434958 32,
+                          -0.598674 0.434958 29.8,
+                          -0.598674 0.434958 32,
+                          -0.74 7.28778e-15 32,
+                          -0.228666 0.703784 29.8,
+                          -0.598674 0.434958 32,
+                          -0.598674 0.434958 29.8,
+                          -0.1 -2.25 32,
+                          -0.598674 -0.434958 32,
+                          -0.74 7.28778e-15 32,
+                          -0.74 7.25725e-15 29.8,
+                          -0.74 7.28778e-15 32,
+                          -0.598674 -0.434958 32,
+                          -0.1 -2.25 32,
+                          -0.74 7.28778e-15 32,
+                          -37.6 2.25 32,
+                          -0.598674 0.434958 29.8,
+                          -0.74 7.28778e-15 32,
+                          -0.74 7.25725e-15 29.8,
+                          -0.1 -2.25 32,
+                          -0.228666 -0.703784 32,
+                          -0.598674 -0.434958 32,
+                          -0.598674 -0.434958 29.8,
+                          -0.598674 -0.434958 32,
+                          -0.228666 -0.703784 32,
+                          -0.74 7.25725e-15 29.8,
+                          -0.598674 -0.434958 32,
+                          -0.598674 -0.434958 29.8,
+                          -0.1 -2.25 32,
+                          0.228666 -0.703784 32,
+                          -0.228666 -0.703784 32,
+                          -0.228666 -0.703784 29.8,
+                          -0.228666 -0.703784 32,
+                          0.228666 -0.703784 32,
+                          -0.598674 -0.434958 29.8,
+                          -0.228666 -0.703784 32,
+                          -0.228666 -0.703784 29.8,
+                          0.856699 -2.0597 32,
+                          0.598674 -0.434958 32,
+                          0.228666 -0.703784 32,
+                          0.228666 -0.703784 29.8,
+                          0.228666 -0.703784 32,
+                          0.598674 -0.434958 32,
+                          -0.1 -2.25 32,
+                          0.856699 -2.0597 32,
+                          0.228666 -0.703784 32,
+                          -0.228666 -0.703784 29.8,
+                          0.228666 -0.703784 32,
+                          0.228666 -0.703784 29.8,
+                          0.228666 -0.703784 29.8,
+                          0.598674 -0.434958 32,
+                          0.598674 -0.434958 29.8,
+                          -0.1 -2.25 32,
+                          -37.6 2.25 32,
+                          -37.6 -2.25 32,
+                          -37.6 -2.25 29.5,
+                          -37.6 -2.25 32,
+                          -37.6 2.25 32,
+                          -0.1 -2.25 29.8,
+                          -0.1 -2.25 32,
+                          -37.6 -2.25 32,
+                          -2.25 -2.25 24.2,
+                          -37.6 -2.25 32,
+                          -0.1 -2.25 22,
+                          -37.6 -2.25 29.5,
+                          -0.1 -2.25 22,
+                          -37.6 -2.25 32,
+                          -2.25 -2.25 29.8,
+                          -0.1 -2.25 29.8,
+                          -37.6 -2.25 32,
+                          -2.25 -2.25 24.2,
+                          -2.25 -2.25 29.8,
+                          -37.6 -2.25 32,
+                          -37.6 2.25 29.5,
+                          -37.6 2.25 32,
+                          2.4 2.25 32,
+                          -37.6 2.25 29.5,
+                          -37.6 -2.25 29.5,
+                          -37.6 2.25 32,
+                          2.4 0.25 29.8,
+                          2.4 2.25 32,
+                          2.4 0.25 32,
+                          -37.6 2.25 24.5,
+                          2.4 2.25 32,
+                          -37.6 2.25 22,
+                          -2.25 2.25 29.8,
+                          -37.6 2.25 22,
+                          2.4 2.25 32,
+                          2.4 0.25 29.8,
+                          2.4 2.25 29.8,
+                          2.4 2.25 32,
+                          -2.25 2.25 29.8,
+                          2.4 2.25 32,
+                          2.4 2.25 29.8,
+                          -37.6 2.25 24.5,
+                          -37.6 2.25 29.5,
+                          2.4 2.25 32,
+                          2.4 0.25 29.8,
+                          2.4 0.25 32,
+                          2.2097 -0.706699 32,
+                          2.2097 -0.706699 29.8,
+                          2.2097 -0.706699 32,
+                          1.66777 -1.51777 32,
+                          2.2097 -0.706699 29.8,
+                          2.4 0.25 29.8,
+                          2.2097 -0.706699 32,
+                          1.66777 -1.51777 29.8,
+                          1.66777 -1.51777 32,
+                          0.856699 -2.0597 32,
+                          2.2097 -0.706699 29.8,
+                          1.66777 -1.51777 32,
+                          1.66777 -1.51777 29.8,
+                          0.856699 -2.0597 29.8,
+                          0.856699 -2.0597 32,
+                          -0.1 -2.25 32,
+                          1.66777 -1.51777 29.8,
+                          0.856699 -2.0597 32,
+                          0.856699 -2.0597 29.8,
+                          0.856699 -2.0597 29.8,
+                          -0.1 -2.25 32,
+                          -0.1 -2.25 29.8,
+                          -37.6 -2.25 22,
+                          -0.606764 0.440835 22,
+                          -0.75 7.15053e-15 22,
+                          -0.75 7.18106e-15 24.2,
+                          -0.75 7.15053e-15 22,
+                          -0.606764 0.440835 22,
+                          -37.6 -2.25 22,
+                          -0.75 7.15053e-15 22,
+                          -0.606764 -0.440835 22,
+                          -0.606764 -0.440835 24.2,
+                          -0.606764 -0.440835 22,
+                          -0.75 7.15053e-15 22,
+                          -0.606764 -0.440835 24.2,
+                          -0.75 7.15053e-15 22,
+                          -0.75 7.18106e-15 24.2,
+                          -37.6 -2.25 22,
+                          -0.231756 0.713294 22,
+                          -0.606764 0.440835 22,
+                          -0.606764 0.440835 24.2,
+                          -0.606764 0.440835 22,
+                          -0.231756 0.713294 22,
+                          -0.606764 0.440835 24.2,
+                          -0.75 7.18106e-15 24.2,
+                          -0.606764 0.440835 22,
+                          2.4 2.25 22,
+                          0.231756 0.713294 22,
+                          -0.231756 0.713294 22,
+                          -0.231756 0.713294 24.2,
+                          -0.231756 0.713294 22,
+                          0.231756 0.713294 22,
+                          -37.6 -2.25 22,
+                          2.4 2.25 22,
+                          -0.231756 0.713294 22,
+                          -0.606764 0.440835 24.2,
+                          -0.231756 0.713294 22,
+                          -0.231756 0.713294 24.2,
+                          2.4 2.25 22,
+                          0.606764 0.440835 22,
+                          0.231756 0.713294 22,
+                          0.231756 0.713294 24.2,
+                          0.231756 0.713294 22,
+                          0.606764 0.440835 22,
+                          -0.231756 0.713294 24.2,
+                          0.231756 0.713294 22,
+                          0.231756 0.713294 24.2,
+                          2.4 2.25 22,
+                          0.75 6.92155e-15 22,
+                          0.606764 0.440835 22,
+                          0.606764 0.440835 24.2,
+                          0.606764 0.440835 22,
+                          0.75 6.92155e-15 22,
+                          0.231756 0.713294 24.2,
+                          0.606764 0.440835 22,
+                          0.606764 0.440835 24.2,
+                          0.856699 -2.0597 22,
+                          0.606764 -0.440835 22,
+                          0.75 6.92155e-15 22,
+                          0.75 6.95208e-15 24.2,
+                          0.75 6.92155e-15 22,
+                          0.606764 -0.440835 22,
+                          2.4 2.25 22,
+                          0.856699 -2.0597 22,
+                          0.75 6.92155e-15 22,
+                          0.606764 0.440835 24.2,
+                          0.75 6.92155e-15 22,
+                          0.75 6.95208e-15 24.2,
+                          -0.1 -2.25 22,
+                          0.231756 -0.713294 22,
+                          0.606764 -0.440835 22,
+                          0.606764 -0.440835 24.2,
+                          0.606764 -0.440835 22,
+                          0.231756 -0.713294 22,
+                          0.856699 -2.0597 22,
+                          -0.1 -2.25 22,
+                          0.606764 -0.440835 22,
+                          0.75 6.95208e-15 24.2,
+                          0.606764 -0.440835 22,
+                          0.606764 -0.440835 24.2,
+                          -0.1 -2.25 22,
+                          -0.231756 -0.713294 22,
+                          0.231756 -0.713294 22,
+                          0.231756 -0.713294 24.2,
+                          0.231756 -0.713294 22,
+                          -0.231756 -0.713294 22,
+                          0.606764 -0.440835 24.2,
+                          0.231756 -0.713294 22,
+                          0.231756 -0.713294 24.2,
+                          -37.6 -2.25 22,
+                          -0.606764 -0.440835 22,
+                          -0.231756 -0.713294 22,
+                          -0.231756 -0.713294 24.2,
+                          -0.231756 -0.713294 22,
+                          -0.606764 -0.440835 22,
+                          -37.6 -2.25 22,
+                          -0.231756 -0.713294 22,
+                          -0.1 -2.25 22,
+                          0.231756 -0.713294 24.2,
+                          -0.231756 -0.713294 22,
+                          -0.231756 -0.713294 24.2,
+                          -0.231756 -0.713294 24.2,
+                          -0.606764 -0.440835 22,
+                          -0.606764 -0.440835 24.2,
+                          -0.1 -2.25 24.2,
+                          -0.1 -2.25 22,
+                          0.856699 -2.0597 22,
+                          -37.6 -2.25 24.5,
+                          -37.6 -2.25 22,
+                          -0.1 -2.25 22,
+                          -0.1 -2.25 24.2,
+                          -2.25 -2.25 24.2,
+                          -0.1 -2.25 22,
+                          -37.6 -2.25 29.5,
+                          -37.6 -2.25 24.5,
+                          -0.1 -2.25 22,
+                          2.4 2.25 22,
+                          1.66777 -1.51777 22,
+                          0.856699 -2.0597 22,
+                          0.856699 -2.0597 24.2,
+                          0.856699 -2.0597 22,
+                          1.66777 -1.51777 22,
+                          0.856699 -2.0597 24.2,
+                          -0.1 -2.25 24.2,
+                          0.856699 -2.0597 22,
+                          2.4 2.25 22,
+                          2.2097 -0.706699 22,
+                          1.66777 -1.51777 22,
+                          1.66777 -1.51777 24.2,
+                          1.66777 -1.51777 22,
+                          2.2097 -0.706699 22,
+                          0.856699 -2.0597 24.2,
+                          1.66777 -1.51777 22,
+                          1.66777 -1.51777 24.2,
+                          2.4 2.25 22,
+                          2.4 0.25 22,
+                          2.2097 -0.706699 22,
+                          2.2097 -0.706699 24.2,
+                          2.2097 -0.706699 22,
+                          2.4 0.25 22,
+                          1.66777 -1.51777 24.2,
+                          2.2097 -0.706699 22,
+                          2.2097 -0.706699 24.2,
+                          2.4 2.25 24.2,
+                          2.4 0.25 22,
+                          2.4 2.25 22,
+                          2.4 2.25 24.2,
+                          2.4 0.25 24.2,
+                          2.4 0.25 22,
+                          2.2097 -0.706699 24.2,
+                          2.4 0.25 22,
+                          2.4 0.25 24.2,
+                          -37.6 -2.25 22,
+                          -37.6 2.25 22,
+                          2.4 2.25 22,
+                          2.4 2.25 24.2,
+                          2.4 2.25 22,
+                          -37.6 2.25 22,
+                          -37.6 2.25 24.5,
+                          -37.6 2.25 22,
+                          -37.6 -2.25 22,
+                          -2.25 2.25 24.2,
+                          2.4 2.25 24.2,
+                          -37.6 2.25 22,
+                          -2.25 2.25 29.8,
+                          -2.25 2.25 24.2,
+                          -37.6 2.25 22,
+                          -37.6 2.25 24.5,
+                          -37.6 -2.25 22,
+                          -37.6 -2.25 24.5,
+                          -42.25 2.25 24.5,
+                          -42.25 -2.25 29.5,
+                          -42.25 2.25 29.5,
+                          -40.9093 -0.525005 29.5,
+                          -42.25 2.25 29.5,
+                          -42.25 -2.25 29.5,
+                          -37.6 2.25 29.5,
+                          -42.25 2.25 24.5,
+                          -42.25 2.25 29.5,
+                          -39.475 0.909323 29.5,
+                          -37.6 2.25 29.5,
+                          -42.25 2.25 29.5,
+                          -40.9093 -0.525005 29.5,
+                          -41.05 2.05121e-14 29.5,
+                          -42.25 2.25 29.5,
+                          -40.9093 0.525005 29.5,
+                          -42.25 2.25 29.5,
+                          -41.05 2.05121e-14 29.5,
+                          -40 1.05 29.5,
+                          -39.475 0.909323 29.5,
+                          -42.25 2.25 29.5,
+                          -40.525 0.909323 29.5,
+                          -40 1.05 29.5,
+                          -42.25 2.25 29.5,
+                          -40.9093 0.525005 29.5,
+                          -40.525 0.909323 29.5,
+                          -42.25 2.25 29.5,
+                          -42.25 2.25 24.5,
+                          -42.25 -2.25 24.5,
+                          -42.25 -2.25 29.5,
+                          -37.6 -2.25 24.5,
+                          -42.25 -2.25 29.5,
+                          -42.25 -2.25 24.5,
+                          -37.6 -2.25 29.5,
+                          -42.25 -2.25 29.5,
+                          -37.6 -2.25 24.5,
+                          -40.525 -0.909323 29.5,
+                          -42.25 -2.25 29.5,
+                          -37.6 -2.25 29.5,
+                          -40.525 -0.909323 29.5,
+                          -40.9093 -0.525005 29.5,
+                          -42.25 -2.25 29.5,
+                          -40.9093 0.525005 24.5,
+                          -42.25 -2.25 24.5,
+                          -42.25 2.25 24.5,
+                          -39.475 -0.909323 24.5,
+                          -37.6 -2.25 24.5,
+                          -42.25 -2.25 24.5,
+                          -40.9093 0.525005 24.5,
+                          -41.05 2.04427e-14 24.5,
+                          -42.25 -2.25 24.5,
+                          -40.9093 -0.525005 24.5,
+                          -42.25 -2.25 24.5,
+                          -41.05 2.04427e-14 24.5,
+                          -40 -1.05 24.5,
+                          -39.475 -0.909323 24.5,
+                          -42.25 -2.25 24.5,
+                          -40.525 -0.909323 24.5,
+                          -40 -1.05 24.5,
+                          -42.25 -2.25 24.5,
+                          -40.9093 -0.525005 24.5,
+                          -40.525 -0.909323 24.5,
+                          -42.25 -2.25 24.5,
+                          -37.6 2.25 24.5,
+                          -42.25 2.25 24.5,
+                          -37.6 2.25 29.5,
+                          -40.525 0.909323 24.5,
+                          -42.25 2.25 24.5,
+                          -37.6 2.25 24.5,
+                          -40.525 0.909323 24.5,
+                          -40.9093 0.525005 24.5,
+                          -42.25 2.25 24.5,
+                          -0.228666 -0.703784 29.8,
+                          -0.1 -2.25 29.8,
+                          -2.25 -2.25 29.8,
+                          0.228666 -0.703784 29.8,
+                          0.598674 -0.434958 29.8,
+                          -0.1 -2.25 29.8,
+                          0.856699 -2.0597 29.8,
+                          -0.1 -2.25 29.8,
+                          0.598674 -0.434958 29.8,
+                          -0.228666 -0.703784 29.8,
+                          0.228666 -0.703784 29.8,
+                          -0.1 -2.25 29.8,
+                          -2.25 2.25 29.8,
+                          -2.25 -2.25 29.8,
+                          -2.25 -2.25 24.2,
+                          -0.598674 0.434958 29.8,
+                          -2.25 -2.25 29.8,
+                          -2.25 2.25 29.8,
+                          -0.598674 -0.434958 29.8,
+                          -0.228666 -0.703784 29.8,
+                          -2.25 -2.25 29.8,
+                          -0.74 7.25725e-15 29.8,
+                          -0.598674 -0.434958 29.8,
+                          -2.25 -2.25 29.8,
+                          -0.598674 0.434958 29.8,
+                          -0.74 7.25725e-15 29.8,
+                          -2.25 -2.25 29.8,
+                          -2.25 2.25 24.2,
+                          -2.25 -2.25 24.2,
+                          -0.1 -2.25 24.2,
+                          -2.25 2.25 29.8,
+                          -2.25 -2.25 24.2,
+                          -2.25 2.25 24.2,
+                          -0.75 7.18106e-15 24.2,
+                          -2.25 2.25 24.2,
+                          -0.1 -2.25 24.2,
+                          -0.606764 -0.440835 24.2,
+                          -0.75 7.18106e-15 24.2,
+                          -0.1 -2.25 24.2,
+                          -0.231756 -0.713294 24.2,
+                          -0.606764 -0.440835 24.2,
+                          -0.1 -2.25 24.2,
+                          0.231756 -0.713294 24.2,
+                          -0.231756 -0.713294 24.2,
+                          -0.1 -2.25 24.2,
+                          0.856699 -2.0597 24.2,
+                          0.231756 -0.713294 24.2,
+                          -0.1 -2.25 24.2,
+                          -39.0907 -0.525005 24.5,
+                          -37.6 2.25 24.5,
+                          -37.6 -2.25 24.5,
+                          -39.475 -0.909323 24.5,
+                          -39.0907 -0.525005 24.5,
+                          -37.6 -2.25 24.5,
+                          -39.0907 0.525005 29.5,
+                          -37.6 -2.25 29.5,
+                          -37.6 2.25 29.5,
+                          -40 -1.05 29.5,
+                          -40.525 -0.909323 29.5,
+                          -37.6 -2.25 29.5,
+                          -39.475 -0.909323 29.5,
+                          -40 -1.05 29.5,
+                          -37.6 -2.25 29.5,
+                          -39.0907 -0.525005 29.5,
+                          -39.475 -0.909323 29.5,
+                          -37.6 -2.25 29.5,
+                          -38.95 2.01915e-14 29.5,
+                          -39.0907 -0.525005 29.5,
+                          -37.6 -2.25 29.5,
+                          -39.0907 0.525005 29.5,
+                          -38.95 2.01915e-14 29.5,
+                          -37.6 -2.25 29.5,
+                          2.2097 -0.706699 29.8,
+                          2.4 2.25 29.8,
+                          2.4 0.25 29.8,
+                          -0.228666 0.703784 29.8,
+                          -2.25 2.25 29.8,
+                          2.4 2.25 29.8,
+                          0.598674 0.434958 29.8,
+                          2.4 2.25 29.8,
+                          0.74 7.03132e-15 29.8,
+                          0.856699 -2.0597 29.8,
+                          0.74 7.03132e-15 29.8,
+                          2.4 2.25 29.8,
+                          0.228666 0.703784 29.8,
+                          -0.228666 0.703784 29.8,
+                          2.4 2.25 29.8,
+                          0.598674 0.434958 29.8,
+                          0.228666 0.703784 29.8,
+                          2.4 2.25 29.8,
+                          1.66777 -1.51777 29.8,
+                          0.856699 -2.0597 29.8,
+                          2.4 2.25 29.8,
+                          2.2097 -0.706699 29.8,
+                          1.66777 -1.51777 29.8,
+                          2.4 2.25 29.8,
+                          -2.25 2.25 24.2,
+                          2.4 0.25 24.2,
+                          2.4 2.25 24.2,
+                          0.231756 0.713294 24.2,
+                          2.4 0.25 24.2,
+                          -2.25 2.25 24.2,
+                          2.2097 -0.706699 24.2,
+                          2.4 0.25 24.2,
+                          0.231756 0.713294 24.2,
+                          -39.475 0.909323 29.5,
+                          -39.0907 0.525005 29.5,
+                          -37.6 2.25 29.5,
+                          -40 1.05 24.5,
+                          -40.525 0.909323 24.5,
+                          -37.6 2.25 24.5,
+                          -39.475 0.909323 24.5,
+                          -40 1.05 24.5,
+                          -37.6 2.25 24.5,
+                          -39.0907 0.525005 24.5,
+                          -39.475 0.909323 24.5,
+                          -37.6 2.25 24.5,
+                          -38.95 2.01221e-14 24.5,
+                          -39.0907 0.525005 24.5,
+                          -37.6 2.25 24.5,
+                          -39.0907 -0.525005 24.5,
+                          -38.95 2.01221e-14 24.5,
+                          -37.6 2.25 24.5,
+                          -0.606764 0.440835 24.2,
+                          -2.25 2.25 24.2,
+                          -0.75 7.18106e-15 24.2,
+                          -0.231756 0.713294 24.2,
+                          0.231756 0.713294 24.2,
+                          -2.25 2.25 24.2,
+                          -0.606764 0.440835 24.2,
+                          -0.231756 0.713294 24.2,
+                          -2.25 2.25 24.2,
+                          -0.228666 0.703784 29.8,
+                          -0.598674 0.434958 29.8,
+                          -2.25 2.25 29.8,
+                          0.856699 -2.0597 29.8,
+                          0.598674 -0.434958 29.8,
+                          0.74 7.03132e-15 29.8,
+                          0.856699 -2.0597 24.2,
+                          0.606764 -0.440835 24.2,
+                          0.231756 -0.713294 24.2,
+                          0.856699 -2.0597 24.2,
+                          0.75 6.95208e-15 24.2,
+                          0.606764 -0.440835 24.2,
+                          1.66777 -1.51777 24.2,
+                          0.606764 0.440835 24.2,
+                          0.75 6.95208e-15 24.2,
+                          0.856699 -2.0597 24.2,
+                          1.66777 -1.51777 24.2,
+                          0.75 6.95208e-15 24.2,
+                          2.2097 -0.706699 24.2,
+                          0.231756 0.713294 24.2,
+                          0.606764 0.440835 24.2,
+                          1.66777 -1.51777 24.2,
+                          2.2097 -0.706699 24.2,
+                          0.606764 0.440835 24.2,
+                          -41.05 2.04427e-14 24.5,
+                          -41.05 2.05121e-14 29.5,
+                          -40.9093 -0.525005 29.5,
+                          -40.9093 0.525005 24.5,
+                          -40.9093 0.525005 29.5,
+                          -41.05 2.05121e-14 29.5,
+                          -40.9093 0.525005 24.5,
+                          -41.05 2.05121e-14 29.5,
+                          -41.05 2.04427e-14 24.5,
+                          -40.9093 -0.525005 24.5,
+                          -40.9093 -0.525005 29.5,
+                          -40.525 -0.909323 29.5,
+                          -40.9093 -0.525005 24.5,
+                          -41.05 2.04427e-14 24.5,
+                          -40.9093 -0.525005 29.5,
+                          -40.525 -0.909323 24.5,
+                          -40.525 -0.909323 29.5,
+                          -40 -1.05 29.5,
+                          -40.9093 -0.525005 24.5,
+                          -40.525 -0.909323 29.5,
+                          -40.525 -0.909323 24.5,
+                          -40 -1.05 24.5,
+                          -40 -1.05 29.5,
+                          -39.475 -0.909323 29.5,
+                          -40.525 -0.909323 24.5,
+                          -40 -1.05 29.5,
+                          -40 -1.05 24.5,
+                          -39.475 -0.909323 24.5,
+                          -39.475 -0.909323 29.5,
+                          -39.0907 -0.525005 29.5,
+                          -40 -1.05 24.5,
+                          -39.475 -0.909323 29.5,
+                          -39.475 -0.909323 24.5,
+                          -39.0907 -0.525005 24.5,
+                          -39.0907 -0.525005 29.5,
+                          -38.95 2.01915e-14 29.5,
+                          -39.475 -0.909323 24.5,
+                          -39.0907 -0.525005 29.5,
+                          -39.0907 -0.525005 24.5,
+                          -38.95 2.01221e-14 24.5,
+                          -38.95 2.01915e-14 29.5,
+                          -39.0907 0.525005 29.5,
+                          -39.0907 -0.525005 24.5,
+                          -38.95 2.01915e-14 29.5,
+                          -38.95 2.01221e-14 24.5,
+                          -39.0907 0.525005 24.5,
+                          -39.0907 0.525005 29.5,
+                          -39.475 0.909323 29.5,
+                          -38.95 2.01221e-14 24.5,
+                          -39.0907 0.525005 29.5,
+                          -39.0907 0.525005 24.5,
+                          -39.475 0.909323 24.5,
+                          -39.475 0.909323 29.5,
+                          -40 1.05 29.5,
+                          -39.0907 0.525005 24.5,
+                          -39.475 0.909323 29.5,
+                          -39.475 0.909323 24.5,
+                          -40 1.05 24.5,
+                          -40 1.05 29.5,
+                          -40.525 0.909323 29.5,
+                          -39.475 0.909323 24.5,
+                          -40 1.05 29.5,
+                          -40 1.05 24.5,
+                          -40.525 0.909323 24.5,
+                          -40.525 0.909323 29.5,
+                          -40.9093 0.525005 29.5,
+                          -40 1.05 24.5,
+                          -40.525 0.909323 29.5,
+                          -40.525 0.909323 24.5,
+                          -40.525 0.909323 24.5,
+                          -40.9093 0.525005 29.5,
+                          -40.9093 0.525005 24.5 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          -1 -5.55112e-17 5.00498e-17,
+                          -1 -5.55112e-17 5.00498e-17,
+                          -1 -5.55112e-17 5.00498e-17,
+                          5.55112e-17 -1 -2.73641e-17,
+                          5.55112e-17 -1 -2.73641e-17,
+                          5.55112e-17 -1 -2.73641e-17,
+                          5.55112e-17 -1 -2.73641e-17,
+                          5.55112e-17 -1 -2.73641e-17,
+                          5.55112e-17 -1 -2.73641e-17,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          -5.55112e-17 1 2.73641e-17,
+                          -5.55112e-17 1 2.73641e-17,
+                          -5.55112e-17 1 2.73641e-17,
+                          -1 -5.55112e-17 5.00498e-17,
+                          -1 -5.55112e-17 5.00498e-17,
+                          -1 -5.55112e-17 5.00498e-17,
+                          0.707107 -4.78442e-17 0.707107,
+                          0.707107 -4.78442e-17 0.707107,
+                          0.707107 -4.78442e-17 0.707107,
+                          -5.55112e-17 1 2.73641e-17,
+                          -5.55112e-17 1 2.73641e-17,
+                          -5.55112e-17 1 2.73641e-17,
+                          -5.55112e-17 1 2.73641e-17,
+                          -5.55112e-17 1 2.73641e-17,
+                          -5.55112e-17 1 2.73641e-17,
+                          -5.55112e-17 1 2.73641e-17,
+                          -5.55112e-17 1 2.73641e-17,
+                          -5.55112e-17 1 2.73641e-17,
+                          -5.55112e-17 1 2.73641e-17,
+                          -5.55112e-17 1 2.73641e-17,
+                          -5.55112e-17 1 2.73641e-17,
+                          5.55112e-17 -1 -2.73641e-17,
+                          5.55112e-17 -1 -2.73641e-17,
+                          5.55112e-17 -1 -2.73641e-17,
+                          0.707107 -4.78442e-17 0.707107,
+                          0.707107 -4.78442e-17 0.707107,
+                          0.707107 -4.78442e-17 0.707107,
+                          5.55112e-17 -1 -2.73641e-17,
+                          5.55112e-17 -1 -2.73641e-17,
+                          5.55112e-17 -1 -2.73641e-17,
+                          -1 -5.55112e-17 5.00498e-17,
+                          -1 -5.55112e-17 5.00498e-17,
+                          -1 -5.55112e-17 5.00498e-17,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          -5.55112e-17 1 2.73641e-17,
+                          -5.55112e-17 1 2.73641e-17,
+                          -5.55112e-17 1 2.73641e-17,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          -1 -5.55112e-17 5.00498e-17,
+                          -1 -5.55112e-17 5.00498e-17,
+                          -1 -5.55112e-17 5.00498e-17,
+                          5.55112e-17 -1 -2.73641e-17,
+                          5.55112e-17 -1 -2.73641e-17,
+                          5.55112e-17 -1 -2.73641e-17,
+                          5.55112e-17 -1 -2.73641e-17,
+                          5.55112e-17 -1 -2.73641e-17,
+                          5.55112e-17 -1 -2.73641e-17,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -5.55112e-17 1 2.73641e-17,
+                          -5.55112e-17 1 2.73641e-17,
+                          -5.55112e-17 1 2.73641e-17,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          1 5.55112e-17 -5.00498e-17,
+                          1 5.55112e-17 -5.00498e-17,
+                          1 5.55112e-17 -5.00498e-17,
+                          1 5.55112e-17 -5.00498e-17,
+                          1 5.55112e-17 -5.00498e-17,
+                          1 5.55112e-17 -5.00498e-17,
+                          0.707107 1.26349e-16 -0.707107,
+                          0.707107 1.26349e-16 -0.707107,
+                          0.707107 1.26349e-16 -0.707107,
+                          0.707107 1.26349e-16 -0.707107,
+                          0.707107 1.26349e-16 -0.707107,
+                          0.707107 1.26349e-16 -0.707107,
+                          5.55112e-17 -1 -2.73641e-17,
+                          5.55112e-17 -1 -2.73641e-17,
+                          5.55112e-17 -1 -2.73641e-17,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          5.55112e-17 -1 -2.73641e-17,
+                          5.55112e-17 -1 -2.73641e-17,
+                          5.55112e-17 -1 -2.73641e-17,
+                          -1 -5.55112e-17 5.00498e-17,
+                          -1 -5.55112e-17 5.00498e-17,
+                          -1 -5.55112e-17 5.00498e-17,
+                          -1 -5.55112e-17 5.00498e-17,
+                          -1 -5.55112e-17 5.00498e-17,
+                          -1 -5.55112e-17 5.00498e-17,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          2.59373e-16 -1.23173e-16 1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -2.59373e-16 1.23173e-16 -1,
+                          -5.55112e-17 1 2.73641e-17,
+                          -5.55112e-17 1 2.73641e-17,
+                          -5.55112e-17 1 2.73641e-17,
+                          1 3.00441e-16 -5.00498e-17,
+                          1 3.00441e-16 -5.00498e-17,
+                          0.866025 0.5 -2.96623e-17,
+                          0.866025 -0.5 -5.70264e-17,
+                          0.866025 -0.5 -5.70264e-17,
+                          1 5.55112e-17 -5.00498e-17,
+                          0.866025 -0.5 -5.70264e-17,
+                          1 5.55112e-17 -5.00498e-17,
+                          1 5.55112e-17 -5.00498e-17,
+                          0.866025 0.5 -2.96623e-17,
+                          0.866025 0.5 -2.96623e-17,
+                          0.5 0.866025 -1.32687e-18,
+                          0.866025 0.5 -2.96623e-17,
+                          1 3.00441e-16 -5.00498e-17,
+                          0.866025 0.5 -2.96623e-17,
+                          0.5 0.866025 -1.32687e-18,
+                          0.5 0.866025 -1.32687e-18,
+                          -2.01557e-15 1 2.73641e-17,
+                          0.866025 0.5 -2.96623e-17,
+                          0.5 0.866025 -1.32687e-18,
+                          0.5 0.866025 -1.32687e-18,
+                          -2.01557e-15 1 2.73641e-17,
+                          -2.01557e-15 1 2.73641e-17,
+                          -0.5 0.866025 4.87229e-17,
+                          0.5 0.866025 -1.32687e-18,
+                          -2.01557e-15 1 2.73641e-17,
+                          -2.01557e-15 1 2.73641e-17,
+                          -0.5 0.866025 4.87229e-17,
+                          -0.5 0.866025 4.87229e-17,
+                          -0.866025 0.5 5.70264e-17,
+                          -2.01557e-15 1 2.73641e-17,
+                          -0.5 0.866025 4.87229e-17,
+                          -0.5 0.866025 4.87229e-17,
+                          -0.866025 0.5 5.70264e-17,
+                          -0.866025 0.5 5.70264e-17,
+                          -1 -1.77976e-16 5.00498e-17,
+                          -0.5 0.866025 4.87229e-17,
+                          -0.866025 0.5 5.70264e-17,
+                          -0.866025 0.5 5.70264e-17,
+                          -1 -1.77976e-16 5.00498e-17,
+                          -1 -1.77976e-16 5.00498e-17,
+                          -0.866025 -0.5 2.96623e-17,
+                          -0.866025 0.5 5.70264e-17,
+                          -1 -1.77976e-16 5.00498e-17,
+                          -1 -1.77976e-16 5.00498e-17,
+                          -0.866025 -0.5 2.96623e-17,
+                          -0.866025 -0.5 2.96623e-17,
+                          -0.5 -0.866025 1.32687e-18,
+                          -1 -1.77976e-16 5.00498e-17,
+                          -0.866025 -0.5 2.96623e-17,
+                          -0.866025 -0.5 2.96623e-17,
+                          -0.5 -0.866025 1.32687e-18,
+                          -0.5 -0.866025 1.32687e-18,
+                          1.8931e-15 -1 -2.73641e-17,
+                          -0.866025 -0.5 2.96623e-17,
+                          -0.5 -0.866025 1.32687e-18,
+                          -0.5 -0.866025 1.32687e-18,
+                          1.67106e-15 -1 -2.73641e-17,
+                          1.8931e-15 -1 -2.73641e-17,
+                          0.5 -0.866025 -4.87229e-17,
+                          -0.5 -0.866025 1.32687e-18,
+                          1.8931e-15 -1 -2.73641e-17,
+                          1.67106e-15 -1 -2.73641e-17,
+                          0.5 -0.866025 -4.87229e-17,
+                          0.5 -0.866025 -4.87229e-17,
+                          0.866025 -0.5 -5.70264e-17,
+                          1.67106e-15 -1 -2.73641e-17,
+                          0.5 -0.866025 -4.87229e-17,
+                          0.5 -0.866025 -4.87229e-17,
+                          0.5 -0.866025 -4.87229e-17,
+                          0.866025 -0.5 -5.70264e-17,
+                          0.866025 -0.5 -5.70264e-17 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -6.8 -2.25 56,
+                          -37.8 2.25 56,
+                          -37.8 -2.25 56,
+                          -37.8 -2.25 53.3,
+                          -37.8 -2.25 56,
+                          -37.8 2.25 56,
+                          -6.8 -2.25 46,
+                          -6.8 -2.25 56,
+                          -37.8 -2.25 56,
+                          -37.8 -2.25 53.3,
+                          -6.8 -2.25 46,
+                          -37.8 -2.25 56,
+                          -6.8 -2.25 56,
+                          -6.8 2.25 56,
+                          -37.8 2.25 56,
+                          -37.8 2.25 53.3,
+                          -37.8 2.25 56,
+                          -6.8 2.25 56,
+                          -37.8 2.25 53.3,
+                          -37.8 -2.25 53.3,
+                          -37.8 2.25 56,
+                          -3.8 2.25 53,
+                          -6.8 2.25 56,
+                          -6.8 -2.25 56,
+                          -37.8 2.25 48.7,
+                          -37.8 2.25 53.3,
+                          -6.8 2.25 56,
+                          -37.8 2.25 46,
+                          -37.8 2.25 48.7,
+                          -6.8 2.25 56,
+                          -6.8 2.25 46,
+                          -37.8 2.25 46,
+                          -6.8 2.25 56,
+                          -3.8 2.25 53,
+                          -6.8 2.25 46,
+                          -6.8 2.25 56,
+                          -3.8 -2.25 49,
+                          -3.8 -2.25 53,
+                          -6.8 -2.25 56,
+                          -3.8 2.25 53,
+                          -6.8 -2.25 56,
+                          -3.8 -2.25 53,
+                          -6.8 -2.25 46,
+                          -3.8 -2.25 49,
+                          -6.8 -2.25 56,
+                          -42.45 2.25 48.7,
+                          -42.45 -2.25 53.3,
+                          -42.45 2.25 53.3,
+                          -41.2825 -0.625 53.3,
+                          -42.45 2.25 53.3,
+                          -42.45 -2.25 53.3,
+                          -37.8 2.25 53.3,
+                          -42.45 2.25 48.7,
+                          -42.45 2.25 53.3,
+                          -39.575 1.08253 53.3,
+                          -37.8 2.25 53.3,
+                          -42.45 2.25 53.3,
+                          -41.2825 -0.625 53.3,
+                          -41.45 3.55271e-14 53.3,
+                          -42.45 2.25 53.3,
+                          -41.2825 0.625 53.3,
+                          -42.45 2.25 53.3,
+                          -41.45 3.55271e-14 53.3,
+                          -40.2 1.25 53.3,
+                          -39.575 1.08253 53.3,
+                          -42.45 2.25 53.3,
+                          -40.825 1.08253 53.3,
+                          -40.2 1.25 53.3,
+                          -42.45 2.25 53.3,
+                          -41.2825 0.625 53.3,
+                          -40.825 1.08253 53.3,
+                          -42.45 2.25 53.3,
+                          -42.45 2.25 48.7,
+                          -42.45 -2.25 48.7,
+                          -42.45 -2.25 53.3,
+                          -37.8 -2.25 48.7,
+                          -42.45 -2.25 53.3,
+                          -42.45 -2.25 48.7,
+                          -37.8 -2.25 53.3,
+                          -42.45 -2.25 53.3,
+                          -37.8 -2.25 48.7,
+                          -40.825 -1.08253 53.3,
+                          -42.45 -2.25 53.3,
+                          -37.8 -2.25 53.3,
+                          -40.825 -1.08253 53.3,
+                          -41.2825 -0.625 53.3,
+                          -42.45 -2.25 53.3,
+                          -41.2825 0.625 48.7,
+                          -42.45 -2.25 48.7,
+                          -42.45 2.25 48.7,
+                          -39.575 -1.08253 48.7,
+                          -37.8 -2.25 48.7,
+                          -42.45 -2.25 48.7,
+                          -41.2825 0.625 48.7,
+                          -41.45 3.55271e-14 48.7,
+                          -42.45 -2.25 48.7,
+                          -41.2825 -0.625 48.7,
+                          -42.45 -2.25 48.7,
+                          -41.45 3.55271e-14 48.7,
+                          -40.2 -1.25 48.7,
+                          -39.575 -1.08253 48.7,
+                          -42.45 -2.25 48.7,
+                          -40.825 -1.08253 48.7,
+                          -40.2 -1.25 48.7,
+                          -42.45 -2.25 48.7,
+                          -41.2825 -0.625 48.7,
+                          -40.825 -1.08253 48.7,
+                          -42.45 -2.25 48.7,
+                          -37.8 2.25 48.7,
+                          -42.45 2.25 48.7,
+                          -37.8 2.25 53.3,
+                          -40.825 1.08253 48.7,
+                          -42.45 2.25 48.7,
+                          -37.8 2.25 48.7,
+                          -40.825 1.08253 48.7,
+                          -41.2825 0.625 48.7,
+                          -42.45 2.25 48.7,
+                          -3.8 2.25 49,
+                          -3.8 -2.25 53,
+                          -3.8 -2.25 49,
+                          -3.8 2.25 53,
+                          -3.8 -2.25 53,
+                          -3.8 2.25 49,
+                          -6.8 2.25 46,
+                          -3.8 -2.25 49,
+                          -6.8 -2.25 46,
+                          -3.8 2.25 49,
+                          -3.8 -2.25 49,
+                          -6.8 2.25 46,
+                          -37.8 -2.25 48.7,
+                          -37.8 -2.25 46,
+                          -6.8 -2.25 46,
+                          -6.8 2.25 46,
+                          -6.8 -2.25 46,
+                          -37.8 -2.25 46,
+                          -37.8 -2.25 53.3,
+                          -37.8 -2.25 48.7,
+                          -6.8 -2.25 46,
+                          -37.8 2.25 48.7,
+                          -37.8 -2.25 46,
+                          -37.8 -2.25 48.7,
+                          -37.8 2.25 46,
+                          -37.8 -2.25 46,
+                          -37.8 2.25 48.7,
+                          -6.8 2.25 46,
+                          -37.8 -2.25 46,
+                          -37.8 2.25 46,
+                          -39.1175 -0.625 48.7,
+                          -37.8 2.25 48.7,
+                          -37.8 -2.25 48.7,
+                          -39.575 -1.08253 48.7,
+                          -39.1175 -0.625 48.7,
+                          -37.8 -2.25 48.7,
+                          -39.1175 0.625 53.3,
+                          -37.8 -2.25 53.3,
+                          -37.8 2.25 53.3,
+                          -40.2 -1.25 53.3,
+                          -40.825 -1.08253 53.3,
+                          -37.8 -2.25 53.3,
+                          -39.575 -1.08253 53.3,
+                          -40.2 -1.25 53.3,
+                          -37.8 -2.25 53.3,
+                          -39.1175 -0.625 53.3,
+                          -39.575 -1.08253 53.3,
+                          -37.8 -2.25 53.3,
+                          -38.95 3.55271e-14 53.3,
+                          -39.1175 -0.625 53.3,
+                          -37.8 -2.25 53.3,
+                          -39.1175 0.625 53.3,
+                          -38.95 3.55271e-14 53.3,
+                          -37.8 -2.25 53.3,
+                          -39.575 1.08253 53.3,
+                          -39.1175 0.625 53.3,
+                          -37.8 2.25 53.3,
+                          -40.2 1.25 48.7,
+                          -40.825 1.08253 48.7,
+                          -37.8 2.25 48.7,
+                          -39.575 1.08253 48.7,
+                          -40.2 1.25 48.7,
+                          -37.8 2.25 48.7,
+                          -39.1175 0.625 48.7,
+                          -39.575 1.08253 48.7,
+                          -37.8 2.25 48.7,
+                          -38.95 3.55271e-14 48.7,
+                          -39.1175 0.625 48.7,
+                          -37.8 2.25 48.7,
+                          -39.1175 -0.625 48.7,
+                          -38.95 3.55271e-14 48.7,
+                          -37.8 2.25 48.7,
+                          -3.8 2.25 53,
+                          -3.8 2.25 49,
+                          -6.8 2.25 46,
+                          -41.45 3.55271e-14 48.7,
+                          -41.45 3.55271e-14 53.3,
+                          -41.2825 -0.625 53.3,
+                          -41.2825 0.625 48.7,
+                          -41.2825 0.625 53.3,
+                          -41.45 3.55271e-14 53.3,
+                          -41.2825 0.625 48.7,
+                          -41.45 3.55271e-14 53.3,
+                          -41.45 3.55271e-14 48.7,
+                          -41.2825 -0.625 48.7,
+                          -41.2825 -0.625 53.3,
+                          -40.825 -1.08253 53.3,
+                          -41.2825 -0.625 48.7,
+                          -41.45 3.55271e-14 48.7,
+                          -41.2825 -0.625 53.3,
+                          -40.825 -1.08253 48.7,
+                          -40.825 -1.08253 53.3,
+                          -40.2 -1.25 53.3,
+                          -41.2825 -0.625 48.7,
+                          -40.825 -1.08253 53.3,
+                          -40.825 -1.08253 48.7,
+                          -40.2 -1.25 48.7,
+                          -40.2 -1.25 53.3,
+                          -39.575 -1.08253 53.3,
+                          -40.825 -1.08253 48.7,
+                          -40.2 -1.25 53.3,
+                          -40.2 -1.25 48.7,
+                          -39.575 -1.08253 48.7,
+                          -39.575 -1.08253 53.3,
+                          -39.1175 -0.625 53.3,
+                          -40.2 -1.25 48.7,
+                          -39.575 -1.08253 53.3,
+                          -39.575 -1.08253 48.7,
+                          -39.1175 -0.625 48.7,
+                          -39.1175 -0.625 53.3,
+                          -38.95 3.55271e-14 53.3,
+                          -39.575 -1.08253 48.7,
+                          -39.1175 -0.625 53.3,
+                          -39.1175 -0.625 48.7,
+                          -38.95 3.55271e-14 48.7,
+                          -38.95 3.55271e-14 53.3,
+                          -39.1175 0.625 53.3,
+                          -39.1175 -0.625 48.7,
+                          -38.95 3.55271e-14 53.3,
+                          -38.95 3.55271e-14 48.7,
+                          -39.1175 0.625 48.7,
+                          -39.1175 0.625 53.3,
+                          -39.575 1.08253 53.3,
+                          -38.95 3.55271e-14 48.7,
+                          -39.1175 0.625 53.3,
+                          -39.1175 0.625 48.7,
+                          -39.575 1.08253 48.7,
+                          -39.575 1.08253 53.3,
+                          -40.2 1.25 53.3,
+                          -39.1175 0.625 48.7,
+                          -39.575 1.08253 53.3,
+                          -39.575 1.08253 48.7,
+                          -40.2 1.25 48.7,
+                          -40.2 1.25 53.3,
+                          -40.825 1.08253 53.3,
+                          -39.575 1.08253 48.7,
+                          -40.2 1.25 53.3,
+                          -40.2 1.25 48.7,
+                          -40.825 1.08253 48.7,
+                          -40.825 1.08253 53.3,
+                          -41.2825 0.625 53.3,
+                          -40.2 1.25 48.7,
+                          -40.825 1.08253 53.3,
+                          -40.825 1.08253 48.7,
+                          -40.825 1.08253 48.7,
+                          -41.2825 0.625 53.3,
+                          -41.2825 0.625 48.7 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          -1 2.22045e-16 -2.64835e-16,
+                          -1 2.22045e-16 -2.64835e-16,
+                          -1 2.22045e-16 -2.64835e-16,
+                          1.11022e-16 -1 9.5809e-17,
+                          1.11022e-16 -1 9.5809e-17,
+                          1.11022e-16 -1 9.5809e-17,
+                          1.11022e-16 -1 9.5809e-17,
+                          1.11022e-16 -1 9.5809e-17,
+                          1.11022e-16 -1 9.5809e-17,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          -1.11022e-16 1 -9.5809e-17,
+                          -1.11022e-16 1 -9.5809e-17,
+                          -1.11022e-16 1 -9.5809e-17,
+                          -1 2.22045e-16 -2.64835e-16,
+                          -1 2.22045e-16 -2.64835e-16,
+                          -1 2.22045e-16 -2.64835e-16,
+                          0.707107 -3.03261e-16 0.707107,
+                          0.707107 -3.03261e-16 0.707107,
+                          0.707107 -3.03261e-16 0.707107,
+                          -1.11022e-16 1 -9.5809e-17,
+                          -1.11022e-16 1 -9.5809e-17,
+                          -1.11022e-16 1 -9.5809e-17,
+                          -1.11022e-16 1 -9.5809e-17,
+                          -1.11022e-16 1 -9.5809e-17,
+                          -1.11022e-16 1 -9.5809e-17,
+                          -1.11022e-16 1 -9.5809e-17,
+                          -1.11022e-16 1 -9.5809e-17,
+                          -1.11022e-16 1 -9.5809e-17,
+                          -1.11022e-16 1 -9.5809e-17,
+                          -1.11022e-16 1 -9.5809e-17,
+                          -1.11022e-16 1 -9.5809e-17,
+                          1.11022e-16 -1 9.5809e-17,
+                          1.11022e-16 -1 9.5809e-17,
+                          1.11022e-16 -1 9.5809e-17,
+                          0.707107 -3.03261e-16 0.707107,
+                          0.707107 -3.03261e-16 0.707107,
+                          0.707107 -3.03261e-16 0.707107,
+                          1.11022e-16 -1 9.5809e-17,
+                          1.11022e-16 -1 9.5809e-17,
+                          1.11022e-16 -1 9.5809e-17,
+                          -1 2.22045e-16 -2.64835e-16,
+                          -1 2.22045e-16 -2.64835e-16,
+                          -1 2.22045e-16 -2.64835e-16,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          -1.11022e-16 1 -9.5809e-17,
+                          -1.11022e-16 1 -9.5809e-17,
+                          -1.11022e-16 1 -9.5809e-17,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          -1 2.22045e-16 -2.64835e-16,
+                          -1 2.22045e-16 -2.64835e-16,
+                          -1 2.22045e-16 -2.64835e-16,
+                          1.11022e-16 -1 9.5809e-17,
+                          1.11022e-16 -1 9.5809e-17,
+                          1.11022e-16 -1 9.5809e-17,
+                          1.11022e-16 -1 9.5809e-17,
+                          1.11022e-16 -1 9.5809e-17,
+                          1.11022e-16 -1 9.5809e-17,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -1.11022e-16 1 -9.5809e-17,
+                          -1.11022e-16 1 -9.5809e-17,
+                          -1.11022e-16 1 -9.5809e-17,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          1 -2.22045e-16 2.64835e-16,
+                          1 -2.22045e-16 2.64835e-16,
+                          1 -2.22045e-16 2.64835e-16,
+                          1 -2.22045e-16 2.64835e-16,
+                          1 -2.22045e-16 2.64835e-16,
+                          1 -2.22045e-16 2.64835e-16,
+                          0.707107 -1.07574e-17 -0.707107,
+                          0.707107 -1.07574e-17 -0.707107,
+                          0.707107 -1.07574e-17 -0.707107,
+                          0.707107 -1.07574e-17 -0.707107,
+                          0.707107 -1.07574e-17 -0.707107,
+                          0.707107 -1.07574e-17 -0.707107,
+                          1.11022e-16 -1 9.5809e-17,
+                          1.11022e-16 -1 9.5809e-17,
+                          1.11022e-16 -1 9.5809e-17,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          1.11022e-16 -1 9.5809e-17,
+                          1.11022e-16 -1 9.5809e-17,
+                          1.11022e-16 -1 9.5809e-17,
+                          -1 2.22045e-16 -2.64835e-16,
+                          -1 2.22045e-16 -2.64835e-16,
+                          -1 2.22045e-16 -2.64835e-16,
+                          -1 2.22045e-16 -2.64835e-16,
+                          -1 2.22045e-16 -2.64835e-16,
+                          -1 2.22045e-16 -2.64835e-16,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          3.20346e-16 -2.06831e-16 1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -3.20346e-16 2.06831e-16 -1,
+                          -1.11022e-16 1 -9.5809e-17,
+                          -1.11022e-16 1 -9.5809e-17,
+                          -1.11022e-16 1 -9.5809e-17,
+                          1 2.28848e-17 2.64835e-16,
+                          1 2.28848e-17 2.64835e-16,
+                          0.866025 0.5 1.81449e-16,
+                          0.866025 -0.5 2.77258e-16,
+                          0.866025 -0.5 2.77258e-16,
+                          1 -2.22045e-16 2.64835e-16,
+                          0.866025 -0.5 2.77258e-16,
+                          1 -2.22045e-16 2.64835e-16,
+                          1 -2.22045e-16 2.64835e-16,
+                          0.866025 0.5 1.81449e-16,
+                          0.866025 0.5 1.81449e-16,
+                          0.5 0.866025 4.94444e-17,
+                          0.866025 0.5 1.81449e-16,
+                          1 2.28848e-17 2.64835e-16,
+                          0.866025 0.5 1.81449e-16,
+                          0.5 0.866025 4.94444e-17,
+                          0.5 0.866025 4.94444e-17,
+                          -2.07108e-15 1 -9.5809e-17,
+                          0.866025 0.5 1.81449e-16,
+                          0.5 0.866025 4.94444e-17,
+                          0.5 0.866025 4.94444e-17,
+                          -2.07108e-15 1 -9.5809e-17,
+                          -2.07108e-15 1 -9.5809e-17,
+                          -0.5 0.866025 -2.1539e-16,
+                          0.5 0.866025 4.94444e-17,
+                          -2.07108e-15 1 -9.5809e-17,
+                          -2.07108e-15 1 -9.5809e-17,
+                          -0.5 0.866025 -2.1539e-16,
+                          -0.5 0.866025 -2.1539e-16,
+                          -0.866025 0.5 -2.77258e-16,
+                          -2.07108e-15 1 -9.5809e-17,
+                          -0.5 0.866025 -2.1539e-16,
+                          -0.5 0.866025 -2.1539e-16,
+                          -0.866025 0.5 -2.77258e-16,
+                          -0.866025 0.5 -2.77258e-16,
+                          -1 9.95799e-17 -2.64835e-16,
+                          -0.5 0.866025 -2.1539e-16,
+                          -0.866025 0.5 -2.77258e-16,
+                          -0.866025 0.5 -2.77258e-16,
+                          -1 9.95799e-17 -2.64835e-16,
+                          -1 9.95799e-17 -2.64835e-16,
+                          -0.866025 -0.5 -1.81449e-16,
+                          -0.866025 0.5 -2.77258e-16,
+                          -1 9.95799e-17 -2.64835e-16,
+                          -1 9.95799e-17 -2.64835e-16,
+                          -0.866025 -0.5 -1.81449e-16,
+                          -0.866025 -0.5 -1.81449e-16,
+                          -0.5 -0.866025 -4.94444e-17,
+                          -1 9.95799e-17 -2.64835e-16,
+                          -0.866025 -0.5 -1.81449e-16,
+                          -0.866025 -0.5 -1.81449e-16,
+                          -0.5 -0.866025 -4.94444e-17,
+                          -0.5 -0.866025 -4.94444e-17,
+                          1.94861e-15 -1 9.5809e-17,
+                          -0.866025 -0.5 -1.81449e-16,
+                          -0.5 -0.866025 -4.94444e-17,
+                          -0.5 -0.866025 -4.94444e-17,
+                          1.72657e-15 -1 9.5809e-17,
+                          1.94861e-15 -1 9.5809e-17,
+                          0.5 -0.866025 2.1539e-16,
+                          -0.5 -0.866025 -4.94444e-17,
+                          1.94861e-15 -1 9.5809e-17,
+                          1.72657e-15 -1 9.5809e-17,
+                          0.5 -0.866025 2.1539e-16,
+                          0.5 -0.866025 2.1539e-16,
+                          0.866025 -0.5 2.77258e-16,
+                          1.72657e-15 -1 9.5809e-17,
+                          0.5 -0.866025 2.1539e-16,
+                          0.5 -0.866025 2.1539e-16,
+                          0.5 -0.866025 2.1539e-16,
+                          0.866025 -0.5 2.77258e-16,
+                          0.866025 -0.5 2.77258e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -6.8 -2.25 78,
+                          -37.8 2.25 78,
+                          -37.8 -2.25 78,
+                          -37.8 -2.25 75.3,
+                          -37.8 -2.25 78,
+                          -37.8 2.25 78,
+                          -6.8 -2.25 68,
+                          -6.8 -2.25 78,
+                          -37.8 -2.25 78,
+                          -37.8 -2.25 75.3,
+                          -6.8 -2.25 68,
+                          -37.8 -2.25 78,
+                          -6.8 -2.25 78,
+                          -6.8 2.25 78,
+                          -37.8 2.25 78,
+                          -37.8 2.25 75.3,
+                          -37.8 2.25 78,
+                          -6.8 2.25 78,
+                          -37.8 2.25 75.3,
+                          -37.8 -2.25 75.3,
+                          -37.8 2.25 78,
+                          -3.8 2.25 75,
+                          -6.8 2.25 78,
+                          -6.8 -2.25 78,
+                          -37.8 2.25 70.7,
+                          -37.8 2.25 75.3,
+                          -6.8 2.25 78,
+                          -37.8 2.25 68,
+                          -37.8 2.25 70.7,
+                          -6.8 2.25 78,
+                          -6.8 2.25 68,
+                          -37.8 2.25 68,
+                          -6.8 2.25 78,
+                          -3.8 2.25 75,
+                          -6.8 2.25 68,
+                          -6.8 2.25 78,
+                          -3.8 -2.25 71,
+                          -3.8 -2.25 75,
+                          -6.8 -2.25 78,
+                          -3.8 2.25 75,
+                          -6.8 -2.25 78,
+                          -3.8 -2.25 75,
+                          -6.8 -2.25 68,
+                          -3.8 -2.25 71,
+                          -6.8 -2.25 78,
+                          -42.45 2.25 70.7,
+                          -42.45 -2.25 75.3,
+                          -42.45 2.25 75.3,
+                          -41.2825 -0.625 75.3,
+                          -42.45 2.25 75.3,
+                          -42.45 -2.25 75.3,
+                          -37.8 2.25 75.3,
+                          -42.45 2.25 70.7,
+                          -42.45 2.25 75.3,
+                          -39.575 1.08253 75.3,
+                          -37.8 2.25 75.3,
+                          -42.45 2.25 75.3,
+                          -41.2825 -0.625 75.3,
+                          -41.45 -7.16515e-15 75.3,
+                          -42.45 2.25 75.3,
+                          -41.2825 0.625 75.3,
+                          -42.45 2.25 75.3,
+                          -41.45 -7.16515e-15 75.3,
+                          -40.2 1.25 75.3,
+                          -39.575 1.08253 75.3,
+                          -42.45 2.25 75.3,
+                          -40.825 1.08253 75.3,
+                          -40.2 1.25 75.3,
+                          -42.45 2.25 75.3,
+                          -41.2825 0.625 75.3,
+                          -40.825 1.08253 75.3,
+                          -42.45 2.25 75.3,
+                          -42.45 2.25 70.7,
+                          -42.45 -2.25 70.7,
+                          -42.45 -2.25 75.3,
+                          -37.8 -2.25 70.7,
+                          -42.45 -2.25 75.3,
+                          -42.45 -2.25 70.7,
+                          -37.8 -2.25 75.3,
+                          -42.45 -2.25 75.3,
+                          -37.8 -2.25 70.7,
+                          -40.825 -1.08253 75.3,
+                          -42.45 -2.25 75.3,
+                          -37.8 -2.25 75.3,
+                          -40.825 -1.08253 75.3,
+                          -41.2825 -0.625 75.3,
+                          -42.45 -2.25 75.3,
+                          -41.2825 0.625 70.7,
+                          -42.45 -2.25 70.7,
+                          -42.45 2.25 70.7,
+                          -39.575 -1.08253 70.7,
+                          -37.8 -2.25 70.7,
+                          -42.45 -2.25 70.7,
+                          -41.2825 0.625 70.7,
+                          -41.45 -6.78032e-15 70.7,
+                          -42.45 -2.25 70.7,
+                          -41.2825 -0.625 70.7,
+                          -42.45 -2.25 70.7,
+                          -41.45 -6.78032e-15 70.7,
+                          -40.2 -1.25 70.7,
+                          -39.575 -1.08253 70.7,
+                          -42.45 -2.25 70.7,
+                          -40.825 -1.08253 70.7,
+                          -40.2 -1.25 70.7,
+                          -42.45 -2.25 70.7,
+                          -41.2825 -0.625 70.7,
+                          -40.825 -1.08253 70.7,
+                          -42.45 -2.25 70.7,
+                          -37.8 2.25 70.7,
+                          -42.45 2.25 70.7,
+                          -37.8 2.25 75.3,
+                          -40.825 1.08253 70.7,
+                          -42.45 2.25 70.7,
+                          -37.8 2.25 70.7,
+                          -40.825 1.08253 70.7,
+                          -41.2825 0.625 70.7,
+                          -42.45 2.25 70.7,
+                          -3.8 2.25 71,
+                          -3.8 -2.25 75,
+                          -3.8 -2.25 71,
+                          -3.8 2.25 75,
+                          -3.8 -2.25 75,
+                          -3.8 2.25 71,
+                          -6.8 2.25 68,
+                          -3.8 -2.25 71,
+                          -6.8 -2.25 68,
+                          -3.8 2.25 71,
+                          -3.8 -2.25 71,
+                          -6.8 2.25 68,
+                          -37.8 -2.25 70.7,
+                          -37.8 -2.25 68,
+                          -6.8 -2.25 68,
+                          -6.8 2.25 68,
+                          -6.8 -2.25 68,
+                          -37.8 -2.25 68,
+                          -37.8 -2.25 75.3,
+                          -37.8 -2.25 70.7,
+                          -6.8 -2.25 68,
+                          -37.8 2.25 70.7,
+                          -37.8 -2.25 68,
+                          -37.8 -2.25 70.7,
+                          -37.8 2.25 68,
+                          -37.8 -2.25 68,
+                          -37.8 2.25 70.7,
+                          -6.8 2.25 68,
+                          -37.8 -2.25 68,
+                          -37.8 2.25 68,
+                          -39.1175 -0.625 70.7,
+                          -37.8 2.25 70.7,
+                          -37.8 -2.25 70.7,
+                          -39.575 -1.08253 70.7,
+                          -39.1175 -0.625 70.7,
+                          -37.8 -2.25 70.7,
+                          -39.1175 0.625 75.3,
+                          -37.8 -2.25 75.3,
+                          -37.8 2.25 75.3,
+                          -40.2 -1.25 75.3,
+                          -40.825 -1.08253 75.3,
+                          -37.8 -2.25 75.3,
+                          -39.575 -1.08253 75.3,
+                          -40.2 -1.25 75.3,
+                          -37.8 -2.25 75.3,
+                          -39.1175 -0.625 75.3,
+                          -39.575 -1.08253 75.3,
+                          -37.8 -2.25 75.3,
+                          -38.95 -7.85904e-15 75.3,
+                          -39.1175 -0.625 75.3,
+                          -37.8 -2.25 75.3,
+                          -39.1175 0.625 75.3,
+                          -38.95 -7.85904e-15 75.3,
+                          -37.8 -2.25 75.3,
+                          -39.575 1.08253 75.3,
+                          -39.1175 0.625 75.3,
+                          -37.8 2.25 75.3,
+                          -40.2 1.25 70.7,
+                          -40.825 1.08253 70.7,
+                          -37.8 2.25 70.7,
+                          -39.575 1.08253 70.7,
+                          -40.2 1.25 70.7,
+                          -37.8 2.25 70.7,
+                          -39.1175 0.625 70.7,
+                          -39.575 1.08253 70.7,
+                          -37.8 2.25 70.7,
+                          -38.95 -7.47421e-15 70.7,
+                          -39.1175 0.625 70.7,
+                          -37.8 2.25 70.7,
+                          -39.1175 -0.625 70.7,
+                          -38.95 -7.47421e-15 70.7,
+                          -37.8 2.25 70.7,
+                          -3.8 2.25 75,
+                          -3.8 2.25 71,
+                          -6.8 2.25 68,
+                          -41.45 -6.78032e-15 70.7,
+                          -41.45 -7.16515e-15 75.3,
+                          -41.2825 -0.625 75.3,
+                          -41.2825 0.625 70.7,
+                          -41.2825 0.625 75.3,
+                          -41.45 -7.16515e-15 75.3,
+                          -41.2825 0.625 70.7,
+                          -41.45 -7.16515e-15 75.3,
+                          -41.45 -6.78032e-15 70.7,
+                          -41.2825 -0.625 70.7,
+                          -41.2825 -0.625 75.3,
+                          -40.825 -1.08253 75.3,
+                          -41.2825 -0.625 70.7,
+                          -41.45 -6.78032e-15 70.7,
+                          -41.2825 -0.625 75.3,
+                          -40.825 -1.08253 70.7,
+                          -40.825 -1.08253 75.3,
+                          -40.2 -1.25 75.3,
+                          -41.2825 -0.625 70.7,
+                          -40.825 -1.08253 75.3,
+                          -40.825 -1.08253 70.7,
+                          -40.2 -1.25 70.7,
+                          -40.2 -1.25 75.3,
+                          -39.575 -1.08253 75.3,
+                          -40.825 -1.08253 70.7,
+                          -40.2 -1.25 75.3,
+                          -40.2 -1.25 70.7,
+                          -39.575 -1.08253 70.7,
+                          -39.575 -1.08253 75.3,
+                          -39.1175 -0.625 75.3,
+                          -40.2 -1.25 70.7,
+                          -39.575 -1.08253 75.3,
+                          -39.575 -1.08253 70.7,
+                          -39.1175 -0.625 70.7,
+                          -39.1175 -0.625 75.3,
+                          -38.95 -7.85904e-15 75.3,
+                          -39.575 -1.08253 70.7,
+                          -39.1175 -0.625 75.3,
+                          -39.1175 -0.625 70.7,
+                          -38.95 -7.47421e-15 70.7,
+                          -38.95 -7.85904e-15 75.3,
+                          -39.1175 0.625 75.3,
+                          -39.1175 -0.625 70.7,
+                          -38.95 -7.85904e-15 75.3,
+                          -38.95 -7.47421e-15 70.7,
+                          -39.1175 0.625 70.7,
+                          -39.1175 0.625 75.3,
+                          -39.575 1.08253 75.3,
+                          -38.95 -7.47421e-15 70.7,
+                          -39.1175 0.625 75.3,
+                          -39.1175 0.625 70.7,
+                          -39.575 1.08253 70.7,
+                          -39.575 1.08253 75.3,
+                          -40.2 1.25 75.3,
+                          -39.1175 0.625 70.7,
+                          -39.575 1.08253 75.3,
+                          -39.575 1.08253 70.7,
+                          -40.2 1.25 70.7,
+                          -40.2 1.25 75.3,
+                          -40.825 1.08253 75.3,
+                          -39.575 1.08253 70.7,
+                          -40.2 1.25 75.3,
+                          -40.2 1.25 70.7,
+                          -40.825 1.08253 70.7,
+                          -40.825 1.08253 75.3,
+                          -41.2825 0.625 75.3,
+                          -40.2 1.25 70.7,
+                          -40.825 1.08253 75.3,
+                          -40.825 1.08253 70.7,
+                          -40.825 1.08253 70.7,
+                          -41.2825 0.625 75.3,
+                          -41.2825 0.625 70.7 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.25 0.25 0.25
+    }
+    Separator {
+        Normal {
+            vector      [ -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -8.939e-16 2.94903e-17 1,
+                          -5.72119e-18 2.94903e-17 1,
+                          -0.309017 7.25398e-17 0.951057,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          5.55112e-17 2.94903e-17 1,
+                          5.55112e-17 2.94903e-17 1,
+                          5.55112e-17 2.94903e-17 1,
+                          5.55112e-17 2.94903e-17 1,
+                          5.55112e-17 2.94903e-17 1,
+                          5.55112e-17 2.94903e-17 1,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -0.309017 7.25398e-17 0.951057,
+                          -0.309017 7.25398e-17 0.951057,
+                          -0.587785 1.08489e-16 0.809017,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -8.939e-16 2.94903e-17 1,
+                          -0.309017 7.25398e-17 0.951057,
+                          -0.309017 7.25398e-17 0.951057,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -0.587785 1.08489e-16 0.809017,
+                          -0.587785 1.08489e-16 0.809017,
+                          -0.809017 1.33818e-16 0.587785,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -0.309017 7.25398e-17 0.951057,
+                          -0.587785 1.08489e-16 0.809017,
+                          -0.587785 1.08489e-16 0.809017,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -0.809017 1.33818e-16 0.587785,
+                          -0.809017 1.33818e-16 0.587785,
+                          -0.951057 1.46048e-16 0.309017,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -0.587785 1.08489e-16 0.809017,
+                          -0.809017 1.33818e-16 0.587785,
+                          -0.809017 1.33818e-16 0.587785,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -0.951057 1.46048e-16 0.309017,
+                          -0.951057 1.46048e-16 0.309017,
+                          -1 1.43982e-16 5.55112e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -0.809017 1.33818e-16 0.587785,
+                          -0.951057 1.46048e-16 0.309017,
+                          -0.951057 1.46048e-16 0.309017,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1 1.43982e-16 5.55112e-17,
+                          -1 1.43982e-16 5.55112e-17,
+                          -1 1.43982e-16 5.55112e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -0.951057 1.46048e-16 0.309017,
+                          -1 1.43982e-16 5.55112e-17,
+                          -1 1.43982e-16 5.55112e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1 1.43982e-16 5.55112e-17,
+                          -1 1.43982e-16 5.55112e-17,
+                          -0.951057 1.27822e-16 -0.309017,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1 1.43982e-16 5.55112e-17,
+                          -1 1.43982e-16 5.55112e-17,
+                          -1 1.43982e-16 5.55112e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -0.951057 1.27822e-16 -0.309017,
+                          -0.951057 1.27822e-16 -0.309017,
+                          -0.809017 9.915e-17 -0.587785,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1 1.43982e-16 5.55112e-17,
+                          -0.951057 1.27822e-16 -0.309017,
+                          -0.951057 1.27822e-16 -0.309017,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -0.809017 9.915e-17 -0.587785,
+                          -0.809017 9.915e-17 -0.587785,
+                          -0.587785 6.07724e-17 -0.809017,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -0.951057 1.27822e-16 -0.309017,
+                          -0.809017 9.915e-17 -0.587785,
+                          -0.809017 9.915e-17 -0.587785,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -0.587785 6.07724e-17 -0.809017,
+                          -0.587785 6.07724e-17 -0.809017,
+                          -0.309017 1.6446e-17 -0.951057,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -0.809017 9.915e-17 -0.587785,
+                          -0.587785 6.07724e-17 -0.809017,
+                          -0.587785 6.07724e-17 -0.809017,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -0.309017 1.6446e-17 -0.951057,
+                          -0.309017 1.6446e-17 -0.951057,
+                          -1.16743e-16 -2.94903e-17 -1,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -1.66533e-16 1 -7.28584e-17,
+                          -0.587785 6.07724e-17 -0.809017,
+                          -0.309017 1.6446e-17 -0.951057,
+                          -0.309017 1.6446e-17 -0.951057,
+                          -5.55112e-17 -2.94903e-17 -1,
+                          -5.55112e-17 -2.94903e-17 -1,
+                          -5.55112e-17 -2.94903e-17 -1,
+                          -0.309017 1.6446e-17 -0.951057,
+                          -1.16743e-16 -2.94903e-17 -1,
+                          -1.16743e-16 -2.94903e-17 -1,
+                          -5.55112e-17 -2.94903e-17 -1,
+                          -5.55112e-17 -2.94903e-17 -1,
+                          0.309017 -7.25398e-17 -0.951057,
+                          -5.55112e-17 -2.94903e-17 -1,
+                          -5.55112e-17 -2.94903e-17 -1,
+                          -5.55112e-17 -2.94903e-17 -1,
+                          0.309017 -7.25398e-17 -0.951057,
+                          0.309017 -7.25398e-17 -0.951057,
+                          0.587785 -1.08489e-16 -0.809017,
+                          -5.55112e-17 -2.94903e-17 -1,
+                          0.309017 -7.25398e-17 -0.951057,
+                          0.309017 -7.25398e-17 -0.951057,
+                          0.587785 -1.08489e-16 -0.809017,
+                          0.587785 -1.08489e-16 -0.809017,
+                          0.809017 -1.33818e-16 -0.587785,
+                          0.309017 -7.25398e-17 -0.951057,
+                          0.587785 -1.08489e-16 -0.809017,
+                          0.587785 -1.08489e-16 -0.809017,
+                          0.809017 -1.33818e-16 -0.587785,
+                          0.809017 -1.33818e-16 -0.587785,
+                          0.951057 -1.46048e-16 -0.309017,
+                          0.587785 -1.08489e-16 -0.809017,
+                          0.809017 -1.33818e-16 -0.587785,
+                          0.809017 -1.33818e-16 -0.587785,
+                          0.951057 -1.46048e-16 -0.309017,
+                          0.951057 -1.46048e-16 -0.309017,
+                          1 -1.43982e-16 -1.16743e-16,
+                          0.809017 -1.33818e-16 -0.587785,
+                          0.951057 -1.46048e-16 -0.309017,
+                          0.951057 -1.46048e-16 -0.309017,
+                          1 -1.43982e-16 -5.55112e-17,
+                          1 -1.43982e-16 -5.55112e-17,
+                          1 -1.43982e-16 -5.55112e-17,
+                          0.951057 -1.46048e-16 -0.309017,
+                          1 -1.43982e-16 -1.16743e-16,
+                          1 -1.43982e-16 -1.16743e-16,
+                          1 -1.43982e-16 -5.55112e-17,
+                          1 -1.43982e-16 -5.55112e-17,
+                          0.951057 -1.27822e-16 0.309017,
+                          1 -1.43982e-16 -5.55112e-17,
+                          1 -1.43982e-16 -5.55112e-17,
+                          1 -1.43982e-16 -5.55112e-17,
+                          0.951057 -1.27822e-16 0.309017,
+                          0.951057 -1.27822e-16 0.309017,
+                          0.809017 -9.915e-17 0.587785,
+                          1 -1.43982e-16 -5.55112e-17,
+                          0.951057 -1.27822e-16 0.309017,
+                          0.951057 -1.27822e-16 0.309017,
+                          0.809017 -9.915e-17 0.587785,
+                          0.809017 -9.915e-17 0.587785,
+                          0.587785 -6.07724e-17 0.809017,
+                          0.951057 -1.27822e-16 0.309017,
+                          0.809017 -9.915e-17 0.587785,
+                          0.809017 -9.915e-17 0.587785,
+                          0.587785 -6.07724e-17 0.809017,
+                          0.587785 -6.07724e-17 0.809017,
+                          0.309017 -1.6446e-17 0.951057,
+                          0.809017 -9.915e-17 0.587785,
+                          0.587785 -6.07724e-17 0.809017,
+                          0.587785 -6.07724e-17 0.809017,
+                          0.309017 -1.6446e-17 0.951057,
+                          0.309017 -1.6446e-17 0.951057,
+                          1.16743e-16 2.94903e-17 1,
+                          0.587785 -6.07724e-17 0.809017,
+                          0.309017 -1.6446e-17 0.951057,
+                          0.309017 -1.6446e-17 0.951057,
+                          0.309017 -1.6446e-17 0.951057,
+                          1.16743e-16 2.94903e-17 1,
+                          1.16743e-16 2.94903e-17 1,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17,
+                          1.66533e-16 -1 7.28584e-17 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -10.5639 -2.25 79.3042,
+                          -29.4361 -2.25 79.3042,
+                          -28.2 -2.25 79.5,
+                          -28.2 -4.25 79.5,
+                          -28.2 -2.25 79.5,
+                          -29.4361 -2.25 79.3042,
+                          -11.8 -2.25 79.5,
+                          -10.5639 -2.25 79.3042,
+                          -28.2 -2.25 79.5,
+                          -11.8 -4.25 79.5,
+                          -11.8 -2.25 79.5,
+                          -28.2 -2.25 79.5,
+                          -11.8 -4.25 79.5,
+                          -28.2 -2.25 79.5,
+                          -28.2 -4.25 79.5,
+                          -9.44885 -2.25 78.7361,
+                          -30.5511 -2.25 78.7361,
+                          -29.4361 -2.25 79.3042,
+                          -29.4361 -4.25 79.3042,
+                          -29.4361 -2.25 79.3042,
+                          -30.5511 -2.25 78.7361,
+                          -10.5639 -2.25 79.3042,
+                          -9.44885 -2.25 78.7361,
+                          -29.4361 -2.25 79.3042,
+                          -28.2 -4.25 79.5,
+                          -29.4361 -2.25 79.3042,
+                          -29.4361 -4.25 79.3042,
+                          -8.56394 -2.25 77.8512,
+                          -31.4361 -2.25 77.8512,
+                          -30.5511 -2.25 78.7361,
+                          -30.5511 -4.25 78.7361,
+                          -30.5511 -2.25 78.7361,
+                          -31.4361 -2.25 77.8512,
+                          -9.44885 -2.25 78.7361,
+                          -8.56394 -2.25 77.8512,
+                          -30.5511 -2.25 78.7361,
+                          -29.4361 -4.25 79.3042,
+                          -30.5511 -2.25 78.7361,
+                          -30.5511 -4.25 78.7361,
+                          -7.99578 -2.25 76.7361,
+                          -32.0042 -2.25 76.7361,
+                          -31.4361 -2.25 77.8512,
+                          -31.4361 -4.25 77.8512,
+                          -31.4361 -2.25 77.8512,
+                          -32.0042 -2.25 76.7361,
+                          -8.56394 -2.25 77.8512,
+                          -7.99578 -2.25 76.7361,
+                          -31.4361 -2.25 77.8512,
+                          -30.5511 -4.25 78.7361,
+                          -31.4361 -2.25 77.8512,
+                          -31.4361 -4.25 77.8512,
+                          -7.8 -2.25 75.5,
+                          -32.2 -2.25 75.5,
+                          -32.0042 -2.25 76.7361,
+                          -32.0042 -4.25 76.7361,
+                          -32.0042 -2.25 76.7361,
+                          -32.2 -2.25 75.5,
+                          -7.99578 -2.25 76.7361,
+                          -7.8 -2.25 75.5,
+                          -32.0042 -2.25 76.7361,
+                          -31.4361 -4.25 77.8512,
+                          -32.0042 -2.25 76.7361,
+                          -32.0042 -4.25 76.7361,
+                          -7.8 -2.25 -6,
+                          -32.2 -2.25 -6,
+                          -32.2 -2.25 75.5,
+                          -32.2 -4.25 75.5,
+                          -32.2 -2.25 75.5,
+                          -32.2 -2.25 -6,
+                          -7.8 -2.25 75.5,
+                          -7.8 -2.25 -6,
+                          -32.2 -2.25 75.5,
+                          -32.0042 -4.25 76.7361,
+                          -32.2 -2.25 75.5,
+                          -32.2 -4.25 75.5,
+                          -7.99578 -2.25 -7.23608,
+                          -32.0042 -2.25 -7.23608,
+                          -32.2 -2.25 -6,
+                          -32.2 -4.25 -6,
+                          -32.2 -2.25 -6,
+                          -32.0042 -2.25 -7.23608,
+                          -7.8 -2.25 -6,
+                          -7.99578 -2.25 -7.23608,
+                          -32.2 -2.25 -6,
+                          -32.2 -4.25 -6,
+                          -32.2 -4.25 75.5,
+                          -32.2 -2.25 -6,
+                          -8.56394 -2.25 -8.35115,
+                          -31.4361 -2.25 -8.35115,
+                          -32.0042 -2.25 -7.23608,
+                          -32.0042 -4.25 -7.23608,
+                          -32.0042 -2.25 -7.23608,
+                          -31.4361 -2.25 -8.35115,
+                          -7.99578 -2.25 -7.23608,
+                          -8.56394 -2.25 -8.35115,
+                          -32.0042 -2.25 -7.23608,
+                          -32.2 -4.25 -6,
+                          -32.0042 -2.25 -7.23608,
+                          -32.0042 -4.25 -7.23608,
+                          -9.44885 -2.25 -9.23606,
+                          -30.5511 -2.25 -9.23606,
+                          -31.4361 -2.25 -8.35115,
+                          -31.4361 -4.25 -8.35115,
+                          -31.4361 -2.25 -8.35115,
+                          -30.5511 -2.25 -9.23606,
+                          -8.56394 -2.25 -8.35115,
+                          -9.44885 -2.25 -9.23606,
+                          -31.4361 -2.25 -8.35115,
+                          -32.0042 -4.25 -7.23608,
+                          -31.4361 -2.25 -8.35115,
+                          -31.4361 -4.25 -8.35115,
+                          -10.5639 -2.25 -9.80422,
+                          -29.4361 -2.25 -9.80422,
+                          -30.5511 -2.25 -9.23606,
+                          -30.5511 -4.25 -9.23606,
+                          -30.5511 -2.25 -9.23606,
+                          -29.4361 -2.25 -9.80422,
+                          -9.44885 -2.25 -9.23606,
+                          -10.5639 -2.25 -9.80422,
+                          -30.5511 -2.25 -9.23606,
+                          -31.4361 -4.25 -8.35115,
+                          -30.5511 -2.25 -9.23606,
+                          -30.5511 -4.25 -9.23606,
+                          -11.8 -2.25 -10,
+                          -28.2 -2.25 -10,
+                          -29.4361 -2.25 -9.80422,
+                          -29.4361 -4.25 -9.80422,
+                          -29.4361 -2.25 -9.80422,
+                          -28.2 -2.25 -10,
+                          -10.5639 -2.25 -9.80422,
+                          -11.8 -2.25 -10,
+                          -29.4361 -2.25 -9.80422,
+                          -30.5511 -4.25 -9.23606,
+                          -29.4361 -2.25 -9.80422,
+                          -29.4361 -4.25 -9.80422,
+                          -28.2 -4.25 -10,
+                          -28.2 -2.25 -10,
+                          -11.8 -2.25 -10,
+                          -29.4361 -4.25 -9.80422,
+                          -28.2 -2.25 -10,
+                          -28.2 -4.25 -10,
+                          -11.8 -4.25 -10,
+                          -11.8 -2.25 -10,
+                          -10.5639 -2.25 -9.80422,
+                          -28.2 -4.25 -10,
+                          -11.8 -2.25 -10,
+                          -11.8 -4.25 -10,
+                          -10.5639 -4.25 -9.80422,
+                          -10.5639 -2.25 -9.80422,
+                          -9.44885 -2.25 -9.23606,
+                          -11.8 -4.25 -10,
+                          -10.5639 -2.25 -9.80422,
+                          -10.5639 -4.25 -9.80422,
+                          -9.44885 -4.25 -9.23606,
+                          -9.44885 -2.25 -9.23606,
+                          -8.56394 -2.25 -8.35115,
+                          -10.5639 -4.25 -9.80422,
+                          -9.44885 -2.25 -9.23606,
+                          -9.44885 -4.25 -9.23606,
+                          -8.56394 -4.25 -8.35115,
+                          -8.56394 -2.25 -8.35115,
+                          -7.99578 -2.25 -7.23608,
+                          -9.44885 -4.25 -9.23606,
+                          -8.56394 -2.25 -8.35115,
+                          -8.56394 -4.25 -8.35115,
+                          -7.99578 -4.25 -7.23608,
+                          -7.99578 -2.25 -7.23608,
+                          -7.8 -2.25 -6,
+                          -8.56394 -4.25 -8.35115,
+                          -7.99578 -2.25 -7.23608,
+                          -7.99578 -4.25 -7.23608,
+                          -7.8 -4.25 -6,
+                          -7.8 -2.25 -6,
+                          -7.8 -2.25 75.5,
+                          -7.99578 -4.25 -7.23608,
+                          -7.8 -2.25 -6,
+                          -7.8 -4.25 -6,
+                          -7.8 -4.25 75.5,
+                          -7.8 -2.25 75.5,
+                          -7.99578 -2.25 76.7361,
+                          -7.8 -4.25 -6,
+                          -7.8 -2.25 75.5,
+                          -7.8 -4.25 75.5,
+                          -7.99578 -4.25 76.7361,
+                          -7.99578 -2.25 76.7361,
+                          -8.56394 -2.25 77.8512,
+                          -7.8 -4.25 75.5,
+                          -7.99578 -2.25 76.7361,
+                          -7.99578 -4.25 76.7361,
+                          -8.56394 -4.25 77.8512,
+                          -8.56394 -2.25 77.8512,
+                          -9.44885 -2.25 78.7361,
+                          -7.99578 -4.25 76.7361,
+                          -8.56394 -2.25 77.8512,
+                          -8.56394 -4.25 77.8512,
+                          -9.44885 -4.25 78.7361,
+                          -9.44885 -2.25 78.7361,
+                          -10.5639 -2.25 79.3042,
+                          -8.56394 -4.25 77.8512,
+                          -9.44885 -2.25 78.7361,
+                          -9.44885 -4.25 78.7361,
+                          -10.5639 -4.25 79.3042,
+                          -10.5639 -2.25 79.3042,
+                          -11.8 -2.25 79.5,
+                          -9.44885 -4.25 78.7361,
+                          -10.5639 -2.25 79.3042,
+                          -10.5639 -4.25 79.3042,
+                          -10.5639 -4.25 79.3042,
+                          -11.8 -2.25 79.5,
+                          -11.8 -4.25 79.5,
+                          -7.99578 -4.25 76.7361,
+                          -32.0042 -4.25 76.7361,
+                          -32.2 -4.25 75.5,
+                          -7.8 -4.25 75.5,
+                          -7.99578 -4.25 76.7361,
+                          -32.2 -4.25 75.5,
+                          -32.2 -4.25 -6,
+                          -7.8 -4.25 75.5,
+                          -32.2 -4.25 75.5,
+                          -8.56394 -4.25 77.8512,
+                          -31.4361 -4.25 77.8512,
+                          -32.0042 -4.25 76.7361,
+                          -7.99578 -4.25 76.7361,
+                          -8.56394 -4.25 77.8512,
+                          -32.0042 -4.25 76.7361,
+                          -9.44885 -4.25 78.7361,
+                          -30.5511 -4.25 78.7361,
+                          -31.4361 -4.25 77.8512,
+                          -8.56394 -4.25 77.8512,
+                          -9.44885 -4.25 78.7361,
+                          -31.4361 -4.25 77.8512,
+                          -10.5639 -4.25 79.3042,
+                          -29.4361 -4.25 79.3042,
+                          -30.5511 -4.25 78.7361,
+                          -9.44885 -4.25 78.7361,
+                          -10.5639 -4.25 79.3042,
+                          -30.5511 -4.25 78.7361,
+                          -11.8 -4.25 79.5,
+                          -28.2 -4.25 79.5,
+                          -29.4361 -4.25 79.3042,
+                          -10.5639 -4.25 79.3042,
+                          -11.8 -4.25 79.5,
+                          -29.4361 -4.25 79.3042,
+                          -32.2 -4.25 -6,
+                          -7.8 -4.25 -6,
+                          -7.8 -4.25 75.5,
+                          -32.0042 -4.25 -7.23608,
+                          -7.99578 -4.25 -7.23608,
+                          -7.8 -4.25 -6,
+                          -32.2 -4.25 -6,
+                          -32.0042 -4.25 -7.23608,
+                          -7.8 -4.25 -6,
+                          -31.4361 -4.25 -8.35115,
+                          -8.56394 -4.25 -8.35115,
+                          -7.99578 -4.25 -7.23608,
+                          -32.0042 -4.25 -7.23608,
+                          -31.4361 -4.25 -8.35115,
+                          -7.99578 -4.25 -7.23608,
+                          -30.5511 -4.25 -9.23606,
+                          -9.44885 -4.25 -9.23606,
+                          -8.56394 -4.25 -8.35115,
+                          -31.4361 -4.25 -8.35115,
+                          -30.5511 -4.25 -9.23606,
+                          -8.56394 -4.25 -8.35115,
+                          -29.4361 -4.25 -9.80422,
+                          -10.5639 -4.25 -9.80422,
+                          -9.44885 -4.25 -9.23606,
+                          -30.5511 -4.25 -9.23606,
+                          -29.4361 -4.25 -9.80422,
+                          -9.44885 -4.25 -9.23606,
+                          -28.2 -4.25 -10,
+                          -11.8 -4.25 -10,
+                          -10.5639 -4.25 -9.80422,
+                          -29.4361 -4.25 -9.80422,
+                          -28.2 -4.25 -10,
+                          -10.5639 -4.25 -9.80422 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/palm2_r.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/palm2_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..2df091827d32de9e452486c61136e50e2ce3c6d1
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/palm2_r.iv
@@ -0,0 +1,4359 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.25 0.25 0.25
+    }
+    Separator {
+        Normal {
+            vector      [ 2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          2.22045e-16 -6.76542e-17 1,
+                          2.22045e-16 -6.76542e-17 1,
+                          2.22045e-16 -6.76542e-17 1,
+                          0.309017 -1.06692e-16 0.951057,
+                          0.309017 -1.06692e-16 0.951057,
+                          2.83277e-16 -6.76542e-17 1,
+                          0.309017 -1.06692e-16 0.951057,
+                          2.83277e-16 -6.76542e-17 1,
+                          1.17146e-15 -6.76542e-17 1,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          1.60812e-16 -6.76542e-17 1,
+                          1.60812e-16 -6.76542e-17 1,
+                          -0.309017 -2.19943e-17 0.951057,
+                          2.22045e-16 -6.76542e-17 1,
+                          2.22045e-16 -6.76542e-17 1,
+                          2.22045e-16 -6.76542e-17 1,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          -0.309017 -2.19943e-17 0.951057,
+                          -0.309017 -2.19943e-17 0.951057,
+                          -0.587785 2.58185e-17 0.809017,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          1.60812e-16 -6.76542e-17 1,
+                          -0.309017 -2.19943e-17 0.951057,
+                          -0.309017 -2.19943e-17 0.951057,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          -0.587785 2.58185e-17 0.809017,
+                          -0.587785 2.58185e-17 0.809017,
+                          -0.809017 7.11041e-17 0.587785,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          -0.309017 -2.19943e-17 0.951057,
+                          -0.587785 2.58185e-17 0.809017,
+                          -0.587785 2.58185e-17 0.809017,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          -0.809017 7.11041e-17 0.587785,
+                          -0.809017 7.11041e-17 0.587785,
+                          -0.951057 1.09429e-16 0.309017,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          -0.587785 2.58185e-17 0.809017,
+                          -0.809017 7.11041e-17 0.587785,
+                          -0.809017 7.11041e-17 0.587785,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          -0.951057 1.09429e-16 0.309017,
+                          -0.951057 1.09429e-16 0.309017,
+                          -1 1.37043e-16 5.55112e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          -0.809017 7.11041e-17 0.587785,
+                          -0.951057 1.09429e-16 0.309017,
+                          -0.951057 1.09429e-16 0.309017,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          -1 1.37043e-16 5.55112e-17,
+                          -1 1.37043e-16 5.55112e-17,
+                          -1 1.37043e-16 5.55112e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          -0.951057 1.09429e-16 0.309017,
+                          -1 1.37043e-16 5.55112e-17,
+                          -1 1.37043e-16 5.55112e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          -1 1.37043e-16 -5.72119e-18,
+                          -1 1.37043e-16 -5.72119e-18,
+                          -0.951057 1.51242e-16 -0.309017,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          -1 1.37043e-16 5.55112e-17,
+                          -1 1.37043e-16 5.55112e-17,
+                          -1 1.37043e-16 5.55112e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          -0.951057 1.51242e-16 -0.309017,
+                          -0.951057 1.51242e-16 -0.309017,
+                          -0.809017 1.50636e-16 -0.587785,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          -1 1.37043e-16 -5.72119e-18,
+                          -0.951057 1.51242e-16 -0.309017,
+                          -0.951057 1.51242e-16 -0.309017,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          -0.809017 1.50636e-16 -0.587785,
+                          -0.809017 1.50636e-16 -0.587785,
+                          -0.587785 1.35285e-16 -0.809017,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          -0.951057 1.51242e-16 -0.309017,
+                          -0.809017 1.50636e-16 -0.587785,
+                          -0.809017 1.50636e-16 -0.587785,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          -0.587785 1.35285e-16 -0.809017,
+                          -0.587785 1.35285e-16 -0.809017,
+                          -0.309017 1.06692e-16 -0.951057,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          -0.809017 1.50636e-16 -0.587785,
+                          -0.587785 1.35285e-16 -0.809017,
+                          -0.587785 1.35285e-16 -0.809017,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          -0.309017 1.06692e-16 -0.951057,
+                          -0.309017 1.06692e-16 -0.951057,
+                          -2.22045e-16 6.76542e-17 -1,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          2.75821e-16 1 3.98986e-17,
+                          -0.587785 1.35285e-16 -0.809017,
+                          -0.309017 1.06692e-16 -0.951057,
+                          -0.309017 1.06692e-16 -0.951057,
+                          -2.22045e-16 6.76542e-17 -1,
+                          -2.22045e-16 6.76542e-17 -1,
+                          -2.22045e-16 6.76542e-17 -1,
+                          -0.309017 1.06692e-16 -0.951057,
+                          -2.22045e-16 6.76542e-17 -1,
+                          -2.22045e-16 6.76542e-17 -1,
+                          -1.60812e-16 6.76542e-17 -1,
+                          -1.60812e-16 6.76542e-17 -1,
+                          0.309017 2.19943e-17 -0.951057,
+                          -2.22045e-16 6.76542e-17 -1,
+                          -2.22045e-16 6.76542e-17 -1,
+                          -2.22045e-16 6.76542e-17 -1,
+                          0.309017 2.19943e-17 -0.951057,
+                          0.309017 2.19943e-17 -0.951057,
+                          0.587785 -2.58185e-17 -0.809017,
+                          -1.60812e-16 6.76542e-17 -1,
+                          0.309017 2.19943e-17 -0.951057,
+                          0.309017 2.19943e-17 -0.951057,
+                          0.587785 -2.58185e-17 -0.809017,
+                          0.587785 -2.58185e-17 -0.809017,
+                          0.809017 -7.11041e-17 -0.587785,
+                          0.309017 2.19943e-17 -0.951057,
+                          0.587785 -2.58185e-17 -0.809017,
+                          0.587785 -2.58185e-17 -0.809017,
+                          0.809017 -7.11041e-17 -0.587785,
+                          0.809017 -7.11041e-17 -0.587785,
+                          0.951057 -1.09429e-16 -0.309017,
+                          0.587785 -2.58185e-17 -0.809017,
+                          0.809017 -7.11041e-17 -0.587785,
+                          0.809017 -7.11041e-17 -0.587785,
+                          0.951057 -1.09429e-16 -0.309017,
+                          0.951057 -1.09429e-16 -0.309017,
+                          1 -1.37043e-16 -5.55112e-17,
+                          0.809017 -7.11041e-17 -0.587785,
+                          0.951057 -1.09429e-16 -0.309017,
+                          0.951057 -1.09429e-16 -0.309017,
+                          1 -1.37043e-16 -5.55112e-17,
+                          1 -1.37043e-16 -5.55112e-17,
+                          1 -1.37043e-16 -5.55112e-17,
+                          0.951057 -1.09429e-16 -0.309017,
+                          1 -1.37043e-16 -5.55112e-17,
+                          1 -1.37043e-16 -5.55112e-17,
+                          1 -1.37043e-16 -5.55112e-17,
+                          1 -1.37043e-16 -5.55112e-17,
+                          0.951057 -1.51242e-16 0.309017,
+                          1 -1.37043e-16 -5.55112e-17,
+                          1 -1.37043e-16 -5.55112e-17,
+                          1 -1.37043e-16 -5.55112e-17,
+                          0.951057 -1.51242e-16 0.309017,
+                          0.951057 -1.51242e-16 0.309017,
+                          0.809017 -1.50636e-16 0.587785,
+                          0.951057 -1.51242e-16 0.309017,
+                          1 -1.37043e-16 -5.55112e-17,
+                          0.951057 -1.51242e-16 0.309017,
+                          0.809017 -1.50636e-16 0.587785,
+                          0.809017 -1.50636e-16 0.587785,
+                          0.587785 -1.35285e-16 0.809017,
+                          0.951057 -1.51242e-16 0.309017,
+                          0.809017 -1.50636e-16 0.587785,
+                          0.809017 -1.50636e-16 0.587785,
+                          0.587785 -1.35285e-16 0.809017,
+                          0.587785 -1.35285e-16 0.809017,
+                          0.309017 -1.06692e-16 0.951057,
+                          0.809017 -1.50636e-16 0.587785,
+                          0.587785 -1.35285e-16 0.809017,
+                          0.587785 -1.35285e-16 0.809017,
+                          0.587785 -1.35285e-16 0.809017,
+                          0.309017 -1.06692e-16 0.951057,
+                          0.309017 -1.06692e-16 0.951057,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17,
+                          -2.75821e-16 -1 -3.98986e-17 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 29.4361 -2.25 79.3042,
+                          11.8 -2.25 79.5,
+                          28.2 -2.25 79.5,
+                          28.2 -4.25 79.5,
+                          28.2 -2.25 79.5,
+                          11.8 -2.25 79.5,
+                          29.4361 -4.25 79.3042,
+                          29.4361 -2.25 79.3042,
+                          28.2 -2.25 79.5,
+                          29.4361 -4.25 79.3042,
+                          28.2 -2.25 79.5,
+                          28.2 -4.25 79.5,
+                          29.4361 -2.25 79.3042,
+                          10.5639 -2.25 79.3042,
+                          11.8 -2.25 79.5,
+                          11.8 -4.25 79.5,
+                          11.8 -2.25 79.5,
+                          10.5639 -2.25 79.3042,
+                          28.2 -4.25 79.5,
+                          11.8 -2.25 79.5,
+                          11.8 -4.25 79.5,
+                          30.5511 -2.25 78.7361,
+                          9.44885 -2.25 78.7361,
+                          10.5639 -2.25 79.3042,
+                          10.5639 -4.25 79.3042,
+                          10.5639 -2.25 79.3042,
+                          9.44885 -2.25 78.7361,
+                          29.4361 -2.25 79.3042,
+                          30.5511 -2.25 78.7361,
+                          10.5639 -2.25 79.3042,
+                          11.8 -4.25 79.5,
+                          10.5639 -2.25 79.3042,
+                          10.5639 -4.25 79.3042,
+                          31.4361 -2.25 77.8512,
+                          8.56394 -2.25 77.8512,
+                          9.44885 -2.25 78.7361,
+                          9.44885 -4.25 78.7361,
+                          9.44885 -2.25 78.7361,
+                          8.56394 -2.25 77.8512,
+                          30.5511 -2.25 78.7361,
+                          31.4361 -2.25 77.8512,
+                          9.44885 -2.25 78.7361,
+                          10.5639 -4.25 79.3042,
+                          9.44885 -2.25 78.7361,
+                          9.44885 -4.25 78.7361,
+                          32.0042 -2.25 76.7361,
+                          7.99578 -2.25 76.7361,
+                          8.56394 -2.25 77.8512,
+                          8.56394 -4.25 77.8512,
+                          8.56394 -2.25 77.8512,
+                          7.99578 -2.25 76.7361,
+                          31.4361 -2.25 77.8512,
+                          32.0042 -2.25 76.7361,
+                          8.56394 -2.25 77.8512,
+                          9.44885 -4.25 78.7361,
+                          8.56394 -2.25 77.8512,
+                          8.56394 -4.25 77.8512,
+                          32.2 -2.25 75.5,
+                          7.8 -2.25 75.5,
+                          7.99578 -2.25 76.7361,
+                          7.99578 -4.25 76.7361,
+                          7.99578 -2.25 76.7361,
+                          7.8 -2.25 75.5,
+                          32.0042 -2.25 76.7361,
+                          32.2 -2.25 75.5,
+                          7.99578 -2.25 76.7361,
+                          8.56394 -4.25 77.8512,
+                          7.99578 -2.25 76.7361,
+                          7.99578 -4.25 76.7361,
+                          32.2 -2.25 -6,
+                          7.8 -2.25 -6,
+                          7.8 -2.25 75.5,
+                          7.8 -4.25 75.5,
+                          7.8 -2.25 75.5,
+                          7.8 -2.25 -6,
+                          32.2 -2.25 75.5,
+                          32.2 -2.25 -6,
+                          7.8 -2.25 75.5,
+                          7.99578 -4.25 76.7361,
+                          7.8 -2.25 75.5,
+                          7.8 -4.25 75.5,
+                          32.0042 -2.25 -7.23608,
+                          7.99578 -2.25 -7.23608,
+                          7.8 -2.25 -6,
+                          7.8 -4.25 -6,
+                          7.8 -2.25 -6,
+                          7.99578 -2.25 -7.23608,
+                          32.2 -2.25 -6,
+                          32.0042 -2.25 -7.23608,
+                          7.8 -2.25 -6,
+                          7.8 -4.25 75.5,
+                          7.8 -2.25 -6,
+                          7.8 -4.25 -6,
+                          31.4361 -2.25 -8.35115,
+                          8.56394 -2.25 -8.35115,
+                          7.99578 -2.25 -7.23608,
+                          7.99578 -4.25 -7.23608,
+                          7.99578 -2.25 -7.23608,
+                          8.56394 -2.25 -8.35115,
+                          32.0042 -2.25 -7.23608,
+                          31.4361 -2.25 -8.35115,
+                          7.99578 -2.25 -7.23608,
+                          7.8 -4.25 -6,
+                          7.99578 -2.25 -7.23608,
+                          7.99578 -4.25 -7.23608,
+                          30.5511 -2.25 -9.23606,
+                          9.44885 -2.25 -9.23606,
+                          8.56394 -2.25 -8.35115,
+                          8.56394 -4.25 -8.35115,
+                          8.56394 -2.25 -8.35115,
+                          9.44885 -2.25 -9.23606,
+                          31.4361 -2.25 -8.35115,
+                          30.5511 -2.25 -9.23606,
+                          8.56394 -2.25 -8.35115,
+                          7.99578 -4.25 -7.23608,
+                          8.56394 -2.25 -8.35115,
+                          8.56394 -4.25 -8.35115,
+                          29.4361 -2.25 -9.80422,
+                          10.5639 -2.25 -9.80422,
+                          9.44885 -2.25 -9.23606,
+                          9.44885 -4.25 -9.23606,
+                          9.44885 -2.25 -9.23606,
+                          10.5639 -2.25 -9.80422,
+                          30.5511 -2.25 -9.23606,
+                          29.4361 -2.25 -9.80422,
+                          9.44885 -2.25 -9.23606,
+                          8.56394 -4.25 -8.35115,
+                          9.44885 -2.25 -9.23606,
+                          9.44885 -4.25 -9.23606,
+                          28.2 -2.25 -10,
+                          11.8 -2.25 -10,
+                          10.5639 -2.25 -9.80422,
+                          10.5639 -4.25 -9.80422,
+                          10.5639 -2.25 -9.80422,
+                          11.8 -2.25 -10,
+                          29.4361 -2.25 -9.80422,
+                          28.2 -2.25 -10,
+                          10.5639 -2.25 -9.80422,
+                          9.44885 -4.25 -9.23606,
+                          10.5639 -2.25 -9.80422,
+                          10.5639 -4.25 -9.80422,
+                          11.8 -4.25 -10,
+                          11.8 -2.25 -10,
+                          28.2 -2.25 -10,
+                          10.5639 -4.25 -9.80422,
+                          11.8 -2.25 -10,
+                          11.8 -4.25 -10,
+                          28.2 -4.25 -10,
+                          28.2 -2.25 -10,
+                          29.4361 -2.25 -9.80422,
+                          11.8 -4.25 -10,
+                          28.2 -2.25 -10,
+                          28.2 -4.25 -10,
+                          29.4361 -4.25 -9.80422,
+                          29.4361 -2.25 -9.80422,
+                          30.5511 -2.25 -9.23606,
+                          28.2 -4.25 -10,
+                          29.4361 -2.25 -9.80422,
+                          29.4361 -4.25 -9.80422,
+                          30.5511 -4.25 -9.23606,
+                          30.5511 -2.25 -9.23606,
+                          31.4361 -2.25 -8.35115,
+                          29.4361 -4.25 -9.80422,
+                          30.5511 -2.25 -9.23606,
+                          30.5511 -4.25 -9.23606,
+                          31.4361 -4.25 -8.35115,
+                          31.4361 -2.25 -8.35115,
+                          32.0042 -2.25 -7.23608,
+                          30.5511 -4.25 -9.23606,
+                          31.4361 -2.25 -8.35115,
+                          31.4361 -4.25 -8.35115,
+                          32.0042 -4.25 -7.23608,
+                          32.0042 -2.25 -7.23608,
+                          32.2 -2.25 -6,
+                          31.4361 -4.25 -8.35115,
+                          32.0042 -2.25 -7.23608,
+                          32.0042 -4.25 -7.23608,
+                          32.2 -4.25 -6,
+                          32.2 -2.25 -6,
+                          32.2 -2.25 75.5,
+                          32.0042 -4.25 -7.23608,
+                          32.2 -2.25 -6,
+                          32.2 -4.25 -6,
+                          32.2 -4.25 75.5,
+                          32.2 -2.25 75.5,
+                          32.0042 -2.25 76.7361,
+                          32.2 -4.25 -6,
+                          32.2 -2.25 75.5,
+                          32.2 -4.25 75.5,
+                          32.0042 -4.25 76.7361,
+                          32.0042 -2.25 76.7361,
+                          31.4361 -2.25 77.8512,
+                          32.0042 -4.25 76.7361,
+                          32.2 -4.25 75.5,
+                          32.0042 -2.25 76.7361,
+                          31.4361 -4.25 77.8512,
+                          31.4361 -2.25 77.8512,
+                          30.5511 -2.25 78.7361,
+                          32.0042 -4.25 76.7361,
+                          31.4361 -2.25 77.8512,
+                          31.4361 -4.25 77.8512,
+                          30.5511 -4.25 78.7361,
+                          30.5511 -2.25 78.7361,
+                          29.4361 -2.25 79.3042,
+                          31.4361 -4.25 77.8512,
+                          30.5511 -2.25 78.7361,
+                          30.5511 -4.25 78.7361,
+                          30.5511 -4.25 78.7361,
+                          29.4361 -2.25 79.3042,
+                          29.4361 -4.25 79.3042,
+                          7.8 -4.25 -6,
+                          32.2 -4.25 -6,
+                          32.2 -4.25 75.5,
+                          7.8 -4.25 75.5,
+                          7.8 -4.25 -6,
+                          32.2 -4.25 75.5,
+                          32.0042 -4.25 76.7361,
+                          7.8 -4.25 75.5,
+                          32.2 -4.25 75.5,
+                          7.99578 -4.25 -7.23608,
+                          32.0042 -4.25 -7.23608,
+                          32.2 -4.25 -6,
+                          7.8 -4.25 -6,
+                          7.99578 -4.25 -7.23608,
+                          32.2 -4.25 -6,
+                          8.56394 -4.25 -8.35115,
+                          31.4361 -4.25 -8.35115,
+                          32.0042 -4.25 -7.23608,
+                          7.99578 -4.25 -7.23608,
+                          8.56394 -4.25 -8.35115,
+                          32.0042 -4.25 -7.23608,
+                          9.44885 -4.25 -9.23606,
+                          30.5511 -4.25 -9.23606,
+                          31.4361 -4.25 -8.35115,
+                          8.56394 -4.25 -8.35115,
+                          9.44885 -4.25 -9.23606,
+                          31.4361 -4.25 -8.35115,
+                          10.5639 -4.25 -9.80422,
+                          29.4361 -4.25 -9.80422,
+                          30.5511 -4.25 -9.23606,
+                          9.44885 -4.25 -9.23606,
+                          10.5639 -4.25 -9.80422,
+                          30.5511 -4.25 -9.23606,
+                          11.8 -4.25 -10,
+                          28.2 -4.25 -10,
+                          29.4361 -4.25 -9.80422,
+                          10.5639 -4.25 -9.80422,
+                          11.8 -4.25 -10,
+                          29.4361 -4.25 -9.80422,
+                          32.0042 -4.25 76.7361,
+                          7.99578 -4.25 76.7361,
+                          7.8 -4.25 75.5,
+                          31.4361 -4.25 77.8512,
+                          8.56394 -4.25 77.8512,
+                          7.99578 -4.25 76.7361,
+                          32.0042 -4.25 76.7361,
+                          31.4361 -4.25 77.8512,
+                          7.99578 -4.25 76.7361,
+                          30.5511 -4.25 78.7361,
+                          9.44885 -4.25 78.7361,
+                          8.56394 -4.25 77.8512,
+                          31.4361 -4.25 77.8512,
+                          30.5511 -4.25 78.7361,
+                          8.56394 -4.25 77.8512,
+                          29.4361 -4.25 79.3042,
+                          10.5639 -4.25 79.3042,
+                          9.44885 -4.25 78.7361,
+                          30.5511 -4.25 78.7361,
+                          29.4361 -4.25 79.3042,
+                          9.44885 -4.25 78.7361,
+                          28.2 -4.25 79.5,
+                          11.8 -4.25 79.5,
+                          10.5639 -4.25 79.3042,
+                          29.4361 -4.25 79.3042,
+                          28.2 -4.25 79.5,
+                          10.5639 -4.25 79.3042 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+    Separator {
+        Normal {
+            vector      [ 3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          1 1.89418e-16 2.77556e-17,
+                          1 1.89418e-16 2.77556e-17,
+                          0.809017 0.587785 -1.0806e-16,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          0.809017 -0.587785 1.52969e-16,
+                          0.809017 -0.587785 1.52969e-16,
+                          1 -5.55112e-17 2.77556e-17,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          0.809017 -0.587785 1.52969e-16,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          0.809017 0.587785 -1.0806e-16,
+                          0.809017 0.587785 -1.0806e-16,
+                          0.309017 0.951057 -2.026e-16,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          0.809017 0.587785 -1.0806e-16,
+                          1 1.89418e-16 2.77556e-17,
+                          0.809017 0.587785 -1.0806e-16,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          0.309017 0.951057 -2.026e-16,
+                          0.309017 0.951057 -2.026e-16,
+                          -0.309017 0.951057 -2.19754e-16,
+                          0.809017 0.587785 -1.0806e-16,
+                          0.309017 0.951057 -2.026e-16,
+                          0.309017 0.951057 -2.026e-16,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          -0.309017 0.951057 -2.19754e-16,
+                          -0.309017 0.951057 -2.19754e-16,
+                          -0.809017 0.587785 -1.52969e-16,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          0.309017 0.951057 -2.026e-16,
+                          -0.309017 0.951057 -2.19754e-16,
+                          -0.309017 0.951057 -2.19754e-16,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          -0.809017 0.587785 -1.52969e-16,
+                          -0.809017 0.587785 -1.52969e-16,
+                          -1 -6.69535e-17 -2.77556e-17,
+                          -0.309017 0.951057 -2.19754e-16,
+                          -0.809017 0.587785 -1.52969e-16,
+                          -0.809017 0.587785 -1.52969e-16,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          -1 -6.69535e-17 -2.77556e-17,
+                          -1 -6.69535e-17 -2.77556e-17,
+                          -0.809017 -0.587785 1.0806e-16,
+                          -0.809017 0.587785 -1.52969e-16,
+                          -1 -6.69535e-17 -2.77556e-17,
+                          -1 -6.69535e-17 -2.77556e-17,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          -0.809017 -0.587785 1.0806e-16,
+                          -0.809017 -0.587785 1.0806e-16,
+                          -0.309017 -0.951057 2.026e-16,
+                          -1 -6.69535e-17 -2.77556e-17,
+                          -0.809017 -0.587785 1.0806e-16,
+                          -0.809017 -0.587785 1.0806e-16,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          -0.309017 -0.951057 2.026e-16,
+                          -0.309017 -0.951057 2.026e-16,
+                          0.309017 -0.951057 2.19754e-16,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          -0.809017 -0.587785 1.0806e-16,
+                          -0.309017 -0.951057 2.026e-16,
+                          -0.309017 -0.951057 2.026e-16,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          0.309017 -0.951057 2.19754e-16,
+                          0.309017 -0.951057 2.19754e-16,
+                          0.809017 -0.587785 1.52969e-16,
+                          -0.309017 -0.951057 2.026e-16,
+                          0.309017 -0.951057 2.19754e-16,
+                          0.309017 -0.951057 2.19754e-16,
+                          0.309017 -0.951057 2.19754e-16,
+                          0.809017 -0.587785 1.52969e-16,
+                          0.809017 -0.587785 1.52969e-16,
+                          -2.77556e-16 -1 2.22045e-16,
+                          -2.77556e-16 -1 2.22045e-16,
+                          -2.77556e-16 -1 2.22045e-16,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          -9.38587e-17 -1 2.22045e-16,
+                          -9.38587e-17 -1 2.22045e-16,
+                          -0.382683 -0.92388 1.94521e-16,
+                          -2.77556e-16 -1 2.22045e-16,
+                          -2.77556e-16 -1 2.22045e-16,
+                          -2.77556e-16 -1 2.22045e-16,
+                          -2.77556e-16 -1 2.22045e-16,
+                          -2.77556e-16 -1 2.22045e-16,
+                          -2.77556e-16 -1 2.22045e-16,
+                          -2.77556e-16 -1 2.22045e-16,
+                          -2.77556e-16 -1 2.22045e-16,
+                          -2.77556e-16 -1 2.22045e-16,
+                          -2.77556e-16 -1 2.22045e-16,
+                          -2.77556e-16 -1 2.22045e-16,
+                          -2.77556e-16 -1 2.22045e-16,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          -0.382683 -0.92388 1.94521e-16,
+                          -0.382683 -0.92388 1.94521e-16,
+                          -0.707107 -0.707107 1.37383e-16,
+                          -0.382683 -0.92388 1.94521e-16,
+                          -9.38587e-17 -1 2.22045e-16,
+                          -0.382683 -0.92388 1.94521e-16,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          -0.707107 -0.707107 1.37383e-16,
+                          -0.707107 -0.707107 1.37383e-16,
+                          -0.92388 -0.382683 5.933e-17,
+                          -0.382683 -0.92388 1.94521e-16,
+                          -0.707107 -0.707107 1.37383e-16,
+                          -0.707107 -0.707107 1.37383e-16,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          -0.92388 -0.382683 5.933e-17,
+                          -0.92388 -0.382683 5.933e-17,
+                          -1 -1.89418e-16 -2.77556e-17,
+                          -0.707107 -0.707107 1.37383e-16,
+                          -0.92388 -0.382683 5.933e-17,
+                          -0.92388 -0.382683 5.933e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -0.92388 -0.382683 5.933e-17,
+                          -1 -1.89418e-16 -2.77556e-17,
+                          -1 -1.89418e-16 -2.77556e-17,
+                          2.77556e-16 1 -2.22045e-16,
+                          2.77556e-16 1 -2.22045e-16,
+                          2.77556e-16 1 -2.22045e-16,
+                          2.77556e-16 1 -2.22045e-16,
+                          2.77556e-16 1 -2.22045e-16,
+                          2.77556e-16 1 -2.22045e-16,
+                          2.77556e-16 1 -2.22045e-16,
+                          2.77556e-16 1 -2.22045e-16,
+                          2.77556e-16 1 -2.22045e-16,
+                          2.77556e-16 1 -2.22045e-16,
+                          2.77556e-16 1 -2.22045e-16,
+                          2.77556e-16 1 -2.22045e-16,
+                          2.77556e-16 1 -2.22045e-16,
+                          2.77556e-16 1 -2.22045e-16,
+                          2.77556e-16 1 -2.22045e-16,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -1 3.00441e-16 -2.77556e-17,
+                          -1 3.00441e-16 -2.77556e-17,
+                          -0.809017 0.587785 -1.52969e-16,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -0.809017 -0.587785 1.0806e-16,
+                          -0.809017 -0.587785 1.0806e-16,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -0.809017 -0.587785 1.0806e-16,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -0.809017 0.587785 -1.52969e-16,
+                          -0.809017 0.587785 -1.52969e-16,
+                          -0.309017 0.951057 -2.19754e-16,
+                          -0.809017 0.587785 -1.52969e-16,
+                          -1 3.00441e-16 -2.77556e-17,
+                          -0.809017 0.587785 -1.52969e-16,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -0.309017 0.951057 -2.19754e-16,
+                          -0.309017 0.951057 -2.19754e-16,
+                          0.309017 0.951057 -2.026e-16,
+                          -0.809017 0.587785 -1.52969e-16,
+                          -0.309017 0.951057 -2.19754e-16,
+                          -0.309017 0.951057 -2.19754e-16,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          0.309017 0.951057 -2.026e-16,
+                          0.309017 0.951057 -2.026e-16,
+                          0.809017 0.587785 -1.0806e-16,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -0.309017 0.951057 -2.19754e-16,
+                          0.309017 0.951057 -2.026e-16,
+                          0.309017 0.951057 -2.026e-16,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          0.809017 0.587785 -1.0806e-16,
+                          0.809017 0.587785 -1.0806e-16,
+                          1 -1.77976e-16 2.77556e-17,
+                          0.309017 0.951057 -2.026e-16,
+                          0.809017 0.587785 -1.0806e-16,
+                          0.809017 0.587785 -1.0806e-16,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          1 -1.77976e-16 2.77556e-17,
+                          1 -1.77976e-16 2.77556e-17,
+                          0.809017 -0.587785 1.52969e-16,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          0.809017 0.587785 -1.0806e-16,
+                          1 -1.77976e-16 2.77556e-17,
+                          1 -1.77976e-16 2.77556e-17,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          0.809017 -0.587785 1.52969e-16,
+                          0.809017 -0.587785 1.52969e-16,
+                          0.309017 -0.951057 2.19754e-16,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          1 -1.77976e-16 2.77556e-17,
+                          0.809017 -0.587785 1.52969e-16,
+                          0.809017 -0.587785 1.52969e-16,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          0.309017 -0.951057 2.19754e-16,
+                          0.309017 -0.951057 2.19754e-16,
+                          -0.309017 -0.951057 2.026e-16,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          0.809017 -0.587785 1.52969e-16,
+                          0.309017 -0.951057 2.19754e-16,
+                          0.309017 -0.951057 2.19754e-16,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -0.309017 -0.951057 2.026e-16,
+                          -0.309017 -0.951057 2.026e-16,
+                          -0.809017 -0.587785 1.0806e-16,
+                          0.309017 -0.951057 2.19754e-16,
+                          -0.309017 -0.951057 2.026e-16,
+                          -0.309017 -0.951057 2.026e-16,
+                          -0.309017 -0.951057 2.026e-16,
+                          -0.809017 -0.587785 1.0806e-16,
+                          -0.809017 -0.587785 1.0806e-16,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -2.77556e-16 -1 2.22045e-16,
+                          -2.77556e-16 -1 2.22045e-16,
+                          -2.77556e-16 -1 2.22045e-16,
+                          -0.382683 -0.92388 1.94521e-16,
+                          -0.382683 -0.92388 1.94521e-16,
+                          -9.38587e-17 -1 2.22045e-16,
+                          -0.382683 -0.92388 1.94521e-16,
+                          -9.38587e-17 -1 2.22045e-16,
+                          -9.38587e-17 -1 2.22045e-16,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          -2.77556e-16 -1 2.22045e-16,
+                          -2.77556e-16 -1 2.22045e-16,
+                          -2.77556e-16 -1 2.22045e-16,
+                          -2.77556e-16 -1 2.22045e-16,
+                          -2.77556e-16 -1 2.22045e-16,
+                          -2.77556e-16 -1 2.22045e-16,
+                          2.77556e-16 1 -2.22045e-16,
+                          2.77556e-16 1 -2.22045e-16,
+                          2.77556e-16 1 -2.22045e-16,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          2.77556e-16 1 -2.22045e-16,
+                          2.77556e-16 1 -2.22045e-16,
+                          2.77556e-16 1 -2.22045e-16,
+                          2.77556e-16 1 -2.22045e-16,
+                          2.77556e-16 1 -2.22045e-16,
+                          2.77556e-16 1 -2.22045e-16,
+                          -1 -1.89418e-16 -2.77556e-17,
+                          -1 -1.89418e-16 -2.77556e-17,
+                          -0.92388 -0.382683 5.933e-17,
+                          -0.92388 -0.382683 5.933e-17,
+                          -0.92388 -0.382683 5.933e-17,
+                          -0.707107 -0.707107 1.37383e-16,
+                          -0.92388 -0.382683 5.933e-17,
+                          -1 -1.89418e-16 -2.77556e-17,
+                          -0.92388 -0.382683 5.933e-17,
+                          -0.707107 -0.707107 1.37383e-16,
+                          -0.707107 -0.707107 1.37383e-16,
+                          -0.382683 -0.92388 1.94521e-16,
+                          -0.92388 -0.382683 5.933e-17,
+                          -0.707107 -0.707107 1.37383e-16,
+                          -0.707107 -0.707107 1.37383e-16,
+                          -0.707107 -0.707107 1.37383e-16,
+                          -0.382683 -0.92388 1.94521e-16,
+                          -0.382683 -0.92388 1.94521e-16,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          2.77556e-16 1 -2.22045e-16,
+                          2.77556e-16 1 -2.22045e-16,
+                          2.77556e-16 1 -2.22045e-16,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          1 -5.55112e-17 2.77556e-17,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          2.77556e-16 1 -2.22045e-16,
+                          2.77556e-16 1 -2.22045e-16,
+                          2.77556e-16 1 -2.22045e-16,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -2.77556e-16 -1 2.22045e-16,
+                          -2.77556e-16 -1 2.22045e-16,
+                          -2.77556e-16 -1 2.22045e-16,
+                          -2.77556e-16 -1 2.22045e-16,
+                          -2.77556e-16 -1 2.22045e-16,
+                          -2.77556e-16 -1 2.22045e-16,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          -3.60822e-16 -1.11022e-16 -1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          3.60822e-16 1.11022e-16 1,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -0.866025 -0.5 8.69853e-17,
+                          -0.866025 0.5 -1.35059e-16,
+                          -0.866025 0.5 -1.35059e-16,
+                          -1 3.00441e-16 -2.77556e-17,
+                          -0.866025 0.5 -1.35059e-16,
+                          -1 3.00441e-16 -2.77556e-17,
+                          -1 3.00441e-16 -2.77556e-17,
+                          -0.866025 -0.5 8.69853e-17,
+                          -0.866025 -0.5 8.69853e-17,
+                          -0.5 -0.866025 1.78418e-16,
+                          -0.866025 -0.5 8.69853e-17,
+                          -1 5.55112e-17 -2.77556e-17,
+                          -0.866025 -0.5 8.69853e-17,
+                          -0.5 -0.866025 1.78418e-16,
+                          -0.5 -0.866025 1.78418e-16,
+                          4.54619e-15 -1 2.22045e-16,
+                          -0.866025 -0.5 8.69853e-17,
+                          -0.5 -0.866025 1.78418e-16,
+                          -0.5 -0.866025 1.78418e-16,
+                          4.54619e-15 -1 2.22045e-16,
+                          4.54619e-15 -1 2.22045e-16,
+                          0.5 -0.866025 2.06174e-16,
+                          -0.5 -0.866025 1.78418e-16,
+                          4.54619e-15 -1 2.22045e-16,
+                          4.54619e-15 -1 2.22045e-16,
+                          0.5 -0.866025 2.06174e-16,
+                          0.5 -0.866025 2.06174e-16,
+                          0.866025 -0.5 1.35059e-16,
+                          4.54619e-15 -1 2.22045e-16,
+                          0.5 -0.866025 2.06174e-16,
+                          0.5 -0.866025 2.06174e-16,
+                          0.866025 -0.5 1.35059e-16,
+                          0.866025 -0.5 1.35059e-16,
+                          1 -1.77976e-16 2.77556e-17,
+                          0.5 -0.866025 2.06174e-16,
+                          0.866025 -0.5 1.35059e-16,
+                          0.866025 -0.5 1.35059e-16,
+                          1 -1.77976e-16 2.77556e-17,
+                          1 -1.77976e-16 2.77556e-17,
+                          0.866025 0.5 -8.69853e-17,
+                          0.866025 -0.5 1.35059e-16,
+                          1 -1.77976e-16 2.77556e-17,
+                          1 -1.77976e-16 2.77556e-17,
+                          0.866025 0.5 -8.69853e-17,
+                          0.866025 0.5 -8.69853e-17,
+                          0.5 0.866025 -1.78418e-16,
+                          1 -1.77976e-16 2.77556e-17,
+                          0.866025 0.5 -8.69853e-17,
+                          0.866025 0.5 -8.69853e-17,
+                          0.5 0.866025 -1.78418e-16,
+                          0.5 0.866025 -1.78418e-16,
+                          -1.3151e-15 1 -2.22045e-16,
+                          0.866025 0.5 -8.69853e-17,
+                          0.5 0.866025 -1.78418e-16,
+                          0.5 0.866025 -1.78418e-16,
+                          -1.3151e-15 1 -2.22045e-16,
+                          -1.3151e-15 1 -2.22045e-16,
+                          -0.5 0.866025 -2.06174e-16,
+                          0.5 0.866025 -1.78418e-16,
+                          -1.3151e-15 1 -2.22045e-16,
+                          -1.3151e-15 1 -2.22045e-16,
+                          -0.5 0.866025 -2.06174e-16,
+                          -0.5 0.866025 -2.06174e-16,
+                          -0.866025 0.5 -1.35059e-16,
+                          -1.3151e-15 1 -2.22045e-16,
+                          -0.5 0.866025 -2.06174e-16,
+                          -0.5 0.866025 -2.06174e-16,
+                          -0.5 0.866025 -2.06174e-16,
+                          -0.866025 0.5 -1.35059e-16,
+                          -0.866025 0.5 -1.35059e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -0.856699 -2.0597 32,
+                          -0.598674 -0.434958 32,
+                          -0.74 6.39488e-14 32,
+                          -0.74 6.39488e-14 29.8,
+                          -0.74 6.39488e-14 32,
+                          -0.598674 -0.434958 32,
+                          -2.4 2.25 32,
+                          -0.74 6.39488e-14 32,
+                          -0.598674 0.434958 32,
+                          -0.598674 0.434958 29.8,
+                          -0.598674 0.434958 32,
+                          -0.74 6.39488e-14 32,
+                          -2.4 2.25 32,
+                          -0.856699 -2.0597 32,
+                          -0.74 6.39488e-14 32,
+                          -0.598674 0.434958 29.8,
+                          -0.74 6.39488e-14 32,
+                          -0.74 6.39488e-14 29.8,
+                          0.1 -2.25 32,
+                          -0.228666 -0.703784 32,
+                          -0.598674 -0.434958 32,
+                          -0.598674 -0.434958 29.8,
+                          -0.598674 -0.434958 32,
+                          -0.228666 -0.703784 32,
+                          -0.856699 -2.0597 32,
+                          0.1 -2.25 32,
+                          -0.598674 -0.434958 32,
+                          -0.598674 -0.434958 29.8,
+                          -0.74 6.39488e-14 29.8,
+                          -0.598674 -0.434958 32,
+                          0.1 -2.25 32,
+                          0.228666 -0.703784 32,
+                          -0.228666 -0.703784 32,
+                          -0.228666 -0.703784 29.8,
+                          -0.228666 -0.703784 32,
+                          0.228666 -0.703784 32,
+                          -0.598674 -0.434958 29.8,
+                          -0.228666 -0.703784 32,
+                          -0.228666 -0.703784 29.8,
+                          37.6 -2.25 32,
+                          0.598674 -0.434958 32,
+                          0.228666 -0.703784 32,
+                          0.228666 -0.703784 29.8,
+                          0.228666 -0.703784 32,
+                          0.598674 -0.434958 32,
+                          0.1 -2.25 32,
+                          37.6 -2.25 32,
+                          0.228666 -0.703784 32,
+                          -0.228666 -0.703784 29.8,
+                          0.228666 -0.703784 32,
+                          0.228666 -0.703784 29.8,
+                          37.6 -2.25 32,
+                          0.74 6.39488e-14 32,
+                          0.598674 -0.434958 32,
+                          0.598674 -0.434958 29.8,
+                          0.598674 -0.434958 32,
+                          0.74 6.39488e-14 32,
+                          0.228666 -0.703784 29.8,
+                          0.598674 -0.434958 32,
+                          0.598674 -0.434958 29.8,
+                          37.6 -2.25 32,
+                          0.598674 0.434958 32,
+                          0.74 6.39488e-14 32,
+                          0.74 6.39488e-14 29.8,
+                          0.74 6.39488e-14 32,
+                          0.598674 0.434958 32,
+                          0.598674 -0.434958 29.8,
+                          0.74 6.39488e-14 32,
+                          0.74 6.39488e-14 29.8,
+                          37.6 -2.25 32,
+                          0.228666 0.703784 32,
+                          0.598674 0.434958 32,
+                          0.598674 0.434958 29.8,
+                          0.598674 0.434958 32,
+                          0.228666 0.703784 32,
+                          0.74 6.39488e-14 29.8,
+                          0.598674 0.434958 32,
+                          0.598674 0.434958 29.8,
+                          -2.4 2.25 32,
+                          -0.228666 0.703784 32,
+                          0.228666 0.703784 32,
+                          0.228666 0.703784 29.8,
+                          0.228666 0.703784 32,
+                          -0.228666 0.703784 32,
+                          -2.4 2.25 32,
+                          0.228666 0.703784 32,
+                          37.6 -2.25 32,
+                          0.598674 0.434958 29.8,
+                          0.228666 0.703784 32,
+                          0.228666 0.703784 29.8,
+                          -2.4 2.25 32,
+                          -0.598674 0.434958 32,
+                          -0.228666 0.703784 32,
+                          -0.228666 0.703784 29.8,
+                          -0.228666 0.703784 32,
+                          -0.598674 0.434958 32,
+                          0.228666 0.703784 29.8,
+                          -0.228666 0.703784 32,
+                          -0.228666 0.703784 29.8,
+                          -0.228666 0.703784 29.8,
+                          -0.598674 0.434958 32,
+                          -0.598674 0.434958 29.8,
+                          37.6 -2.25 29.5,
+                          37.6 -2.25 32,
+                          0.1 -2.25 32,
+                          37.6 2.25 32,
+                          -2.4 2.25 32,
+                          37.6 -2.25 32,
+                          37.6 2.25 29.5,
+                          37.6 2.25 32,
+                          37.6 -2.25 32,
+                          37.6 2.25 29.5,
+                          37.6 -2.25 32,
+                          37.6 -2.25 29.5,
+                          0.1 -2.25 29.8,
+                          0.1 -2.25 32,
+                          -0.856699 -2.0597 32,
+                          37.6 -2.25 24.5,
+                          0.1 -2.25 32,
+                          37.6 -2.25 22,
+                          2.25 -2.25 29.8,
+                          37.6 -2.25 22,
+                          0.1 -2.25 32,
+                          2.25 -2.25 29.8,
+                          0.1 -2.25 32,
+                          0.1 -2.25 29.8,
+                          37.6 -2.25 24.5,
+                          37.6 -2.25 29.5,
+                          0.1 -2.25 32,
+                          -2.4 2.25 32,
+                          -1.66777 -1.51777 32,
+                          -0.856699 -2.0597 32,
+                          -0.856699 -2.0597 29.8,
+                          -0.856699 -2.0597 32,
+                          -1.66777 -1.51777 32,
+                          -0.856699 -2.0597 29.8,
+                          0.1 -2.25 29.8,
+                          -0.856699 -2.0597 32,
+                          -2.4 2.25 32,
+                          -2.2097 -0.706699 32,
+                          -1.66777 -1.51777 32,
+                          -1.66777 -1.51777 29.8,
+                          -1.66777 -1.51777 32,
+                          -2.2097 -0.706699 32,
+                          -0.856699 -2.0597 29.8,
+                          -1.66777 -1.51777 32,
+                          -1.66777 -1.51777 29.8,
+                          -2.4 2.25 32,
+                          -2.4 0.25 32,
+                          -2.2097 -0.706699 32,
+                          -2.2097 -0.706699 29.8,
+                          -2.2097 -0.706699 32,
+                          -2.4 0.25 32,
+                          -1.66777 -1.51777 29.8,
+                          -2.2097 -0.706699 32,
+                          -2.2097 -0.706699 29.8,
+                          -2.4 2.25 29.8,
+                          -2.4 0.25 32,
+                          -2.4 2.25 32,
+                          -2.4 2.25 29.8,
+                          -2.4 0.25 29.8,
+                          -2.4 0.25 32,
+                          -2.2097 -0.706699 29.8,
+                          -2.4 0.25 32,
+                          -2.4 0.25 29.8,
+                          -2.4 2.25 29.8,
+                          -2.4 2.25 32,
+                          37.6 2.25 32,
+                          2.25 2.25 24.2,
+                          37.6 2.25 32,
+                          -2.4 2.25 22,
+                          37.6 2.25 29.5,
+                          -2.4 2.25 22,
+                          37.6 2.25 32,
+                          2.25 2.25 29.8,
+                          -2.4 2.25 29.8,
+                          37.6 2.25 32,
+                          2.25 2.25 24.2,
+                          2.25 2.25 29.8,
+                          37.6 2.25 32,
+                          0.1 -2.25 22,
+                          0.606764 -0.440835 22,
+                          0.75 6.39488e-14 22,
+                          0.75 6.39488e-14 24.2,
+                          0.75 6.39488e-14 22,
+                          0.606764 -0.440835 22,
+                          37.6 2.25 22,
+                          0.75 6.39488e-14 22,
+                          0.606764 0.440835 22,
+                          0.606764 0.440835 24.2,
+                          0.606764 0.440835 22,
+                          0.75 6.39488e-14 22,
+                          37.6 2.25 22,
+                          0.1 -2.25 22,
+                          0.75 6.39488e-14 22,
+                          0.606764 0.440835 24.2,
+                          0.75 6.39488e-14 22,
+                          0.75 6.39488e-14 24.2,
+                          0.1 -2.25 22,
+                          0.231756 -0.713294 22,
+                          0.606764 -0.440835 22,
+                          0.606764 -0.440835 24.2,
+                          0.606764 -0.440835 22,
+                          0.231756 -0.713294 22,
+                          0.606764 -0.440835 24.2,
+                          0.75 6.39488e-14 24.2,
+                          0.606764 -0.440835 22,
+                          0.1 -2.25 22,
+                          -0.231756 -0.713294 22,
+                          0.231756 -0.713294 22,
+                          0.231756 -0.713294 24.2,
+                          0.231756 -0.713294 22,
+                          -0.231756 -0.713294 22,
+                          0.606764 -0.440835 24.2,
+                          0.231756 -0.713294 22,
+                          0.231756 -0.713294 24.2,
+                          -0.856699 -2.0597 22,
+                          -0.606764 -0.440835 22,
+                          -0.231756 -0.713294 22,
+                          -0.231756 -0.713294 24.2,
+                          -0.231756 -0.713294 22,
+                          -0.606764 -0.440835 22,
+                          -0.856699 -2.0597 22,
+                          -0.231756 -0.713294 22,
+                          0.1 -2.25 22,
+                          0.231756 -0.713294 24.2,
+                          -0.231756 -0.713294 22,
+                          -0.231756 -0.713294 24.2,
+                          -0.856699 -2.0597 22,
+                          -0.75 6.39488e-14 22,
+                          -0.606764 -0.440835 22,
+                          -0.606764 -0.440835 24.2,
+                          -0.606764 -0.440835 22,
+                          -0.75 6.39488e-14 22,
+                          -0.231756 -0.713294 24.2,
+                          -0.606764 -0.440835 22,
+                          -0.606764 -0.440835 24.2,
+                          -1.66777 -1.51777 22,
+                          -0.606764 0.440835 22,
+                          -0.75 6.39488e-14 22,
+                          -0.75 6.39488e-14 24.2,
+                          -0.75 6.39488e-14 22,
+                          -0.606764 0.440835 22,
+                          -0.856699 -2.0597 22,
+                          -1.66777 -1.51777 22,
+                          -0.75 6.39488e-14 22,
+                          -0.606764 -0.440835 24.2,
+                          -0.75 6.39488e-14 22,
+                          -0.75 6.39488e-14 24.2,
+                          -2.2097 -0.706699 22,
+                          -0.231756 0.713294 22,
+                          -0.606764 0.440835 22,
+                          -0.606764 0.440835 24.2,
+                          -0.606764 0.440835 22,
+                          -0.231756 0.713294 22,
+                          -1.66777 -1.51777 22,
+                          -2.2097 -0.706699 22,
+                          -0.606764 0.440835 22,
+                          -0.75 6.39488e-14 24.2,
+                          -0.606764 0.440835 22,
+                          -0.606764 0.440835 24.2,
+                          37.6 2.25 22,
+                          0.231756 0.713294 22,
+                          -0.231756 0.713294 22,
+                          -0.231756 0.713294 24.2,
+                          -0.231756 0.713294 22,
+                          0.231756 0.713294 22,
+                          -2.4 2.25 22,
+                          37.6 2.25 22,
+                          -0.231756 0.713294 22,
+                          -2.4 0.25 22,
+                          -2.4 2.25 22,
+                          -0.231756 0.713294 22,
+                          -2.2097 -0.706699 22,
+                          -2.4 0.25 22,
+                          -0.231756 0.713294 22,
+                          -0.606764 0.440835 24.2,
+                          -0.231756 0.713294 22,
+                          -0.231756 0.713294 24.2,
+                          37.6 2.25 22,
+                          0.606764 0.440835 22,
+                          0.231756 0.713294 22,
+                          0.231756 0.713294 24.2,
+                          0.231756 0.713294 22,
+                          0.606764 0.440835 22,
+                          -0.231756 0.713294 24.2,
+                          0.231756 0.713294 22,
+                          0.231756 0.713294 24.2,
+                          0.231756 0.713294 24.2,
+                          0.606764 0.440835 22,
+                          0.606764 0.440835 24.2,
+                          37.6 2.25 22,
+                          37.6 -2.25 22,
+                          0.1 -2.25 22,
+                          0.1 -2.25 24.2,
+                          0.1 -2.25 22,
+                          37.6 -2.25 22,
+                          -0.856699 -2.0597 24.2,
+                          -0.856699 -2.0597 22,
+                          0.1 -2.25 22,
+                          -0.856699 -2.0597 24.2,
+                          0.1 -2.25 22,
+                          0.1 -2.25 24.2,
+                          37.6 -2.25 24.5,
+                          37.6 -2.25 22,
+                          37.6 2.25 22,
+                          2.25 -2.25 24.2,
+                          0.1 -2.25 24.2,
+                          37.6 -2.25 22,
+                          2.25 -2.25 29.8,
+                          2.25 -2.25 24.2,
+                          37.6 -2.25 22,
+                          37.6 2.25 24.5,
+                          37.6 2.25 22,
+                          -2.4 2.25 22,
+                          37.6 2.25 24.5,
+                          37.6 -2.25 24.5,
+                          37.6 2.25 22,
+                          -2.4 0.25 24.2,
+                          -2.4 2.25 22,
+                          -2.4 0.25 22,
+                          -2.4 2.25 24.2,
+                          -2.4 2.25 22,
+                          -2.4 0.25 24.2,
+                          2.25 2.25 24.2,
+                          -2.4 2.25 22,
+                          -2.4 2.25 24.2,
+                          37.6 2.25 29.5,
+                          37.6 2.25 24.5,
+                          -2.4 2.25 22,
+                          -2.4 0.25 24.2,
+                          -2.4 0.25 22,
+                          -2.2097 -0.706699 22,
+                          -2.2097 -0.706699 24.2,
+                          -2.2097 -0.706699 22,
+                          -1.66777 -1.51777 22,
+                          -2.2097 -0.706699 24.2,
+                          -2.4 0.25 24.2,
+                          -2.2097 -0.706699 22,
+                          -1.66777 -1.51777 24.2,
+                          -1.66777 -1.51777 22,
+                          -0.856699 -2.0597 22,
+                          -2.2097 -0.706699 24.2,
+                          -1.66777 -1.51777 22,
+                          -1.66777 -1.51777 24.2,
+                          -1.66777 -1.51777 24.2,
+                          -0.856699 -2.0597 22,
+                          -0.856699 -2.0597 24.2,
+                          42.25 -2.25 24.5,
+                          42.25 2.25 24.5,
+                          42.25 2.25 29.5,
+                          37.6 2.25 24.5,
+                          42.25 2.25 29.5,
+                          42.25 2.25 24.5,
+                          42.25 -2.25 29.5,
+                          42.25 -2.25 24.5,
+                          42.25 2.25 29.5,
+                          40.9093 0.525005 29.5,
+                          42.25 -2.25 29.5,
+                          42.25 2.25 29.5,
+                          37.6 2.25 29.5,
+                          42.25 2.25 29.5,
+                          37.6 2.25 24.5,
+                          40.525 0.909323 29.5,
+                          42.25 2.25 29.5,
+                          37.6 2.25 29.5,
+                          40.525 0.909323 29.5,
+                          40.9093 0.525005 29.5,
+                          42.25 2.25 29.5,
+                          40.9093 -0.525005 24.5,
+                          42.25 2.25 24.5,
+                          42.25 -2.25 24.5,
+                          39.475 0.909323 24.5,
+                          37.6 2.25 24.5,
+                          42.25 2.25 24.5,
+                          40.9093 -0.525005 24.5,
+                          41.05 6.39488e-14 24.5,
+                          42.25 2.25 24.5,
+                          40.9093 0.525005 24.5,
+                          42.25 2.25 24.5,
+                          41.05 6.39488e-14 24.5,
+                          40 1.05 24.5,
+                          39.475 0.909323 24.5,
+                          42.25 2.25 24.5,
+                          40.525 0.909323 24.5,
+                          40 1.05 24.5,
+                          42.25 2.25 24.5,
+                          40.9093 0.525005 24.5,
+                          40.525 0.909323 24.5,
+                          42.25 2.25 24.5,
+                          37.6 -2.25 29.5,
+                          42.25 -2.25 24.5,
+                          42.25 -2.25 29.5,
+                          37.6 -2.25 24.5,
+                          42.25 -2.25 24.5,
+                          37.6 -2.25 29.5,
+                          40.525 -0.909323 24.5,
+                          42.25 -2.25 24.5,
+                          37.6 -2.25 24.5,
+                          40.525 -0.909323 24.5,
+                          40.9093 -0.525005 24.5,
+                          42.25 -2.25 24.5,
+                          39.475 -0.909323 29.5,
+                          37.6 -2.25 29.5,
+                          42.25 -2.25 29.5,
+                          40.9093 0.525005 29.5,
+                          41.05 6.39488e-14 29.5,
+                          42.25 -2.25 29.5,
+                          40.9093 -0.525005 29.5,
+                          42.25 -2.25 29.5,
+                          41.05 6.39488e-14 29.5,
+                          40 -1.05 29.5,
+                          39.475 -0.909323 29.5,
+                          42.25 -2.25 29.5,
+                          40.525 -0.909323 29.5,
+                          40 -1.05 29.5,
+                          42.25 -2.25 29.5,
+                          40.9093 -0.525005 29.5,
+                          40.525 -0.909323 29.5,
+                          42.25 -2.25 29.5,
+                          2.25 2.25 29.8,
+                          2.25 -2.25 29.8,
+                          0.1 -2.25 29.8,
+                          0.74 6.39488e-14 29.8,
+                          2.25 2.25 29.8,
+                          0.1 -2.25 29.8,
+                          0.598674 -0.434958 29.8,
+                          0.74 6.39488e-14 29.8,
+                          0.1 -2.25 29.8,
+                          0.228666 -0.703784 29.8,
+                          0.598674 -0.434958 29.8,
+                          0.1 -2.25 29.8,
+                          -0.228666 -0.703784 29.8,
+                          0.228666 -0.703784 29.8,
+                          0.1 -2.25 29.8,
+                          -0.856699 -2.0597 29.8,
+                          -0.228666 -0.703784 29.8,
+                          0.1 -2.25 29.8,
+                          39.0907 -0.525005 29.5,
+                          37.6 2.25 29.5,
+                          37.6 -2.25 29.5,
+                          39.475 -0.909323 29.5,
+                          39.0907 -0.525005 29.5,
+                          37.6 -2.25 29.5,
+                          39.0907 0.525005 24.5,
+                          37.6 -2.25 24.5,
+                          37.6 2.25 24.5,
+                          40 -1.05 24.5,
+                          40.525 -0.909323 24.5,
+                          37.6 -2.25 24.5,
+                          39.475 -0.909323 24.5,
+                          40 -1.05 24.5,
+                          37.6 -2.25 24.5,
+                          39.0907 -0.525005 24.5,
+                          39.475 -0.909323 24.5,
+                          37.6 -2.25 24.5,
+                          38.95 6.39488e-14 24.5,
+                          39.0907 -0.525005 24.5,
+                          37.6 -2.25 24.5,
+                          39.0907 0.525005 24.5,
+                          38.95 6.39488e-14 24.5,
+                          37.6 -2.25 24.5,
+                          0.231756 -0.713294 24.2,
+                          0.1 -2.25 24.2,
+                          2.25 -2.25 24.2,
+                          -0.231756 -0.713294 24.2,
+                          -0.606764 -0.440835 24.2,
+                          0.1 -2.25 24.2,
+                          -0.856699 -2.0597 24.2,
+                          0.1 -2.25 24.2,
+                          -0.606764 -0.440835 24.2,
+                          0.231756 -0.713294 24.2,
+                          -0.231756 -0.713294 24.2,
+                          0.1 -2.25 24.2,
+                          2.25 2.25 24.2,
+                          2.25 -2.25 24.2,
+                          2.25 -2.25 29.8,
+                          0.606764 0.440835 24.2,
+                          2.25 -2.25 24.2,
+                          2.25 2.25 24.2,
+                          0.606764 0.440835 24.2,
+                          0.75 6.39488e-14 24.2,
+                          2.25 -2.25 24.2,
+                          0.606764 -0.440835 24.2,
+                          2.25 -2.25 24.2,
+                          0.75 6.39488e-14 24.2,
+                          0.606764 -0.440835 24.2,
+                          0.231756 -0.713294 24.2,
+                          2.25 -2.25 24.2,
+                          2.25 2.25 24.2,
+                          2.25 -2.25 29.8,
+                          2.25 2.25 29.8,
+                          2.25 2.25 29.8,
+                          -2.4 0.25 29.8,
+                          -2.4 2.25 29.8,
+                          -0.228666 0.703784 29.8,
+                          -2.4 0.25 29.8,
+                          2.25 2.25 29.8,
+                          -2.2097 -0.706699 29.8,
+                          -2.4 0.25 29.8,
+                          -0.228666 0.703784 29.8,
+                          -2.2097 -0.706699 24.2,
+                          -2.4 2.25 24.2,
+                          -2.4 0.25 24.2,
+                          0.231756 0.713294 24.2,
+                          2.25 2.25 24.2,
+                          -2.4 2.25 24.2,
+                          -0.231756 0.713294 24.2,
+                          0.231756 0.713294 24.2,
+                          -2.4 2.25 24.2,
+                          -0.606764 0.440835 24.2,
+                          -0.231756 0.713294 24.2,
+                          -2.4 2.25 24.2,
+                          -0.75 6.39488e-14 24.2,
+                          -0.606764 0.440835 24.2,
+                          -2.4 2.25 24.2,
+                          -0.856699 -2.0597 24.2,
+                          -0.75 6.39488e-14 24.2,
+                          -2.4 2.25 24.2,
+                          -1.66777 -1.51777 24.2,
+                          -0.856699 -2.0597 24.2,
+                          -2.4 2.25 24.2,
+                          -2.2097 -0.706699 24.2,
+                          -1.66777 -1.51777 24.2,
+                          -2.4 2.25 24.2,
+                          0.228666 0.703784 29.8,
+                          -0.228666 0.703784 29.8,
+                          2.25 2.25 29.8,
+                          0.598674 0.434958 29.8,
+                          0.228666 0.703784 29.8,
+                          2.25 2.25 29.8,
+                          0.74 6.39488e-14 29.8,
+                          0.598674 0.434958 29.8,
+                          2.25 2.25 29.8,
+                          0.231756 0.713294 24.2,
+                          0.606764 0.440835 24.2,
+                          2.25 2.25 24.2,
+                          39.475 0.909323 24.5,
+                          39.0907 0.525005 24.5,
+                          37.6 2.25 24.5,
+                          40 1.05 29.5,
+                          40.525 0.909323 29.5,
+                          37.6 2.25 29.5,
+                          39.475 0.909323 29.5,
+                          40 1.05 29.5,
+                          37.6 2.25 29.5,
+                          39.0907 0.525005 29.5,
+                          39.475 0.909323 29.5,
+                          37.6 2.25 29.5,
+                          38.95 6.39488e-14 29.5,
+                          39.0907 0.525005 29.5,
+                          37.6 2.25 29.5,
+                          39.0907 -0.525005 29.5,
+                          38.95 6.39488e-14 29.5,
+                          37.6 2.25 29.5,
+                          -1.66777 -1.51777 29.8,
+                          -0.598674 0.434958 29.8,
+                          -0.74 6.39488e-14 29.8,
+                          -0.856699 -2.0597 29.8,
+                          -0.74 6.39488e-14 29.8,
+                          -0.598674 -0.434958 29.8,
+                          -0.856699 -2.0597 29.8,
+                          -1.66777 -1.51777 29.8,
+                          -0.74 6.39488e-14 29.8,
+                          -2.2097 -0.706699 29.8,
+                          -0.228666 0.703784 29.8,
+                          -0.598674 0.434958 29.8,
+                          -1.66777 -1.51777 29.8,
+                          -2.2097 -0.706699 29.8,
+                          -0.598674 0.434958 29.8,
+                          -0.856699 -2.0597 29.8,
+                          -0.598674 -0.434958 29.8,
+                          -0.228666 -0.703784 29.8,
+                          -0.856699 -2.0597 24.2,
+                          -0.606764 -0.440835 24.2,
+                          -0.75 6.39488e-14 24.2,
+                          41.05 6.39488e-14 24.5,
+                          41.05 6.39488e-14 29.5,
+                          40.9093 0.525005 29.5,
+                          40.9093 -0.525005 24.5,
+                          40.9093 -0.525005 29.5,
+                          41.05 6.39488e-14 29.5,
+                          40.9093 -0.525005 24.5,
+                          41.05 6.39488e-14 29.5,
+                          41.05 6.39488e-14 24.5,
+                          40.9093 0.525005 24.5,
+                          40.9093 0.525005 29.5,
+                          40.525 0.909323 29.5,
+                          40.9093 0.525005 24.5,
+                          41.05 6.39488e-14 24.5,
+                          40.9093 0.525005 29.5,
+                          40.525 0.909323 24.5,
+                          40.525 0.909323 29.5,
+                          40 1.05 29.5,
+                          40.9093 0.525005 24.5,
+                          40.525 0.909323 29.5,
+                          40.525 0.909323 24.5,
+                          40 1.05 24.5,
+                          40 1.05 29.5,
+                          39.475 0.909323 29.5,
+                          40.525 0.909323 24.5,
+                          40 1.05 29.5,
+                          40 1.05 24.5,
+                          39.475 0.909323 24.5,
+                          39.475 0.909323 29.5,
+                          39.0907 0.525005 29.5,
+                          40 1.05 24.5,
+                          39.475 0.909323 29.5,
+                          39.475 0.909323 24.5,
+                          39.0907 0.525005 24.5,
+                          39.0907 0.525005 29.5,
+                          38.95 6.39488e-14 29.5,
+                          39.475 0.909323 24.5,
+                          39.0907 0.525005 29.5,
+                          39.0907 0.525005 24.5,
+                          38.95 6.39488e-14 24.5,
+                          38.95 6.39488e-14 29.5,
+                          39.0907 -0.525005 29.5,
+                          39.0907 0.525005 24.5,
+                          38.95 6.39488e-14 29.5,
+                          38.95 6.39488e-14 24.5,
+                          39.0907 -0.525005 24.5,
+                          39.0907 -0.525005 29.5,
+                          39.475 -0.909323 29.5,
+                          38.95 6.39488e-14 24.5,
+                          39.0907 -0.525005 29.5,
+                          39.0907 -0.525005 24.5,
+                          39.475 -0.909323 24.5,
+                          39.475 -0.909323 29.5,
+                          40 -1.05 29.5,
+                          39.0907 -0.525005 24.5,
+                          39.475 -0.909323 29.5,
+                          39.475 -0.909323 24.5,
+                          40 -1.05 24.5,
+                          40 -1.05 29.5,
+                          40.525 -0.909323 29.5,
+                          39.475 -0.909323 24.5,
+                          40 -1.05 29.5,
+                          40 -1.05 24.5,
+                          40.525 -0.909323 24.5,
+                          40.525 -0.909323 29.5,
+                          40.9093 -0.525005 29.5,
+                          40 -1.05 24.5,
+                          40.525 -0.909323 29.5,
+                          40.525 -0.909323 24.5,
+                          40.525 -0.909323 24.5,
+                          40.9093 -0.525005 29.5,
+                          40.9093 -0.525005 24.5 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          1 3.55952e-16 3.33067e-16,
+                          1 3.55952e-16 3.33067e-16,
+                          0.809017 0.587785 2.36828e-16,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          0.809017 -0.587785 3.02085e-16,
+                          0.809017 -0.587785 3.02085e-16,
+                          1 1.11022e-16 3.33067e-16,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          0.809017 -0.587785 3.02085e-16,
+                          1 1.11022e-16 3.33067e-16,
+                          1 1.11022e-16 3.33067e-16,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          0.809017 0.587785 2.36828e-16,
+                          0.809017 0.587785 2.36828e-16,
+                          0.309017 0.951057 5.01291e-17,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          0.809017 0.587785 2.36828e-16,
+                          1 3.55952e-16 3.33067e-16,
+                          0.809017 0.587785 2.36828e-16,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          0.309017 0.951057 5.01291e-17,
+                          0.309017 0.951057 5.01291e-17,
+                          -0.309017 0.951057 -1.55718e-16,
+                          0.809017 0.587785 2.36828e-16,
+                          0.309017 0.951057 5.01291e-17,
+                          0.309017 0.951057 5.01291e-17,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          -0.309017 0.951057 -1.55718e-16,
+                          -0.309017 0.951057 -1.55718e-16,
+                          -0.809017 0.587785 -3.02085e-16,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          0.309017 0.951057 5.01291e-17,
+                          -0.309017 0.951057 -1.55718e-16,
+                          -0.309017 0.951057 -1.55718e-16,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          -0.809017 0.587785 -3.02085e-16,
+                          -0.809017 0.587785 -3.02085e-16,
+                          -1 -2.33487e-16 -3.33067e-16,
+                          -0.309017 0.951057 -1.55718e-16,
+                          -0.809017 0.587785 -3.02085e-16,
+                          -0.809017 0.587785 -3.02085e-16,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          -1 -2.33487e-16 -3.33067e-16,
+                          -1 -2.33487e-16 -3.33067e-16,
+                          -0.809017 -0.587785 -2.36828e-16,
+                          -0.809017 0.587785 -3.02085e-16,
+                          -1 -2.33487e-16 -3.33067e-16,
+                          -1 -2.33487e-16 -3.33067e-16,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          -0.809017 -0.587785 -2.36828e-16,
+                          -0.809017 -0.587785 -2.36828e-16,
+                          -0.309017 -0.951057 -5.01291e-17,
+                          -1 -2.33487e-16 -3.33067e-16,
+                          -0.809017 -0.587785 -2.36828e-16,
+                          -0.809017 -0.587785 -2.36828e-16,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          -0.309017 -0.951057 -5.01291e-17,
+                          -0.309017 -0.951057 -5.01291e-17,
+                          0.309017 -0.951057 1.55718e-16,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          -0.809017 -0.587785 -2.36828e-16,
+                          -0.309017 -0.951057 -5.01291e-17,
+                          -0.309017 -0.951057 -5.01291e-17,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          0.309017 -0.951057 1.55718e-16,
+                          0.309017 -0.951057 1.55718e-16,
+                          0.809017 -0.587785 3.02085e-16,
+                          -0.309017 -0.951057 -5.01291e-17,
+                          0.309017 -0.951057 1.55718e-16,
+                          0.309017 -0.951057 1.55718e-16,
+                          0.309017 -0.951057 1.55718e-16,
+                          0.809017 -0.587785 3.02085e-16,
+                          0.809017 -0.587785 3.02085e-16,
+                          -4.16334e-16 -1 5.55112e-17,
+                          -4.16334e-16 -1 5.55112e-17,
+                          -4.16334e-16 -1 5.55112e-17,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          1 1.11022e-16 3.33067e-16,
+                          1 1.11022e-16 3.33067e-16,
+                          1 1.11022e-16 3.33067e-16,
+                          1 1.11022e-16 3.33067e-16,
+                          1 1.11022e-16 3.33067e-16,
+                          1 1.11022e-16 3.33067e-16,
+                          -2.32637e-16 -1 5.55112e-17,
+                          -2.32637e-16 -1 5.55112e-17,
+                          -0.382683 -0.92388 -7.61736e-17,
+                          -4.16334e-16 -1 5.55112e-17,
+                          -4.16334e-16 -1 5.55112e-17,
+                          -4.16334e-16 -1 5.55112e-17,
+                          -4.16334e-16 -1 5.55112e-17,
+                          -4.16334e-16 -1 5.55112e-17,
+                          -4.16334e-16 -1 5.55112e-17,
+                          -4.16334e-16 -1 5.55112e-17,
+                          -4.16334e-16 -1 5.55112e-17,
+                          -4.16334e-16 -1 5.55112e-17,
+                          -4.16334e-16 -1 5.55112e-17,
+                          -4.16334e-16 -1 5.55112e-17,
+                          -4.16334e-16 -1 5.55112e-17,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          -0.382683 -0.92388 -7.61736e-17,
+                          -0.382683 -0.92388 -7.61736e-17,
+                          -0.707107 -0.707107 -1.96262e-16,
+                          -0.382683 -0.92388 -7.61736e-17,
+                          -2.32637e-16 -1 5.55112e-17,
+                          -0.382683 -0.92388 -7.61736e-17,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          -0.707107 -0.707107 -1.96262e-16,
+                          -0.707107 -0.707107 -1.96262e-16,
+                          -0.92388 -0.382683 -2.86471e-16,
+                          -0.382683 -0.92388 -7.61736e-17,
+                          -0.707107 -0.707107 -1.96262e-16,
+                          -0.707107 -0.707107 -1.96262e-16,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          -0.92388 -0.382683 -2.86471e-16,
+                          -0.92388 -0.382683 -2.86471e-16,
+                          -1 -3.55952e-16 -3.33067e-16,
+                          -0.707107 -0.707107 -1.96262e-16,
+                          -0.92388 -0.382683 -2.86471e-16,
+                          -0.92388 -0.382683 -2.86471e-16,
+                          -1 -1.11022e-16 -3.33067e-16,
+                          -1 -1.11022e-16 -3.33067e-16,
+                          -1 -1.11022e-16 -3.33067e-16,
+                          -1 -1.11022e-16 -3.33067e-16,
+                          -1 -1.11022e-16 -3.33067e-16,
+                          -1 -1.11022e-16 -3.33067e-16,
+                          -0.92388 -0.382683 -2.86471e-16,
+                          -1 -3.55952e-16 -3.33067e-16,
+                          -1 -3.55952e-16 -3.33067e-16,
+                          4.16334e-16 1 -5.55112e-17,
+                          4.16334e-16 1 -5.55112e-17,
+                          4.16334e-16 1 -5.55112e-17,
+                          4.16334e-16 1 -5.55112e-17,
+                          4.16334e-16 1 -5.55112e-17,
+                          4.16334e-16 1 -5.55112e-17,
+                          4.16334e-16 1 -5.55112e-17,
+                          4.16334e-16 1 -5.55112e-17,
+                          4.16334e-16 1 -5.55112e-17,
+                          4.16334e-16 1 -5.55112e-17,
+                          4.16334e-16 1 -5.55112e-17,
+                          4.16334e-16 1 -5.55112e-17,
+                          4.16334e-16 1 -5.55112e-17,
+                          4.16334e-16 1 -5.55112e-17,
+                          4.16334e-16 1 -5.55112e-17,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -1 1.33907e-16 -3.33067e-16,
+                          -1 1.33907e-16 -3.33067e-16,
+                          -0.809017 0.587785 -3.02085e-16,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -0.809017 -0.587785 -2.36828e-16,
+                          -0.809017 -0.587785 -2.36828e-16,
+                          -1 -1.11022e-16 -3.33067e-16,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -0.809017 -0.587785 -2.36828e-16,
+                          -1 -1.11022e-16 -3.33067e-16,
+                          -1 -1.11022e-16 -3.33067e-16,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -0.809017 0.587785 -3.02085e-16,
+                          -0.809017 0.587785 -3.02085e-16,
+                          -0.309017 0.951057 -1.55718e-16,
+                          -0.809017 0.587785 -3.02085e-16,
+                          -1 1.33907e-16 -3.33067e-16,
+                          -0.809017 0.587785 -3.02085e-16,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -0.309017 0.951057 -1.55718e-16,
+                          -0.309017 0.951057 -1.55718e-16,
+                          0.309017 0.951057 5.01291e-17,
+                          -0.809017 0.587785 -3.02085e-16,
+                          -0.309017 0.951057 -1.55718e-16,
+                          -0.309017 0.951057 -1.55718e-16,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          0.309017 0.951057 5.01291e-17,
+                          0.309017 0.951057 5.01291e-17,
+                          0.809017 0.587785 2.36828e-16,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -0.309017 0.951057 -1.55718e-16,
+                          0.309017 0.951057 5.01291e-17,
+                          0.309017 0.951057 5.01291e-17,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          0.809017 0.587785 2.36828e-16,
+                          0.809017 0.587785 2.36828e-16,
+                          1 -1.14424e-17 3.33067e-16,
+                          0.309017 0.951057 5.01291e-17,
+                          0.809017 0.587785 2.36828e-16,
+                          0.809017 0.587785 2.36828e-16,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          1 -1.14424e-17 3.33067e-16,
+                          1 -1.14424e-17 3.33067e-16,
+                          0.809017 -0.587785 3.02085e-16,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          0.809017 0.587785 2.36828e-16,
+                          1 -1.14424e-17 3.33067e-16,
+                          1 -1.14424e-17 3.33067e-16,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          0.809017 -0.587785 3.02085e-16,
+                          0.809017 -0.587785 3.02085e-16,
+                          0.309017 -0.951057 1.55718e-16,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          1 -1.14424e-17 3.33067e-16,
+                          0.809017 -0.587785 3.02085e-16,
+                          0.809017 -0.587785 3.02085e-16,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          0.309017 -0.951057 1.55718e-16,
+                          0.309017 -0.951057 1.55718e-16,
+                          -0.309017 -0.951057 -5.01291e-17,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          0.809017 -0.587785 3.02085e-16,
+                          0.309017 -0.951057 1.55718e-16,
+                          0.309017 -0.951057 1.55718e-16,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -0.309017 -0.951057 -5.01291e-17,
+                          -0.309017 -0.951057 -5.01291e-17,
+                          -0.809017 -0.587785 -2.36828e-16,
+                          0.309017 -0.951057 1.55718e-16,
+                          -0.309017 -0.951057 -5.01291e-17,
+                          -0.309017 -0.951057 -5.01291e-17,
+                          -0.309017 -0.951057 -5.01291e-17,
+                          -0.809017 -0.587785 -2.36828e-16,
+                          -0.809017 -0.587785 -2.36828e-16,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -4.16334e-16 -1 5.55112e-17,
+                          -4.16334e-16 -1 5.55112e-17,
+                          -4.16334e-16 -1 5.55112e-17,
+                          -0.382683 -0.92388 -7.61736e-17,
+                          -0.382683 -0.92388 -7.61736e-17,
+                          -2.32637e-16 -1 5.55112e-17,
+                          -0.382683 -0.92388 -7.61736e-17,
+                          -2.32637e-16 -1 5.55112e-17,
+                          -2.32637e-16 -1 5.55112e-17,
+                          1 1.11022e-16 3.33067e-16,
+                          1 1.11022e-16 3.33067e-16,
+                          1 1.11022e-16 3.33067e-16,
+                          -4.16334e-16 -1 5.55112e-17,
+                          -4.16334e-16 -1 5.55112e-17,
+                          -4.16334e-16 -1 5.55112e-17,
+                          -4.16334e-16 -1 5.55112e-17,
+                          -4.16334e-16 -1 5.55112e-17,
+                          -4.16334e-16 -1 5.55112e-17,
+                          4.16334e-16 1 -5.55112e-17,
+                          4.16334e-16 1 -5.55112e-17,
+                          4.16334e-16 1 -5.55112e-17,
+                          1 1.11022e-16 3.33067e-16,
+                          1 1.11022e-16 3.33067e-16,
+                          1 1.11022e-16 3.33067e-16,
+                          -1 -1.11022e-16 -3.33067e-16,
+                          -1 -1.11022e-16 -3.33067e-16,
+                          -1 -1.11022e-16 -3.33067e-16,
+                          -1 -1.11022e-16 -3.33067e-16,
+                          -1 -1.11022e-16 -3.33067e-16,
+                          -1 -1.11022e-16 -3.33067e-16,
+                          4.16334e-16 1 -5.55112e-17,
+                          4.16334e-16 1 -5.55112e-17,
+                          4.16334e-16 1 -5.55112e-17,
+                          4.16334e-16 1 -5.55112e-17,
+                          4.16334e-16 1 -5.55112e-17,
+                          4.16334e-16 1 -5.55112e-17,
+                          -1 -3.55952e-16 -3.33067e-16,
+                          -1 -3.55952e-16 -3.33067e-16,
+                          -0.92388 -0.382683 -2.86471e-16,
+                          -0.92388 -0.382683 -2.86471e-16,
+                          -0.92388 -0.382683 -2.86471e-16,
+                          -0.707107 -0.707107 -1.96262e-16,
+                          -0.92388 -0.382683 -2.86471e-16,
+                          -1 -3.55952e-16 -3.33067e-16,
+                          -0.92388 -0.382683 -2.86471e-16,
+                          -0.707107 -0.707107 -1.96262e-16,
+                          -0.707107 -0.707107 -1.96262e-16,
+                          -0.382683 -0.92388 -7.61736e-17,
+                          -0.92388 -0.382683 -2.86471e-16,
+                          -0.707107 -0.707107 -1.96262e-16,
+                          -0.707107 -0.707107 -1.96262e-16,
+                          -0.707107 -0.707107 -1.96262e-16,
+                          -0.382683 -0.92388 -7.61736e-17,
+                          -0.382683 -0.92388 -7.61736e-17,
+                          1 1.11022e-16 3.33067e-16,
+                          1 1.11022e-16 3.33067e-16,
+                          1 1.11022e-16 3.33067e-16,
+                          4.16334e-16 1 -5.55112e-17,
+                          4.16334e-16 1 -5.55112e-17,
+                          4.16334e-16 1 -5.55112e-17,
+                          1 1.11022e-16 3.33067e-16,
+                          1 1.11022e-16 3.33067e-16,
+                          1 1.11022e-16 3.33067e-16,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          4.16334e-16 1 -5.55112e-17,
+                          4.16334e-16 1 -5.55112e-17,
+                          4.16334e-16 1 -5.55112e-17,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -4.16334e-16 -1 5.55112e-17,
+                          -4.16334e-16 -1 5.55112e-17,
+                          -4.16334e-16 -1 5.55112e-17,
+                          -4.16334e-16 -1 5.55112e-17,
+                          -4.16334e-16 -1 5.55112e-17,
+                          -4.16334e-16 -1 5.55112e-17,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          -1 -1.11022e-16 -3.33067e-16,
+                          -1 -1.11022e-16 -3.33067e-16,
+                          -1 -1.11022e-16 -3.33067e-16,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          -1 -1.11022e-16 -3.33067e-16,
+                          -1 -1.11022e-16 -3.33067e-16,
+                          -1 -1.11022e-16 -3.33067e-16,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          -7.21645e-16 2.77556e-16 -1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          7.21645e-16 -2.77556e-16 1,
+                          -1 -1.11022e-16 -3.33067e-16,
+                          -1 -1.11022e-16 -3.33067e-16,
+                          -0.866025 -0.5 -2.60689e-16,
+                          -0.866025 0.5 -3.162e-16,
+                          -0.866025 0.5 -3.162e-16,
+                          -1 1.33907e-16 -3.33067e-16,
+                          -0.866025 0.5 -3.162e-16,
+                          -1 1.33907e-16 -3.33067e-16,
+                          -1 1.33907e-16 -3.33067e-16,
+                          -0.866025 -0.5 -2.60689e-16,
+                          -0.866025 -0.5 -2.60689e-16,
+                          -0.5 -0.866025 -1.18459e-16,
+                          -0.866025 -0.5 -2.60689e-16,
+                          -1 -1.11022e-16 -3.33067e-16,
+                          -0.866025 -0.5 -2.60689e-16,
+                          -0.5 -0.866025 -1.18459e-16,
+                          -0.5 -0.866025 -1.18459e-16,
+                          4.40742e-15 -1 5.55112e-17,
+                          -0.866025 -0.5 -2.60689e-16,
+                          -0.5 -0.866025 -1.18459e-16,
+                          -0.5 -0.866025 -1.18459e-16,
+                          4.40742e-15 -1 5.55112e-17,
+                          4.40742e-15 -1 5.55112e-17,
+                          0.5 -0.866025 2.14608e-16,
+                          -0.5 -0.866025 -1.18459e-16,
+                          4.40742e-15 -1 5.55112e-17,
+                          4.40742e-15 -1 5.55112e-17,
+                          0.5 -0.866025 2.14608e-16,
+                          0.5 -0.866025 2.14608e-16,
+                          0.866025 -0.5 3.162e-16,
+                          4.40742e-15 -1 5.55112e-17,
+                          0.5 -0.866025 2.14608e-16,
+                          0.5 -0.866025 2.14608e-16,
+                          0.866025 -0.5 3.162e-16,
+                          0.866025 -0.5 3.162e-16,
+                          1 -1.14424e-17 3.33067e-16,
+                          0.5 -0.866025 2.14608e-16,
+                          0.866025 -0.5 3.162e-16,
+                          0.866025 -0.5 3.162e-16,
+                          1 -1.14424e-17 3.33067e-16,
+                          1 -1.14424e-17 3.33067e-16,
+                          0.866025 0.5 2.60689e-16,
+                          0.866025 -0.5 3.162e-16,
+                          1 -1.14424e-17 3.33067e-16,
+                          1 -1.14424e-17 3.33067e-16,
+                          0.866025 0.5 2.60689e-16,
+                          0.866025 0.5 2.60689e-16,
+                          0.5 0.866025 1.18459e-16,
+                          1 -1.14424e-17 3.33067e-16,
+                          0.866025 0.5 2.60689e-16,
+                          0.866025 0.5 2.60689e-16,
+                          0.5 0.866025 1.18459e-16,
+                          0.5 0.866025 1.18459e-16,
+                          -1.17633e-15 1 -5.55112e-17,
+                          0.866025 0.5 2.60689e-16,
+                          0.5 0.866025 1.18459e-16,
+                          0.5 0.866025 1.18459e-16,
+                          -1.17633e-15 1 -5.55112e-17,
+                          -1.17633e-15 1 -5.55112e-17,
+                          -0.5 0.866025 -2.14608e-16,
+                          0.5 0.866025 1.18459e-16,
+                          -1.17633e-15 1 -5.55112e-17,
+                          -1.17633e-15 1 -5.55112e-17,
+                          -0.5 0.866025 -2.14608e-16,
+                          -0.5 0.866025 -2.14608e-16,
+                          -0.866025 0.5 -3.162e-16,
+                          -1.17633e-15 1 -5.55112e-17,
+                          -0.5 0.866025 -2.14608e-16,
+                          -0.5 0.866025 -2.14608e-16,
+                          -0.5 0.866025 -2.14608e-16,
+                          -0.866025 0.5 -3.162e-16,
+                          -0.866025 0.5 -3.162e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -0.856699 -2.0597 5,
+                          -0.598674 -0.434958 5,
+                          -0.74 6.5602e-14 5,
+                          -0.74 6.64568e-14 2.8,
+                          -0.74 6.5602e-14 5,
+                          -0.598674 -0.434958 5,
+                          -2.4 2.25 5,
+                          -0.74 6.5602e-14 5,
+                          -0.598674 0.434958 5,
+                          -0.598674 0.434958 2.8,
+                          -0.598674 0.434958 5,
+                          -0.74 6.5602e-14 5,
+                          -2.4 2.25 5,
+                          -0.856699 -2.0597 5,
+                          -0.74 6.5602e-14 5,
+                          -0.598674 0.434958 2.8,
+                          -0.74 6.5602e-14 5,
+                          -0.74 6.64568e-14 2.8,
+                          0.1 -2.25 5,
+                          -0.228666 -0.703784 5,
+                          -0.598674 -0.434958 5,
+                          -0.598674 -0.434958 2.8,
+                          -0.598674 -0.434958 5,
+                          -0.228666 -0.703784 5,
+                          -0.856699 -2.0597 5,
+                          0.1 -2.25 5,
+                          -0.598674 -0.434958 5,
+                          -0.598674 -0.434958 2.8,
+                          -0.74 6.64568e-14 2.8,
+                          -0.598674 -0.434958 5,
+                          0.1 -2.25 5,
+                          0.228666 -0.703784 5,
+                          -0.228666 -0.703784 5,
+                          -0.228666 -0.703784 2.8,
+                          -0.228666 -0.703784 5,
+                          0.228666 -0.703784 5,
+                          -0.598674 -0.434958 2.8,
+                          -0.228666 -0.703784 5,
+                          -0.228666 -0.703784 2.8,
+                          37.6 -2.25 5,
+                          0.598674 -0.434958 5,
+                          0.228666 -0.703784 5,
+                          0.228666 -0.703784 2.8,
+                          0.228666 -0.703784 5,
+                          0.598674 -0.434958 5,
+                          0.1 -2.25 5,
+                          37.6 -2.25 5,
+                          0.228666 -0.703784 5,
+                          -0.228666 -0.703784 2.8,
+                          0.228666 -0.703784 5,
+                          0.228666 -0.703784 2.8,
+                          37.6 -2.25 5,
+                          0.74 6.58484e-14 5,
+                          0.598674 -0.434958 5,
+                          0.598674 -0.434958 2.8,
+                          0.598674 -0.434958 5,
+                          0.74 6.58484e-14 5,
+                          0.228666 -0.703784 2.8,
+                          0.598674 -0.434958 5,
+                          0.598674 -0.434958 2.8,
+                          37.6 -2.25 5,
+                          0.598674 0.434958 5,
+                          0.74 6.58484e-14 5,
+                          0.74 6.67033e-14 2.8,
+                          0.74 6.58484e-14 5,
+                          0.598674 0.434958 5,
+                          0.598674 -0.434958 2.8,
+                          0.74 6.58484e-14 5,
+                          0.74 6.67033e-14 2.8,
+                          37.6 -2.25 5,
+                          0.228666 0.703784 5,
+                          0.598674 0.434958 5,
+                          0.598674 0.434958 2.8,
+                          0.598674 0.434958 5,
+                          0.228666 0.703784 5,
+                          0.74 6.67033e-14 2.8,
+                          0.598674 0.434958 5,
+                          0.598674 0.434958 2.8,
+                          -2.4 2.25 5,
+                          -0.228666 0.703784 5,
+                          0.228666 0.703784 5,
+                          0.228666 0.703784 2.8,
+                          0.228666 0.703784 5,
+                          -0.228666 0.703784 5,
+                          -2.4 2.25 5,
+                          0.228666 0.703784 5,
+                          37.6 -2.25 5,
+                          0.598674 0.434958 2.8,
+                          0.228666 0.703784 5,
+                          0.228666 0.703784 2.8,
+                          -2.4 2.25 5,
+                          -0.598674 0.434958 5,
+                          -0.228666 0.703784 5,
+                          -0.228666 0.703784 2.8,
+                          -0.228666 0.703784 5,
+                          -0.598674 0.434958 5,
+                          0.228666 0.703784 2.8,
+                          -0.228666 0.703784 5,
+                          -0.228666 0.703784 2.8,
+                          -0.228666 0.703784 2.8,
+                          -0.598674 0.434958 5,
+                          -0.598674 0.434958 2.8,
+                          37.6 -2.25 2.5,
+                          37.6 -2.25 5,
+                          0.1 -2.25 5,
+                          37.6 2.25 5,
+                          -2.4 2.25 5,
+                          37.6 -2.25 5,
+                          37.6 2.25 2.5,
+                          37.6 2.25 5,
+                          37.6 -2.25 5,
+                          37.6 2.25 2.5,
+                          37.6 -2.25 5,
+                          37.6 -2.25 2.5,
+                          0.1 -2.25 2.8,
+                          0.1 -2.25 5,
+                          -0.856699 -2.0597 5,
+                          37.6 -2.25 -2.5,
+                          0.1 -2.25 5,
+                          37.6 -2.25 -5,
+                          2.25 -2.25 2.8,
+                          37.6 -2.25 -5,
+                          0.1 -2.25 5,
+                          2.25 -2.25 2.8,
+                          0.1 -2.25 5,
+                          0.1 -2.25 2.8,
+                          37.6 -2.25 -2.5,
+                          37.6 -2.25 2.5,
+                          0.1 -2.25 5,
+                          -2.4 2.25 5,
+                          -1.66777 -1.51777 5,
+                          -0.856699 -2.0597 5,
+                          -0.856699 -2.0597 2.8,
+                          -0.856699 -2.0597 5,
+                          -1.66777 -1.51777 5,
+                          -0.856699 -2.0597 2.8,
+                          0.1 -2.25 2.8,
+                          -0.856699 -2.0597 5,
+                          -2.4 2.25 5,
+                          -2.2097 -0.706699 5,
+                          -1.66777 -1.51777 5,
+                          -1.66777 -1.51777 2.8,
+                          -1.66777 -1.51777 5,
+                          -2.2097 -0.706699 5,
+                          -0.856699 -2.0597 2.8,
+                          -1.66777 -1.51777 5,
+                          -1.66777 -1.51777 2.8,
+                          -2.4 2.25 5,
+                          -2.4 0.25 5,
+                          -2.2097 -0.706699 5,
+                          -2.2097 -0.706699 2.8,
+                          -2.2097 -0.706699 5,
+                          -2.4 0.25 5,
+                          -1.66777 -1.51777 2.8,
+                          -2.2097 -0.706699 5,
+                          -2.2097 -0.706699 2.8,
+                          -2.4 2.25 2.8,
+                          -2.4 0.25 5,
+                          -2.4 2.25 5,
+                          -2.4 2.25 2.8,
+                          -2.4 0.25 2.8,
+                          -2.4 0.25 5,
+                          -2.2097 -0.706699 2.8,
+                          -2.4 0.25 5,
+                          -2.4 0.25 2.8,
+                          -2.4 2.25 2.8,
+                          -2.4 2.25 5,
+                          37.6 2.25 5,
+                          2.25 2.25 -2.8,
+                          37.6 2.25 5,
+                          -2.4 2.25 -5,
+                          37.6 2.25 2.5,
+                          -2.4 2.25 -5,
+                          37.6 2.25 5,
+                          2.25 2.25 2.8,
+                          -2.4 2.25 2.8,
+                          37.6 2.25 5,
+                          2.25 2.25 -2.8,
+                          2.25 2.25 2.8,
+                          37.6 2.25 5,
+                          0.1 -2.25 -5,
+                          0.606764 -0.440835 -5,
+                          0.75 6.97359e-14 -5,
+                          0.75 6.8881e-14 -2.8,
+                          0.75 6.97359e-14 -5,
+                          0.606764 -0.440835 -5,
+                          37.6 2.25 -5,
+                          0.75 6.97359e-14 -5,
+                          0.606764 0.440835 -5,
+                          0.606764 0.440835 -2.8,
+                          0.606764 0.440835 -5,
+                          0.75 6.97359e-14 -5,
+                          37.6 2.25 -5,
+                          0.1 -2.25 -5,
+                          0.75 6.97359e-14 -5,
+                          0.606764 0.440835 -2.8,
+                          0.75 6.97359e-14 -5,
+                          0.75 6.8881e-14 -2.8,
+                          0.1 -2.25 -5,
+                          0.231756 -0.713294 -5,
+                          0.606764 -0.440835 -5,
+                          0.606764 -0.440835 -2.8,
+                          0.606764 -0.440835 -5,
+                          0.231756 -0.713294 -5,
+                          0.606764 -0.440835 -2.8,
+                          0.75 6.8881e-14 -2.8,
+                          0.606764 -0.440835 -5,
+                          0.1 -2.25 -5,
+                          -0.231756 -0.713294 -5,
+                          0.231756 -0.713294 -5,
+                          0.231756 -0.713294 -2.8,
+                          0.231756 -0.713294 -5,
+                          -0.231756 -0.713294 -5,
+                          0.606764 -0.440835 -2.8,
+                          0.231756 -0.713294 -5,
+                          0.231756 -0.713294 -2.8,
+                          -0.856699 -2.0597 -5,
+                          -0.606764 -0.440835 -5,
+                          -0.231756 -0.713294 -5,
+                          -0.231756 -0.713294 -2.8,
+                          -0.231756 -0.713294 -5,
+                          -0.606764 -0.440835 -5,
+                          -0.856699 -2.0597 -5,
+                          -0.231756 -0.713294 -5,
+                          0.1 -2.25 -5,
+                          0.231756 -0.713294 -2.8,
+                          -0.231756 -0.713294 -5,
+                          -0.231756 -0.713294 -2.8,
+                          -0.856699 -2.0597 -5,
+                          -0.75 6.94861e-14 -5,
+                          -0.606764 -0.440835 -5,
+                          -0.606764 -0.440835 -2.8,
+                          -0.606764 -0.440835 -5,
+                          -0.75 6.94861e-14 -5,
+                          -0.231756 -0.713294 -2.8,
+                          -0.606764 -0.440835 -5,
+                          -0.606764 -0.440835 -2.8,
+                          -1.66777 -1.51777 -5,
+                          -0.606764 0.440835 -5,
+                          -0.75 6.94861e-14 -5,
+                          -0.75 6.86312e-14 -2.8,
+                          -0.75 6.94861e-14 -5,
+                          -0.606764 0.440835 -5,
+                          -0.856699 -2.0597 -5,
+                          -1.66777 -1.51777 -5,
+                          -0.75 6.94861e-14 -5,
+                          -0.606764 -0.440835 -2.8,
+                          -0.75 6.94861e-14 -5,
+                          -0.75 6.86312e-14 -2.8,
+                          -2.2097 -0.706699 -5,
+                          -0.231756 0.713294 -5,
+                          -0.606764 0.440835 -5,
+                          -0.606764 0.440835 -2.8,
+                          -0.606764 0.440835 -5,
+                          -0.231756 0.713294 -5,
+                          -1.66777 -1.51777 -5,
+                          -2.2097 -0.706699 -5,
+                          -0.606764 0.440835 -5,
+                          -0.75 6.86312e-14 -2.8,
+                          -0.606764 0.440835 -5,
+                          -0.606764 0.440835 -2.8,
+                          37.6 2.25 -5,
+                          0.231756 0.713294 -5,
+                          -0.231756 0.713294 -5,
+                          -0.231756 0.713294 -2.8,
+                          -0.231756 0.713294 -5,
+                          0.231756 0.713294 -5,
+                          -2.4 2.25 -5,
+                          37.6 2.25 -5,
+                          -0.231756 0.713294 -5,
+                          -2.4 0.25 -5,
+                          -2.4 2.25 -5,
+                          -0.231756 0.713294 -5,
+                          -2.2097 -0.706699 -5,
+                          -2.4 0.25 -5,
+                          -0.231756 0.713294 -5,
+                          -0.606764 0.440835 -2.8,
+                          -0.231756 0.713294 -5,
+                          -0.231756 0.713294 -2.8,
+                          37.6 2.25 -5,
+                          0.606764 0.440835 -5,
+                          0.231756 0.713294 -5,
+                          0.231756 0.713294 -2.8,
+                          0.231756 0.713294 -5,
+                          0.606764 0.440835 -5,
+                          -0.231756 0.713294 -2.8,
+                          0.231756 0.713294 -5,
+                          0.231756 0.713294 -2.8,
+                          0.231756 0.713294 -2.8,
+                          0.606764 0.440835 -5,
+                          0.606764 0.440835 -2.8,
+                          37.6 2.25 -5,
+                          37.6 -2.25 -5,
+                          0.1 -2.25 -5,
+                          0.1 -2.25 -2.8,
+                          0.1 -2.25 -5,
+                          37.6 -2.25 -5,
+                          -0.856699 -2.0597 -2.8,
+                          -0.856699 -2.0597 -5,
+                          0.1 -2.25 -5,
+                          -0.856699 -2.0597 -2.8,
+                          0.1 -2.25 -5,
+                          0.1 -2.25 -2.8,
+                          37.6 -2.25 -2.5,
+                          37.6 -2.25 -5,
+                          37.6 2.25 -5,
+                          2.25 -2.25 -2.8,
+                          0.1 -2.25 -2.8,
+                          37.6 -2.25 -5,
+                          2.25 -2.25 2.8,
+                          2.25 -2.25 -2.8,
+                          37.6 -2.25 -5,
+                          37.6 2.25 -2.5,
+                          37.6 2.25 -5,
+                          -2.4 2.25 -5,
+                          37.6 2.25 -2.5,
+                          37.6 -2.25 -2.5,
+                          37.6 2.25 -5,
+                          -2.4 0.25 -2.8,
+                          -2.4 2.25 -5,
+                          -2.4 0.25 -5,
+                          -2.4 2.25 -2.8,
+                          -2.4 2.25 -5,
+                          -2.4 0.25 -2.8,
+                          2.25 2.25 -2.8,
+                          -2.4 2.25 -5,
+                          -2.4 2.25 -2.8,
+                          37.6 2.25 2.5,
+                          37.6 2.25 -2.5,
+                          -2.4 2.25 -5,
+                          -2.4 0.25 -2.8,
+                          -2.4 0.25 -5,
+                          -2.2097 -0.706699 -5,
+                          -2.2097 -0.706699 -2.8,
+                          -2.2097 -0.706699 -5,
+                          -1.66777 -1.51777 -5,
+                          -2.2097 -0.706699 -2.8,
+                          -2.4 0.25 -2.8,
+                          -2.2097 -0.706699 -5,
+                          -1.66777 -1.51777 -2.8,
+                          -1.66777 -1.51777 -5,
+                          -0.856699 -2.0597 -5,
+                          -2.2097 -0.706699 -2.8,
+                          -1.66777 -1.51777 -5,
+                          -1.66777 -1.51777 -2.8,
+                          -1.66777 -1.51777 -2.8,
+                          -0.856699 -2.0597 -5,
+                          -0.856699 -2.0597 -2.8,
+                          42.25 -2.25 -2.5,
+                          42.25 2.25 -2.5,
+                          42.25 2.25 2.5,
+                          37.6 2.25 -2.5,
+                          42.25 2.25 2.5,
+                          42.25 2.25 -2.5,
+                          42.25 -2.25 2.5,
+                          42.25 -2.25 -2.5,
+                          42.25 2.25 2.5,
+                          40.9093 0.525005 2.5,
+                          42.25 -2.25 2.5,
+                          42.25 2.25 2.5,
+                          37.6 2.25 2.5,
+                          42.25 2.25 2.5,
+                          37.6 2.25 -2.5,
+                          40.525 0.909323 2.5,
+                          42.25 2.25 2.5,
+                          37.6 2.25 2.5,
+                          40.525 0.909323 2.5,
+                          40.9093 0.525005 2.5,
+                          42.25 2.25 2.5,
+                          40.9093 -0.525005 -2.5,
+                          42.25 2.25 -2.5,
+                          42.25 -2.25 -2.5,
+                          39.475 0.909323 -2.5,
+                          37.6 2.25 -2.5,
+                          42.25 2.25 -2.5,
+                          40.9093 -0.525005 -2.5,
+                          41.05 7.54757e-14 -2.5,
+                          42.25 2.25 -2.5,
+                          40.9093 0.525005 -2.5,
+                          42.25 2.25 -2.5,
+                          41.05 7.54757e-14 -2.5,
+                          40 1.05 -2.5,
+                          39.475 0.909323 -2.5,
+                          42.25 2.25 -2.5,
+                          40.525 0.909323 -2.5,
+                          40 1.05 -2.5,
+                          42.25 2.25 -2.5,
+                          40.9093 0.525005 -2.5,
+                          40.525 0.909323 -2.5,
+                          42.25 2.25 -2.5,
+                          37.6 -2.25 2.5,
+                          42.25 -2.25 -2.5,
+                          42.25 -2.25 2.5,
+                          37.6 -2.25 -2.5,
+                          42.25 -2.25 -2.5,
+                          37.6 -2.25 2.5,
+                          40.525 -0.909323 -2.5,
+                          42.25 -2.25 -2.5,
+                          37.6 -2.25 -2.5,
+                          40.525 -0.909323 -2.5,
+                          40.9093 -0.525005 -2.5,
+                          42.25 -2.25 -2.5,
+                          39.475 -0.909323 2.5,
+                          37.6 -2.25 2.5,
+                          42.25 -2.25 2.5,
+                          40.9093 0.525005 2.5,
+                          41.05 7.35328e-14 2.5,
+                          42.25 -2.25 2.5,
+                          40.9093 -0.525005 2.5,
+                          42.25 -2.25 2.5,
+                          41.05 7.35328e-14 2.5,
+                          40 -1.05 2.5,
+                          39.475 -0.909323 2.5,
+                          42.25 -2.25 2.5,
+                          40.525 -0.909323 2.5,
+                          40 -1.05 2.5,
+                          42.25 -2.25 2.5,
+                          40.9093 -0.525005 2.5,
+                          40.525 -0.909323 2.5,
+                          42.25 -2.25 2.5,
+                          2.25 2.25 2.8,
+                          2.25 -2.25 2.8,
+                          0.1 -2.25 2.8,
+                          0.74 6.67033e-14 2.8,
+                          2.25 2.25 2.8,
+                          0.1 -2.25 2.8,
+                          0.598674 -0.434958 2.8,
+                          0.74 6.67033e-14 2.8,
+                          0.1 -2.25 2.8,
+                          0.228666 -0.703784 2.8,
+                          0.598674 -0.434958 2.8,
+                          0.1 -2.25 2.8,
+                          -0.228666 -0.703784 2.8,
+                          0.228666 -0.703784 2.8,
+                          0.1 -2.25 2.8,
+                          -0.856699 -2.0597 2.8,
+                          -0.228666 -0.703784 2.8,
+                          0.1 -2.25 2.8,
+                          39.0907 -0.525005 2.5,
+                          37.6 2.25 2.5,
+                          37.6 -2.25 2.5,
+                          39.475 -0.909323 2.5,
+                          39.0907 -0.525005 2.5,
+                          37.6 -2.25 2.5,
+                          39.0907 0.525005 -2.5,
+                          37.6 -2.25 -2.5,
+                          37.6 2.25 -2.5,
+                          40 -1.05 -2.5,
+                          40.525 -0.909323 -2.5,
+                          37.6 -2.25 -2.5,
+                          39.475 -0.909323 -2.5,
+                          40 -1.05 -2.5,
+                          37.6 -2.25 -2.5,
+                          39.0907 -0.525005 -2.5,
+                          39.475 -0.909323 -2.5,
+                          37.6 -2.25 -2.5,
+                          38.95 7.5126e-14 -2.5,
+                          39.0907 -0.525005 -2.5,
+                          37.6 -2.25 -2.5,
+                          39.0907 0.525005 -2.5,
+                          38.95 7.5126e-14 -2.5,
+                          37.6 -2.25 -2.5,
+                          0.231756 -0.713294 -2.8,
+                          0.1 -2.25 -2.8,
+                          2.25 -2.25 -2.8,
+                          -0.231756 -0.713294 -2.8,
+                          -0.606764 -0.440835 -2.8,
+                          0.1 -2.25 -2.8,
+                          -0.856699 -2.0597 -2.8,
+                          0.1 -2.25 -2.8,
+                          -0.606764 -0.440835 -2.8,
+                          0.231756 -0.713294 -2.8,
+                          -0.231756 -0.713294 -2.8,
+                          0.1 -2.25 -2.8,
+                          2.25 2.25 -2.8,
+                          2.25 -2.25 -2.8,
+                          2.25 -2.25 2.8,
+                          0.606764 0.440835 -2.8,
+                          2.25 -2.25 -2.8,
+                          2.25 2.25 -2.8,
+                          0.606764 0.440835 -2.8,
+                          0.75 6.8881e-14 -2.8,
+                          2.25 -2.25 -2.8,
+                          0.606764 -0.440835 -2.8,
+                          2.25 -2.25 -2.8,
+                          0.75 6.8881e-14 -2.8,
+                          0.606764 -0.440835 -2.8,
+                          0.231756 -0.713294 -2.8,
+                          2.25 -2.25 -2.8,
+                          2.25 2.25 -2.8,
+                          2.25 -2.25 2.8,
+                          2.25 2.25 2.8,
+                          2.25 2.25 2.8,
+                          -2.4 0.25 2.8,
+                          -2.4 2.25 2.8,
+                          -0.228666 0.703784 2.8,
+                          -2.4 0.25 2.8,
+                          2.25 2.25 2.8,
+                          -2.2097 -0.706699 2.8,
+                          -2.4 0.25 2.8,
+                          -0.228666 0.703784 2.8,
+                          -2.2097 -0.706699 -2.8,
+                          -2.4 2.25 -2.8,
+                          -2.4 0.25 -2.8,
+                          0.231756 0.713294 -2.8,
+                          2.25 2.25 -2.8,
+                          -2.4 2.25 -2.8,
+                          -0.231756 0.713294 -2.8,
+                          0.231756 0.713294 -2.8,
+                          -2.4 2.25 -2.8,
+                          -0.606764 0.440835 -2.8,
+                          -0.231756 0.713294 -2.8,
+                          -2.4 2.25 -2.8,
+                          -0.75 6.86312e-14 -2.8,
+                          -0.606764 0.440835 -2.8,
+                          -2.4 2.25 -2.8,
+                          -0.856699 -2.0597 -2.8,
+                          -0.75 6.86312e-14 -2.8,
+                          -2.4 2.25 -2.8,
+                          -1.66777 -1.51777 -2.8,
+                          -0.856699 -2.0597 -2.8,
+                          -2.4 2.25 -2.8,
+                          -2.2097 -0.706699 -2.8,
+                          -1.66777 -1.51777 -2.8,
+                          -2.4 2.25 -2.8,
+                          0.228666 0.703784 2.8,
+                          -0.228666 0.703784 2.8,
+                          2.25 2.25 2.8,
+                          0.598674 0.434958 2.8,
+                          0.228666 0.703784 2.8,
+                          2.25 2.25 2.8,
+                          0.74 6.67033e-14 2.8,
+                          0.598674 0.434958 2.8,
+                          2.25 2.25 2.8,
+                          0.231756 0.713294 -2.8,
+                          0.606764 0.440835 -2.8,
+                          2.25 2.25 -2.8,
+                          39.475 0.909323 -2.5,
+                          39.0907 0.525005 -2.5,
+                          37.6 2.25 -2.5,
+                          40 1.05 2.5,
+                          40.525 0.909323 2.5,
+                          37.6 2.25 2.5,
+                          39.475 0.909323 2.5,
+                          40 1.05 2.5,
+                          37.6 2.25 2.5,
+                          39.0907 0.525005 2.5,
+                          39.475 0.909323 2.5,
+                          37.6 2.25 2.5,
+                          38.95 7.31831e-14 2.5,
+                          39.0907 0.525005 2.5,
+                          37.6 2.25 2.5,
+                          39.0907 -0.525005 2.5,
+                          38.95 7.31831e-14 2.5,
+                          37.6 2.25 2.5,
+                          -1.66777 -1.51777 2.8,
+                          -0.598674 0.434958 2.8,
+                          -0.74 6.64568e-14 2.8,
+                          -0.856699 -2.0597 2.8,
+                          -0.74 6.64568e-14 2.8,
+                          -0.598674 -0.434958 2.8,
+                          -0.856699 -2.0597 2.8,
+                          -1.66777 -1.51777 2.8,
+                          -0.74 6.64568e-14 2.8,
+                          -2.2097 -0.706699 2.8,
+                          -0.228666 0.703784 2.8,
+                          -0.598674 0.434958 2.8,
+                          -1.66777 -1.51777 2.8,
+                          -2.2097 -0.706699 2.8,
+                          -0.598674 0.434958 2.8,
+                          -0.856699 -2.0597 2.8,
+                          -0.598674 -0.434958 2.8,
+                          -0.228666 -0.703784 2.8,
+                          -0.856699 -2.0597 -2.8,
+                          -0.606764 -0.440835 -2.8,
+                          -0.75 6.86312e-14 -2.8,
+                          41.05 7.54757e-14 -2.5,
+                          41.05 7.35328e-14 2.5,
+                          40.9093 0.525005 2.5,
+                          40.9093 -0.525005 -2.5,
+                          40.9093 -0.525005 2.5,
+                          41.05 7.35328e-14 2.5,
+                          40.9093 -0.525005 -2.5,
+                          41.05 7.35328e-14 2.5,
+                          41.05 7.54757e-14 -2.5,
+                          40.9093 0.525005 -2.5,
+                          40.9093 0.525005 2.5,
+                          40.525 0.909323 2.5,
+                          40.9093 0.525005 -2.5,
+                          41.05 7.54757e-14 -2.5,
+                          40.9093 0.525005 2.5,
+                          40.525 0.909323 -2.5,
+                          40.525 0.909323 2.5,
+                          40 1.05 2.5,
+                          40.9093 0.525005 -2.5,
+                          40.525 0.909323 2.5,
+                          40.525 0.909323 -2.5,
+                          40 1.05 -2.5,
+                          40 1.05 2.5,
+                          39.475 0.909323 2.5,
+                          40.525 0.909323 -2.5,
+                          40 1.05 2.5,
+                          40 1.05 -2.5,
+                          39.475 0.909323 -2.5,
+                          39.475 0.909323 2.5,
+                          39.0907 0.525005 2.5,
+                          40 1.05 -2.5,
+                          39.475 0.909323 2.5,
+                          39.475 0.909323 -2.5,
+                          39.0907 0.525005 -2.5,
+                          39.0907 0.525005 2.5,
+                          38.95 7.31831e-14 2.5,
+                          39.475 0.909323 -2.5,
+                          39.0907 0.525005 2.5,
+                          39.0907 0.525005 -2.5,
+                          38.95 7.5126e-14 -2.5,
+                          38.95 7.31831e-14 2.5,
+                          39.0907 -0.525005 2.5,
+                          39.0907 0.525005 -2.5,
+                          38.95 7.31831e-14 2.5,
+                          38.95 7.5126e-14 -2.5,
+                          39.0907 -0.525005 -2.5,
+                          39.0907 -0.525005 2.5,
+                          39.475 -0.909323 2.5,
+                          38.95 7.5126e-14 -2.5,
+                          39.0907 -0.525005 2.5,
+                          39.0907 -0.525005 -2.5,
+                          39.475 -0.909323 -2.5,
+                          39.475 -0.909323 2.5,
+                          40 -1.05 2.5,
+                          39.0907 -0.525005 -2.5,
+                          39.475 -0.909323 2.5,
+                          39.475 -0.909323 -2.5,
+                          40 -1.05 -2.5,
+                          40 -1.05 2.5,
+                          40.525 -0.909323 2.5,
+                          39.475 -0.909323 -2.5,
+                          40 -1.05 2.5,
+                          40 -1.05 -2.5,
+                          40.525 -0.909323 -2.5,
+                          40.525 -0.909323 2.5,
+                          40.9093 -0.525005 2.5,
+                          40 -1.05 -2.5,
+                          40.525 -0.909323 2.5,
+                          40.525 -0.909323 -2.5,
+                          40.525 -0.909323 -2.5,
+                          40.9093 -0.525005 2.5,
+                          40.9093 -0.525005 -2.5 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          -2.22045e-16 -1 -2.30287e-17,
+                          -2.22045e-16 -1 -2.30287e-17,
+                          -2.22045e-16 -1 -2.30287e-17,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1 -1.11022e-16 -9.16756e-17,
+                          1 -1.11022e-16 -9.16756e-17,
+                          1 -1.11022e-16 -9.16756e-17,
+                          1 -1.11022e-16 -9.16756e-17,
+                          1 -1.11022e-16 -9.16756e-17,
+                          1 -1.11022e-16 -9.16756e-17,
+                          -0.707107 -1.11879e-17 0.707107,
+                          -0.707107 -1.11879e-17 0.707107,
+                          -0.707107 -1.11879e-17 0.707107,
+                          -2.22045e-16 -1 -2.30287e-17,
+                          -2.22045e-16 -1 -2.30287e-17,
+                          -2.22045e-16 -1 -2.30287e-17,
+                          -2.22045e-16 -1 -2.30287e-17,
+                          -2.22045e-16 -1 -2.30287e-17,
+                          -2.22045e-16 -1 -2.30287e-17,
+                          -2.22045e-16 -1 -2.30287e-17,
+                          -2.22045e-16 -1 -2.30287e-17,
+                          -2.22045e-16 -1 -2.30287e-17,
+                          -2.22045e-16 -1 -2.30287e-17,
+                          -2.22045e-16 -1 -2.30287e-17,
+                          -2.22045e-16 -1 -2.30287e-17,
+                          2.22045e-16 1 2.30287e-17,
+                          2.22045e-16 1 2.30287e-17,
+                          2.22045e-16 1 2.30287e-17,
+                          -0.707107 -1.11879e-17 0.707107,
+                          -0.707107 -1.11879e-17 0.707107,
+                          -0.707107 -1.11879e-17 0.707107,
+                          2.22045e-16 1 2.30287e-17,
+                          2.22045e-16 1 2.30287e-17,
+                          2.22045e-16 1 2.30287e-17,
+                          2.22045e-16 1 2.30287e-17,
+                          2.22045e-16 1 2.30287e-17,
+                          2.22045e-16 1 2.30287e-17,
+                          2.22045e-16 1 2.30287e-17,
+                          2.22045e-16 1 2.30287e-17,
+                          2.22045e-16 1 2.30287e-17,
+                          1 -1.11022e-16 -9.16756e-17,
+                          1 -1.11022e-16 -9.16756e-17,
+                          1 -1.11022e-16 -9.16756e-17,
+                          2.22045e-16 1 2.30287e-17,
+                          2.22045e-16 1 2.30287e-17,
+                          2.22045e-16 1 2.30287e-17,
+                          1 -1.11022e-16 -9.16756e-17,
+                          1 -1.11022e-16 -9.16756e-17,
+                          1 -1.11022e-16 -9.16756e-17,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          2.22045e-16 1 2.30287e-17,
+                          2.22045e-16 1 2.30287e-17,
+                          2.22045e-16 1 2.30287e-17,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -2.22045e-16 -1 -2.30287e-17,
+                          -2.22045e-16 -1 -2.30287e-17,
+                          -2.22045e-16 -1 -2.30287e-17,
+                          -2.22045e-16 -1 -2.30287e-17,
+                          -2.22045e-16 -1 -2.30287e-17,
+                          -2.22045e-16 -1 -2.30287e-17,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1 -1.11022e-16 -9.16756e-17,
+                          1 -1.11022e-16 -9.16756e-17,
+                          1 -1.11022e-16 -9.16756e-17,
+                          1 -1.11022e-16 -9.16756e-17,
+                          1 -1.11022e-16 -9.16756e-17,
+                          1 -1.11022e-16 -9.16756e-17,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -2.22045e-16 -1 -2.30287e-17,
+                          -2.22045e-16 -1 -2.30287e-17,
+                          -2.22045e-16 -1 -2.30287e-17,
+                          -0.707107 1.68197e-16 -0.707107,
+                          -0.707107 1.68197e-16 -0.707107,
+                          -0.707107 1.68197e-16 -0.707107,
+                          -0.707107 1.68197e-16 -0.707107,
+                          -0.707107 1.68197e-16 -0.707107,
+                          -0.707107 1.68197e-16 -0.707107,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1 1.11022e-16 9.16756e-17,
+                          -1 1.11022e-16 9.16756e-17,
+                          -1 1.11022e-16 9.16756e-17,
+                          -1 1.11022e-16 9.16756e-17,
+                          -1 1.11022e-16 9.16756e-17,
+                          -1 1.11022e-16 9.16756e-17,
+                          2.22045e-16 1 2.30287e-17,
+                          2.22045e-16 1 2.30287e-17,
+                          2.22045e-16 1 2.30287e-17,
+                          2.22045e-16 1 2.30287e-17,
+                          2.22045e-16 1 2.30287e-17,
+                          2.22045e-16 1 2.30287e-17,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          -1.30665e-16 1.26844e-16 -1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          1.30665e-16 -1.26844e-16 1,
+                          -1 1.11022e-16 9.16756e-17,
+                          -1 1.11022e-16 9.16756e-17,
+                          -0.866025 -0.5 6.7879e-17,
+                          -0.866025 0.5 9.09077e-17,
+                          -0.866025 0.5 9.09077e-17,
+                          -1 3.55952e-16 9.16756e-17,
+                          -0.866025 0.5 9.09077e-17,
+                          -1 3.55952e-16 9.16756e-17,
+                          -1 3.55952e-16 9.16756e-17,
+                          -0.866025 -0.5 6.7879e-17,
+                          -0.866025 -0.5 6.7879e-17,
+                          -0.5 -0.866025 2.58943e-17,
+                          -0.866025 -0.5 6.7879e-17,
+                          -1 1.11022e-16 9.16756e-17,
+                          -0.866025 -0.5 6.7879e-17,
+                          -0.5 -0.866025 2.58943e-17,
+                          -0.5 -0.866025 2.58943e-17,
+                          -2.05963e-15 -1 -2.30287e-17,
+                          -0.866025 -0.5 6.7879e-17,
+                          -0.5 -0.866025 2.58943e-17,
+                          -0.5 -0.866025 2.58943e-17,
+                          -1.83759e-15 -1 -2.30287e-17,
+                          -2.05963e-15 -1 -2.30287e-17,
+                          0.5 -0.866025 -6.57812e-17,
+                          -0.5 -0.866025 2.58943e-17,
+                          -2.05963e-15 -1 -2.30287e-17,
+                          -1.83759e-15 -1 -2.30287e-17,
+                          0.5 -0.866025 -6.57812e-17,
+                          0.5 -0.866025 -6.57812e-17,
+                          0.866025 -0.5 -9.09077e-17,
+                          -1.83759e-15 -1 -2.30287e-17,
+                          0.5 -0.866025 -6.57812e-17,
+                          0.5 -0.866025 -6.57812e-17,
+                          0.866025 -0.5 -9.09077e-17,
+                          0.866025 -0.5 -9.09077e-17,
+                          1 -2.33487e-16 -9.16756e-17,
+                          0.5 -0.866025 -6.57812e-17,
+                          0.866025 -0.5 -9.09077e-17,
+                          0.866025 -0.5 -9.09077e-17,
+                          1 -2.33487e-16 -9.16756e-17,
+                          1 -2.33487e-16 -9.16756e-17,
+                          0.866025 0.5 -6.7879e-17,
+                          0.866025 -0.5 -9.09077e-17,
+                          1 -2.33487e-16 -9.16756e-17,
+                          1 -2.33487e-16 -9.16756e-17,
+                          0.866025 0.5 -6.7879e-17,
+                          0.866025 0.5 -6.7879e-17,
+                          0.5 0.866025 -2.58943e-17,
+                          1 -2.33487e-16 -9.16756e-17,
+                          0.866025 0.5 -6.7879e-17,
+                          0.866025 0.5 -6.7879e-17,
+                          0.5 0.866025 -2.58943e-17,
+                          0.5 0.866025 -2.58943e-17,
+                          2.1821e-15 1 2.30287e-17,
+                          0.866025 0.5 -6.7879e-17,
+                          0.5 0.866025 -2.58943e-17,
+                          0.5 0.866025 -2.58943e-17,
+                          2.1821e-15 1 2.30287e-17,
+                          2.1821e-15 1 2.30287e-17,
+                          -0.5 0.866025 6.57812e-17,
+                          0.5 0.866025 -2.58943e-17,
+                          2.1821e-15 1 2.30287e-17,
+                          2.1821e-15 1 2.30287e-17,
+                          -0.5 0.866025 6.57812e-17,
+                          -0.5 0.866025 6.57812e-17,
+                          -0.866025 0.5 9.09077e-17,
+                          2.1821e-15 1 2.30287e-17,
+                          -0.5 0.866025 6.57812e-17,
+                          -0.5 0.866025 6.57812e-17,
+                          -0.5 0.866025 6.57812e-17,
+                          -0.866025 0.5 9.09077e-17,
+                          -0.866025 0.5 9.09077e-17 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 6.8 2.25 78,
+                          6.8 -2.25 78,
+                          37.8 -2.25 78,
+                          37.8 -2.25 75.3,
+                          37.8 -2.25 78,
+                          6.8 -2.25 78,
+                          37.8 2.25 78,
+                          6.8 2.25 78,
+                          37.8 -2.25 78,
+                          37.8 2.25 75.3,
+                          37.8 2.25 78,
+                          37.8 -2.25 78,
+                          37.8 2.25 75.3,
+                          37.8 -2.25 78,
+                          37.8 -2.25 75.3,
+                          3.8 -2.25 75,
+                          6.8 -2.25 78,
+                          6.8 2.25 78,
+                          37.8 -2.25 70.7,
+                          37.8 -2.25 75.3,
+                          6.8 -2.25 78,
+                          37.8 -2.25 68,
+                          37.8 -2.25 70.7,
+                          6.8 -2.25 78,
+                          6.8 -2.25 68,
+                          37.8 -2.25 68,
+                          6.8 -2.25 78,
+                          3.8 -2.25 75,
+                          6.8 -2.25 68,
+                          6.8 -2.25 78,
+                          6.8 2.25 68,
+                          6.8 2.25 78,
+                          37.8 2.25 78,
+                          3.8 2.25 75,
+                          3.8 -2.25 75,
+                          6.8 2.25 78,
+                          3.8 2.25 71,
+                          3.8 2.25 75,
+                          6.8 2.25 78,
+                          6.8 2.25 68,
+                          3.8 2.25 71,
+                          6.8 2.25 78,
+                          37.8 2.25 75.3,
+                          6.8 2.25 68,
+                          37.8 2.25 78,
+                          42.45 -2.25 70.7,
+                          42.45 2.25 70.7,
+                          42.45 2.25 75.3,
+                          37.8 2.25 70.7,
+                          42.45 2.25 75.3,
+                          42.45 2.25 70.7,
+                          42.45 -2.25 75.3,
+                          42.45 -2.25 70.7,
+                          42.45 2.25 75.3,
+                          41.2825 0.625 75.3,
+                          42.45 -2.25 75.3,
+                          42.45 2.25 75.3,
+                          37.8 2.25 75.3,
+                          42.45 2.25 75.3,
+                          37.8 2.25 70.7,
+                          40.825 1.08253 75.3,
+                          42.45 2.25 75.3,
+                          37.8 2.25 75.3,
+                          40.825 1.08253 75.3,
+                          41.2825 0.625 75.3,
+                          42.45 2.25 75.3,
+                          41.2825 -0.625 70.7,
+                          42.45 2.25 70.7,
+                          42.45 -2.25 70.7,
+                          39.575 1.08253 70.7,
+                          37.8 2.25 70.7,
+                          42.45 2.25 70.7,
+                          41.2825 -0.625 70.7,
+                          41.45 2.13163e-14 70.7,
+                          42.45 2.25 70.7,
+                          41.2825 0.625 70.7,
+                          42.45 2.25 70.7,
+                          41.45 2.13163e-14 70.7,
+                          40.2 1.25 70.7,
+                          39.575 1.08253 70.7,
+                          42.45 2.25 70.7,
+                          40.825 1.08253 70.7,
+                          40.2 1.25 70.7,
+                          42.45 2.25 70.7,
+                          41.2825 0.625 70.7,
+                          40.825 1.08253 70.7,
+                          42.45 2.25 70.7,
+                          37.8 -2.25 75.3,
+                          42.45 -2.25 70.7,
+                          42.45 -2.25 75.3,
+                          37.8 -2.25 70.7,
+                          42.45 -2.25 70.7,
+                          37.8 -2.25 75.3,
+                          40.825 -1.08253 70.7,
+                          42.45 -2.25 70.7,
+                          37.8 -2.25 70.7,
+                          40.825 -1.08253 70.7,
+                          41.2825 -0.625 70.7,
+                          42.45 -2.25 70.7,
+                          39.575 -1.08253 75.3,
+                          37.8 -2.25 75.3,
+                          42.45 -2.25 75.3,
+                          41.2825 0.625 75.3,
+                          41.45 2.13163e-14 75.3,
+                          42.45 -2.25 75.3,
+                          41.2825 -0.625 75.3,
+                          42.45 -2.25 75.3,
+                          41.45 2.13163e-14 75.3,
+                          40.2 -1.25 75.3,
+                          39.575 -1.08253 75.3,
+                          42.45 -2.25 75.3,
+                          40.825 -1.08253 75.3,
+                          40.2 -1.25 75.3,
+                          42.45 -2.25 75.3,
+                          41.2825 -0.625 75.3,
+                          40.825 -1.08253 75.3,
+                          42.45 -2.25 75.3,
+                          39.1175 -0.625 75.3,
+                          37.8 2.25 75.3,
+                          37.8 -2.25 75.3,
+                          39.575 -1.08253 75.3,
+                          39.1175 -0.625 75.3,
+                          37.8 -2.25 75.3,
+                          37.8 2.25 68,
+                          37.8 -2.25 70.7,
+                          37.8 -2.25 68,
+                          37.8 2.25 70.7,
+                          37.8 -2.25 70.7,
+                          37.8 2.25 68,
+                          39.1175 0.625 70.7,
+                          37.8 -2.25 70.7,
+                          37.8 2.25 70.7,
+                          40.2 -1.25 70.7,
+                          40.825 -1.08253 70.7,
+                          37.8 -2.25 70.7,
+                          39.575 -1.08253 70.7,
+                          40.2 -1.25 70.7,
+                          37.8 -2.25 70.7,
+                          39.1175 -0.625 70.7,
+                          39.575 -1.08253 70.7,
+                          37.8 -2.25 70.7,
+                          38.95 2.13163e-14 70.7,
+                          39.1175 -0.625 70.7,
+                          37.8 -2.25 70.7,
+                          39.1175 0.625 70.7,
+                          38.95 2.13163e-14 70.7,
+                          37.8 -2.25 70.7,
+                          37.8 2.25 68,
+                          37.8 -2.25 68,
+                          6.8 -2.25 68,
+                          3.8 -2.25 75,
+                          3.8 -2.25 71,
+                          6.8 -2.25 68,
+                          3.8 2.25 71,
+                          6.8 -2.25 68,
+                          3.8 -2.25 71,
+                          6.8 2.25 68,
+                          6.8 -2.25 68,
+                          3.8 2.25 71,
+                          37.8 2.25 68,
+                          6.8 -2.25 68,
+                          6.8 2.25 68,
+                          3.8 2.25 75,
+                          3.8 -2.25 71,
+                          3.8 -2.25 75,
+                          3.8 2.25 71,
+                          3.8 -2.25 71,
+                          3.8 2.25 75,
+                          37.8 2.25 70.7,
+                          37.8 2.25 68,
+                          6.8 2.25 68,
+                          37.8 2.25 75.3,
+                          37.8 2.25 70.7,
+                          6.8 2.25 68,
+                          39.575 1.08253 70.7,
+                          39.1175 0.625 70.7,
+                          37.8 2.25 70.7,
+                          40.2 1.25 75.3,
+                          40.825 1.08253 75.3,
+                          37.8 2.25 75.3,
+                          39.575 1.08253 75.3,
+                          40.2 1.25 75.3,
+                          37.8 2.25 75.3,
+                          39.1175 0.625 75.3,
+                          39.575 1.08253 75.3,
+                          37.8 2.25 75.3,
+                          38.95 2.13163e-14 75.3,
+                          39.1175 0.625 75.3,
+                          37.8 2.25 75.3,
+                          39.1175 -0.625 75.3,
+                          38.95 2.13163e-14 75.3,
+                          37.8 2.25 75.3,
+                          41.45 2.13163e-14 70.7,
+                          41.45 2.13163e-14 75.3,
+                          41.2825 0.625 75.3,
+                          41.2825 -0.625 70.7,
+                          41.2825 -0.625 75.3,
+                          41.45 2.13163e-14 75.3,
+                          41.2825 -0.625 70.7,
+                          41.45 2.13163e-14 75.3,
+                          41.45 2.13163e-14 70.7,
+                          41.2825 0.625 70.7,
+                          41.2825 0.625 75.3,
+                          40.825 1.08253 75.3,
+                          41.2825 0.625 70.7,
+                          41.45 2.13163e-14 70.7,
+                          41.2825 0.625 75.3,
+                          40.825 1.08253 70.7,
+                          40.825 1.08253 75.3,
+                          40.2 1.25 75.3,
+                          41.2825 0.625 70.7,
+                          40.825 1.08253 75.3,
+                          40.825 1.08253 70.7,
+                          40.2 1.25 70.7,
+                          40.2 1.25 75.3,
+                          39.575 1.08253 75.3,
+                          40.825 1.08253 70.7,
+                          40.2 1.25 75.3,
+                          40.2 1.25 70.7,
+                          39.575 1.08253 70.7,
+                          39.575 1.08253 75.3,
+                          39.1175 0.625 75.3,
+                          40.2 1.25 70.7,
+                          39.575 1.08253 75.3,
+                          39.575 1.08253 70.7,
+                          39.1175 0.625 70.7,
+                          39.1175 0.625 75.3,
+                          38.95 2.13163e-14 75.3,
+                          39.575 1.08253 70.7,
+                          39.1175 0.625 75.3,
+                          39.1175 0.625 70.7,
+                          38.95 2.13163e-14 70.7,
+                          38.95 2.13163e-14 75.3,
+                          39.1175 -0.625 75.3,
+                          39.1175 0.625 70.7,
+                          38.95 2.13163e-14 75.3,
+                          38.95 2.13163e-14 70.7,
+                          39.1175 -0.625 70.7,
+                          39.1175 -0.625 75.3,
+                          39.575 -1.08253 75.3,
+                          38.95 2.13163e-14 70.7,
+                          39.1175 -0.625 75.3,
+                          39.1175 -0.625 70.7,
+                          39.575 -1.08253 70.7,
+                          39.575 -1.08253 75.3,
+                          40.2 -1.25 75.3,
+                          39.1175 -0.625 70.7,
+                          39.575 -1.08253 75.3,
+                          39.575 -1.08253 70.7,
+                          40.2 -1.25 70.7,
+                          40.2 -1.25 75.3,
+                          40.825 -1.08253 75.3,
+                          39.575 -1.08253 70.7,
+                          40.2 -1.25 75.3,
+                          40.2 -1.25 70.7,
+                          40.825 -1.08253 70.7,
+                          40.825 -1.08253 75.3,
+                          41.2825 -0.625 75.3,
+                          40.2 -1.25 70.7,
+                          40.825 -1.08253 75.3,
+                          40.825 -1.08253 70.7,
+                          40.825 -1.08253 70.7,
+                          41.2825 -0.625 75.3,
+                          41.2825 -0.625 70.7 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          -4.44089e-16 -1 1.10566e-16,
+                          -4.44089e-16 -1 1.10566e-16,
+                          -4.44089e-16 -1 1.10566e-16,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          1 5.55112e-17 -4.93655e-17,
+                          1 5.55112e-17 -4.93655e-17,
+                          1 5.55112e-17 -4.93655e-17,
+                          1 5.55112e-17 -4.93655e-17,
+                          1 5.55112e-17 -4.93655e-17,
+                          1 5.55112e-17 -4.93655e-17,
+                          -0.707107 -1.46661e-16 0.707107,
+                          -0.707107 -1.46661e-16 0.707107,
+                          -0.707107 -1.46661e-16 0.707107,
+                          -4.44089e-16 -1 1.10566e-16,
+                          -4.44089e-16 -1 1.10566e-16,
+                          -4.44089e-16 -1 1.10566e-16,
+                          -4.44089e-16 -1 1.10566e-16,
+                          -4.44089e-16 -1 1.10566e-16,
+                          -4.44089e-16 -1 1.10566e-16,
+                          -4.44089e-16 -1 1.10566e-16,
+                          -4.44089e-16 -1 1.10566e-16,
+                          -4.44089e-16 -1 1.10566e-16,
+                          -4.44089e-16 -1 1.10566e-16,
+                          -4.44089e-16 -1 1.10566e-16,
+                          -4.44089e-16 -1 1.10566e-16,
+                          4.44089e-16 1 -1.10566e-16,
+                          4.44089e-16 1 -1.10566e-16,
+                          4.44089e-16 1 -1.10566e-16,
+                          -0.707107 -1.46661e-16 0.707107,
+                          -0.707107 -1.46661e-16 0.707107,
+                          -0.707107 -1.46661e-16 0.707107,
+                          4.44089e-16 1 -1.10566e-16,
+                          4.44089e-16 1 -1.10566e-16,
+                          4.44089e-16 1 -1.10566e-16,
+                          4.44089e-16 1 -1.10566e-16,
+                          4.44089e-16 1 -1.10566e-16,
+                          4.44089e-16 1 -1.10566e-16,
+                          4.44089e-16 1 -1.10566e-16,
+                          4.44089e-16 1 -1.10566e-16,
+                          4.44089e-16 1 -1.10566e-16,
+                          1 5.55112e-17 -4.93655e-17,
+                          1 5.55112e-17 -4.93655e-17,
+                          1 5.55112e-17 -4.93655e-17,
+                          4.44089e-16 1 -1.10566e-16,
+                          4.44089e-16 1 -1.10566e-16,
+                          4.44089e-16 1 -1.10566e-16,
+                          1 5.55112e-17 -4.93655e-17,
+                          1 5.55112e-17 -4.93655e-17,
+                          1 5.55112e-17 -4.93655e-17,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          4.44089e-16 1 -1.10566e-16,
+                          4.44089e-16 1 -1.10566e-16,
+                          4.44089e-16 1 -1.10566e-16,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -4.44089e-16 -1 1.10566e-16,
+                          -4.44089e-16 -1 1.10566e-16,
+                          -4.44089e-16 -1 1.10566e-16,
+                          -4.44089e-16 -1 1.10566e-16,
+                          -4.44089e-16 -1 1.10566e-16,
+                          -4.44089e-16 -1 1.10566e-16,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          1 5.55112e-17 -4.93655e-17,
+                          1 5.55112e-17 -4.93655e-17,
+                          1 5.55112e-17 -4.93655e-17,
+                          1 5.55112e-17 -4.93655e-17,
+                          1 5.55112e-17 -4.93655e-17,
+                          1 5.55112e-17 -4.93655e-17,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -4.44089e-16 -1 1.10566e-16,
+                          -4.44089e-16 -1 1.10566e-16,
+                          -4.44089e-16 -1 1.10566e-16,
+                          -0.707107 6.81564e-17 -0.707107,
+                          -0.707107 6.81564e-17 -0.707107,
+                          -0.707107 6.81564e-17 -0.707107,
+                          -0.707107 6.81564e-17 -0.707107,
+                          -0.707107 6.81564e-17 -0.707107,
+                          -0.707107 6.81564e-17 -0.707107,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -1 -5.55112e-17 4.93655e-17,
+                          -1 -5.55112e-17 4.93655e-17,
+                          -1 -5.55112e-17 4.93655e-17,
+                          -1 -5.55112e-17 4.93655e-17,
+                          -1 -5.55112e-17 4.93655e-17,
+                          -1 -5.55112e-17 4.93655e-17,
+                          4.44089e-16 1 -1.10566e-16,
+                          4.44089e-16 1 -1.10566e-16,
+                          4.44089e-16 1 -1.10566e-16,
+                          4.44089e-16 1 -1.10566e-16,
+                          4.44089e-16 1 -1.10566e-16,
+                          4.44089e-16 1 -1.10566e-16,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          -2.24809e-16 1.51899e-16 -1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          2.24809e-16 -1.51899e-16 1,
+                          -1 -5.55112e-17 4.93655e-17,
+                          -1 -5.55112e-17 4.93655e-17,
+                          -0.866025 -0.5 9.80346e-17,
+                          -0.866025 0.5 -1.25311e-17,
+                          -0.866025 0.5 -1.25311e-17,
+                          -1 1.89418e-16 4.93655e-17,
+                          -0.866025 0.5 -1.25311e-17,
+                          -1 1.89418e-16 4.93655e-17,
+                          -1 1.89418e-16 4.93655e-17,
+                          -0.866025 -0.5 9.80346e-17,
+                          -0.866025 -0.5 9.80346e-17,
+                          -0.5 -0.866025 1.20435e-16,
+                          -0.866025 -0.5 9.80346e-17,
+                          -1 -5.55112e-17 4.93655e-17,
+                          -0.866025 -0.5 9.80346e-17,
+                          -0.5 -0.866025 1.20435e-16,
+                          -0.5 -0.866025 1.20435e-16,
+                          -2.28168e-15 -1 1.10566e-16,
+                          -0.866025 -0.5 9.80346e-17,
+                          -0.5 -0.866025 1.20435e-16,
+                          -0.5 -0.866025 1.20435e-16,
+                          -2.05963e-15 -1 1.10566e-16,
+                          -2.28168e-15 -1 1.10566e-16,
+                          0.5 -0.866025 7.107e-17,
+                          -0.5 -0.866025 1.20435e-16,
+                          -2.28168e-15 -1 1.10566e-16,
+                          -2.05963e-15 -1 1.10566e-16,
+                          0.5 -0.866025 7.107e-17,
+                          0.5 -0.866025 7.107e-17,
+                          0.866025 -0.5 1.25311e-17,
+                          -2.05963e-15 -1 1.10566e-16,
+                          0.5 -0.866025 7.107e-17,
+                          0.5 -0.866025 7.107e-17,
+                          0.866025 -0.5 1.25311e-17,
+                          0.866025 -0.5 1.25311e-17,
+                          1 -6.69535e-17 -4.93655e-17,
+                          0.5 -0.866025 7.107e-17,
+                          0.866025 -0.5 1.25311e-17,
+                          0.866025 -0.5 1.25311e-17,
+                          1 -6.69535e-17 -4.93655e-17,
+                          1 -6.69535e-17 -4.93655e-17,
+                          0.866025 0.5 -9.80346e-17,
+                          0.866025 -0.5 1.25311e-17,
+                          1 -6.69535e-17 -4.93655e-17,
+                          1 -6.69535e-17 -4.93655e-17,
+                          0.866025 0.5 -9.80346e-17,
+                          0.866025 0.5 -9.80346e-17,
+                          0.5 0.866025 -1.20435e-16,
+                          1 -6.69535e-17 -4.93655e-17,
+                          0.866025 0.5 -9.80346e-17,
+                          0.866025 0.5 -9.80346e-17,
+                          0.5 0.866025 -1.20435e-16,
+                          0.5 0.866025 -1.20435e-16,
+                          2.40414e-15 1 -1.10566e-16,
+                          0.866025 0.5 -9.80346e-17,
+                          0.5 0.866025 -1.20435e-16,
+                          0.5 0.866025 -1.20435e-16,
+                          2.40414e-15 1 -1.10566e-16,
+                          2.40414e-15 1 -1.10566e-16,
+                          -0.5 0.866025 -7.107e-17,
+                          0.5 0.866025 -1.20435e-16,
+                          2.40414e-15 1 -1.10566e-16,
+                          2.40414e-15 1 -1.10566e-16,
+                          -0.5 0.866025 -7.107e-17,
+                          -0.5 0.866025 -7.107e-17,
+                          -0.866025 0.5 -1.25311e-17,
+                          2.40414e-15 1 -1.10566e-16,
+                          -0.5 0.866025 -7.107e-17,
+                          -0.5 0.866025 -7.107e-17,
+                          -0.5 0.866025 -7.107e-17,
+                          -0.866025 0.5 -1.25311e-17,
+                          -0.866025 0.5 -1.25311e-17 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 6.8 2.25 56,
+                          6.8 -2.25 56,
+                          37.8 -2.25 56,
+                          37.8 -2.25 53.3,
+                          37.8 -2.25 56,
+                          6.8 -2.25 56,
+                          37.8 2.25 56,
+                          6.8 2.25 56,
+                          37.8 -2.25 56,
+                          37.8 2.25 53.3,
+                          37.8 2.25 56,
+                          37.8 -2.25 56,
+                          37.8 2.25 53.3,
+                          37.8 -2.25 56,
+                          37.8 -2.25 53.3,
+                          3.8 -2.25 53,
+                          6.8 -2.25 56,
+                          6.8 2.25 56,
+                          37.8 -2.25 48.7,
+                          37.8 -2.25 53.3,
+                          6.8 -2.25 56,
+                          37.8 -2.25 46,
+                          37.8 -2.25 48.7,
+                          6.8 -2.25 56,
+                          6.8 -2.25 46,
+                          37.8 -2.25 46,
+                          6.8 -2.25 56,
+                          3.8 -2.25 53,
+                          6.8 -2.25 46,
+                          6.8 -2.25 56,
+                          6.8 2.25 46,
+                          6.8 2.25 56,
+                          37.8 2.25 56,
+                          3.8 2.25 53,
+                          3.8 -2.25 53,
+                          6.8 2.25 56,
+                          3.8 2.25 49,
+                          3.8 2.25 53,
+                          6.8 2.25 56,
+                          6.8 2.25 46,
+                          3.8 2.25 49,
+                          6.8 2.25 56,
+                          37.8 2.25 53.3,
+                          6.8 2.25 46,
+                          37.8 2.25 56,
+                          42.45 -2.25 48.7,
+                          42.45 2.25 48.7,
+                          42.45 2.25 53.3,
+                          37.8 2.25 48.7,
+                          42.45 2.25 53.3,
+                          42.45 2.25 48.7,
+                          42.45 -2.25 53.3,
+                          42.45 -2.25 48.7,
+                          42.45 2.25 53.3,
+                          41.2825 0.625 53.3,
+                          42.45 -2.25 53.3,
+                          42.45 2.25 53.3,
+                          37.8 2.25 53.3,
+                          42.45 2.25 53.3,
+                          37.8 2.25 48.7,
+                          40.825 1.08253 53.3,
+                          42.45 2.25 53.3,
+                          37.8 2.25 53.3,
+                          40.825 1.08253 53.3,
+                          41.2825 0.625 53.3,
+                          42.45 2.25 53.3,
+                          41.2825 -0.625 48.7,
+                          42.45 2.25 48.7,
+                          42.45 -2.25 48.7,
+                          39.575 1.08253 48.7,
+                          37.8 2.25 48.7,
+                          42.45 2.25 48.7,
+                          41.2825 -0.625 48.7,
+                          41.45 4.06586e-14 48.7,
+                          42.45 2.25 48.7,
+                          41.2825 0.625 48.7,
+                          42.45 2.25 48.7,
+                          41.45 4.06586e-14 48.7,
+                          40.2 1.25 48.7,
+                          39.575 1.08253 48.7,
+                          42.45 2.25 48.7,
+                          40.825 1.08253 48.7,
+                          40.2 1.25 48.7,
+                          42.45 2.25 48.7,
+                          41.2825 0.625 48.7,
+                          40.825 1.08253 48.7,
+                          42.45 2.25 48.7,
+                          37.8 -2.25 53.3,
+                          42.45 -2.25 48.7,
+                          42.45 -2.25 53.3,
+                          37.8 -2.25 48.7,
+                          42.45 -2.25 48.7,
+                          37.8 -2.25 53.3,
+                          40.825 -1.08253 48.7,
+                          42.45 -2.25 48.7,
+                          37.8 -2.25 48.7,
+                          40.825 -1.08253 48.7,
+                          41.2825 -0.625 48.7,
+                          42.45 -2.25 48.7,
+                          39.575 -1.08253 53.3,
+                          37.8 -2.25 53.3,
+                          42.45 -2.25 53.3,
+                          41.2825 0.625 53.3,
+                          41.45 4.05434e-14 53.3,
+                          42.45 -2.25 53.3,
+                          41.2825 -0.625 53.3,
+                          42.45 -2.25 53.3,
+                          41.45 4.05434e-14 53.3,
+                          40.2 -1.25 53.3,
+                          39.575 -1.08253 53.3,
+                          42.45 -2.25 53.3,
+                          40.825 -1.08253 53.3,
+                          40.2 -1.25 53.3,
+                          42.45 -2.25 53.3,
+                          41.2825 -0.625 53.3,
+                          40.825 -1.08253 53.3,
+                          42.45 -2.25 53.3,
+                          39.1175 -0.625 53.3,
+                          37.8 2.25 53.3,
+                          37.8 -2.25 53.3,
+                          39.575 -1.08253 53.3,
+                          39.1175 -0.625 53.3,
+                          37.8 -2.25 53.3,
+                          37.8 2.25 46,
+                          37.8 -2.25 48.7,
+                          37.8 -2.25 46,
+                          37.8 2.25 48.7,
+                          37.8 -2.25 48.7,
+                          37.8 2.25 46,
+                          39.1175 0.625 48.7,
+                          37.8 -2.25 48.7,
+                          37.8 2.25 48.7,
+                          40.2 -1.25 48.7,
+                          40.825 -1.08253 48.7,
+                          37.8 -2.25 48.7,
+                          39.575 -1.08253 48.7,
+                          40.2 -1.25 48.7,
+                          37.8 -2.25 48.7,
+                          39.1175 -0.625 48.7,
+                          39.575 -1.08253 48.7,
+                          37.8 -2.25 48.7,
+                          38.95 4.02423e-14 48.7,
+                          39.1175 -0.625 48.7,
+                          37.8 -2.25 48.7,
+                          39.1175 0.625 48.7,
+                          38.95 4.02423e-14 48.7,
+                          37.8 -2.25 48.7,
+                          37.8 2.25 46,
+                          37.8 -2.25 46,
+                          6.8 -2.25 46,
+                          3.8 -2.25 53,
+                          3.8 -2.25 49,
+                          6.8 -2.25 46,
+                          3.8 2.25 49,
+                          6.8 -2.25 46,
+                          3.8 -2.25 49,
+                          6.8 2.25 46,
+                          6.8 -2.25 46,
+                          3.8 2.25 49,
+                          37.8 2.25 46,
+                          6.8 -2.25 46,
+                          6.8 2.25 46,
+                          3.8 2.25 53,
+                          3.8 -2.25 49,
+                          3.8 -2.25 53,
+                          3.8 2.25 49,
+                          3.8 -2.25 49,
+                          3.8 2.25 53,
+                          37.8 2.25 48.7,
+                          37.8 2.25 46,
+                          6.8 2.25 46,
+                          37.8 2.25 53.3,
+                          37.8 2.25 48.7,
+                          6.8 2.25 46,
+                          39.575 1.08253 48.7,
+                          39.1175 0.625 48.7,
+                          37.8 2.25 48.7,
+                          40.2 1.25 53.3,
+                          40.825 1.08253 53.3,
+                          37.8 2.25 53.3,
+                          39.575 1.08253 53.3,
+                          40.2 1.25 53.3,
+                          37.8 2.25 53.3,
+                          39.1175 0.625 53.3,
+                          39.575 1.08253 53.3,
+                          37.8 2.25 53.3,
+                          38.95 4.0127e-14 53.3,
+                          39.1175 0.625 53.3,
+                          37.8 2.25 53.3,
+                          39.1175 -0.625 53.3,
+                          38.95 4.0127e-14 53.3,
+                          37.8 2.25 53.3,
+                          41.45 4.06586e-14 48.7,
+                          41.45 4.05434e-14 53.3,
+                          41.2825 0.625 53.3,
+                          41.2825 -0.625 48.7,
+                          41.2825 -0.625 53.3,
+                          41.45 4.05434e-14 53.3,
+                          41.2825 -0.625 48.7,
+                          41.45 4.05434e-14 53.3,
+                          41.45 4.06586e-14 48.7,
+                          41.2825 0.625 48.7,
+                          41.2825 0.625 53.3,
+                          40.825 1.08253 53.3,
+                          41.2825 0.625 48.7,
+                          41.45 4.06586e-14 48.7,
+                          41.2825 0.625 53.3,
+                          40.825 1.08253 48.7,
+                          40.825 1.08253 53.3,
+                          40.2 1.25 53.3,
+                          41.2825 0.625 48.7,
+                          40.825 1.08253 53.3,
+                          40.825 1.08253 48.7,
+                          40.2 1.25 48.7,
+                          40.2 1.25 53.3,
+                          39.575 1.08253 53.3,
+                          40.825 1.08253 48.7,
+                          40.2 1.25 53.3,
+                          40.2 1.25 48.7,
+                          39.575 1.08253 48.7,
+                          39.575 1.08253 53.3,
+                          39.1175 0.625 53.3,
+                          40.2 1.25 48.7,
+                          39.575 1.08253 53.3,
+                          39.575 1.08253 48.7,
+                          39.1175 0.625 48.7,
+                          39.1175 0.625 53.3,
+                          38.95 4.0127e-14 53.3,
+                          39.575 1.08253 48.7,
+                          39.1175 0.625 53.3,
+                          39.1175 0.625 48.7,
+                          38.95 4.02423e-14 48.7,
+                          38.95 4.0127e-14 53.3,
+                          39.1175 -0.625 53.3,
+                          39.1175 0.625 48.7,
+                          38.95 4.0127e-14 53.3,
+                          38.95 4.02423e-14 48.7,
+                          39.1175 -0.625 48.7,
+                          39.1175 -0.625 53.3,
+                          39.575 -1.08253 53.3,
+                          38.95 4.02423e-14 48.7,
+                          39.1175 -0.625 53.3,
+                          39.1175 -0.625 48.7,
+                          39.575 -1.08253 48.7,
+                          39.575 -1.08253 53.3,
+                          40.2 -1.25 53.3,
+                          39.1175 -0.625 48.7,
+                          39.575 -1.08253 53.3,
+                          39.575 -1.08253 48.7,
+                          40.2 -1.25 48.7,
+                          40.2 -1.25 53.3,
+                          40.825 -1.08253 53.3,
+                          39.575 -1.08253 48.7,
+                          40.2 -1.25 53.3,
+                          40.2 -1.25 48.7,
+                          40.825 -1.08253 48.7,
+                          40.825 -1.08253 53.3,
+                          41.2825 -0.625 53.3,
+                          40.2 -1.25 48.7,
+                          40.825 -1.08253 53.3,
+                          40.825 -1.08253 48.7,
+                          40.825 -1.08253 48.7,
+                          41.2825 -0.625 53.3,
+                          41.2825 -0.625 48.7 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/proximal_index_middle_thumb.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/proximal_index_middle_thumb.iv
new file mode 100644
index 0000000000000000000000000000000000000000..fe7105d9d0d420fa3afe56a0255cdb6ed68aa957
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/proximal_index_middle_thumb.iv
@@ -0,0 +1,2010 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+    Separator {
+        Normal {
+            vector      [ -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1 2.65746e-16 5.55112e-17,
+                          -1 2.65746e-16 5.55112e-17,
+                          -0.809017 0.587785 1.63188e-16,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -0.809017 -0.587785 -7.33693e-17,
+                          -0.809017 -0.587785 -7.33693e-17,
+                          -1 2.08167e-17 5.55112e-17,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -0.809017 -0.587785 -7.33693e-17,
+                          -1 2.08167e-17 5.55112e-17,
+                          -1 2.08167e-17 5.55112e-17,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -0.809017 0.587785 1.63188e-16,
+                          -0.809017 0.587785 1.63188e-16,
+                          -0.309017 0.951057 2.08533e-16,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -0.809017 0.587785 1.63188e-16,
+                          -1 2.65746e-16 5.55112e-17,
+                          -0.809017 0.587785 1.63188e-16,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -0.309017 0.951057 2.08533e-16,
+                          -0.309017 0.951057 2.08533e-16,
+                          0.309017 0.951057 1.74225e-16,
+                          -0.809017 0.587785 1.63188e-16,
+                          -0.309017 0.951057 2.08533e-16,
+                          -0.309017 0.951057 2.08533e-16,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          0.309017 0.951057 1.74225e-16,
+                          0.309017 0.951057 1.74225e-16,
+                          0.809017 0.587785 7.33693e-17,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -0.309017 0.951057 2.08533e-16,
+                          0.309017 0.951057 1.74225e-16,
+                          0.309017 0.951057 1.74225e-16,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          0.809017 0.587785 7.33693e-17,
+                          0.809017 0.587785 7.33693e-17,
+                          1 -1.43281e-16 -5.55112e-17,
+                          0.309017 0.951057 1.74225e-16,
+                          0.809017 0.587785 7.33693e-17,
+                          0.809017 0.587785 7.33693e-17,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          1 -1.43281e-16 -5.55112e-17,
+                          1 -1.43281e-16 -5.55112e-17,
+                          0.809017 -0.587785 -1.63188e-16,
+                          0.809017 0.587785 7.33693e-17,
+                          1 -1.43281e-16 -5.55112e-17,
+                          1 -1.43281e-16 -5.55112e-17,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          0.809017 -0.587785 -1.63188e-16,
+                          0.809017 -0.587785 -1.63188e-16,
+                          0.309017 -0.951057 -2.08533e-16,
+                          1 -1.43281e-16 -5.55112e-17,
+                          0.809017 -0.587785 -1.63188e-16,
+                          0.809017 -0.587785 -1.63188e-16,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          0.309017 -0.951057 -2.08533e-16,
+                          0.309017 -0.951057 -2.08533e-16,
+                          -0.309017 -0.951057 -1.74225e-16,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          0.809017 -0.587785 -1.63188e-16,
+                          0.309017 -0.951057 -2.08533e-16,
+                          0.309017 -0.951057 -2.08533e-16,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -0.309017 -0.951057 -1.74225e-16,
+                          -0.309017 -0.951057 -1.74225e-16,
+                          -0.809017 -0.587785 -7.33693e-17,
+                          0.309017 -0.951057 -2.08533e-16,
+                          -0.309017 -0.951057 -1.74225e-16,
+                          -0.309017 -0.951057 -1.74225e-16,
+                          -0.309017 -0.951057 -1.74225e-16,
+                          -0.809017 -0.587785 -7.33693e-17,
+                          -0.809017 -0.587785 -7.33693e-17,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1 2.08167e-17 5.55112e-17,
+                          -1 2.08167e-17 5.55112e-17,
+                          -1 2.08167e-17 5.55112e-17,
+                          -1 2.08167e-17 5.55112e-17,
+                          -1 2.08167e-17 5.55112e-17,
+                          -1 2.08167e-17 5.55112e-17,
+                          -1.07369e-16 -1 -2.01228e-16,
+                          -1.07369e-16 -1 -2.01228e-16,
+                          0.382683 -0.92388 -2.07154e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          0.382683 -0.92388 -2.07154e-16,
+                          0.382683 -0.92388 -2.07154e-16,
+                          0.707107 -0.707107 -1.81542e-16,
+                          0.382683 -0.92388 -2.07154e-16,
+                          -1.07369e-16 -1 -2.01228e-16,
+                          0.382683 -0.92388 -2.07154e-16,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          0.707107 -0.707107 -1.81542e-16,
+                          0.707107 -0.707107 -1.81542e-16,
+                          0.92388 -0.382683 -1.28292e-16,
+                          0.382683 -0.92388 -2.07154e-16,
+                          0.707107 -0.707107 -1.81542e-16,
+                          0.707107 -0.707107 -1.81542e-16,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          0.92388 -0.382683 -1.28292e-16,
+                          0.92388 -0.382683 -1.28292e-16,
+                          1 -2.65746e-16 -5.55112e-17,
+                          0.707107 -0.707107 -1.81542e-16,
+                          0.92388 -0.382683 -1.28292e-16,
+                          0.92388 -0.382683 -1.28292e-16,
+                          1 -2.08167e-17 -5.55112e-17,
+                          1 -2.08167e-17 -5.55112e-17,
+                          1 -2.08167e-17 -5.55112e-17,
+                          1 -2.08167e-17 -5.55112e-17,
+                          1 -2.08167e-17 -5.55112e-17,
+                          1 -2.08167e-17 -5.55112e-17,
+                          0.92388 -0.382683 -1.28292e-16,
+                          1 -2.65746e-16 -5.55112e-17,
+                          1 -2.65746e-16 -5.55112e-17,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1 2.24113e-16 -5.55112e-17,
+                          1 2.24113e-16 -5.55112e-17,
+                          0.809017 0.587785 7.33693e-17,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          0.809017 -0.587785 -1.63188e-16,
+                          0.809017 -0.587785 -1.63188e-16,
+                          1 -2.08167e-17 -5.55112e-17,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          0.809017 -0.587785 -1.63188e-16,
+                          1 -2.08167e-17 -5.55112e-17,
+                          1 -2.08167e-17 -5.55112e-17,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          0.809017 0.587785 7.33693e-17,
+                          0.809017 0.587785 7.33693e-17,
+                          0.309017 0.951057 1.74225e-16,
+                          0.809017 0.587785 7.33693e-17,
+                          1 2.24113e-16 -5.55112e-17,
+                          0.809017 0.587785 7.33693e-17,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          0.309017 0.951057 1.74225e-16,
+                          0.309017 0.951057 1.74225e-16,
+                          -0.309017 0.951057 2.08533e-16,
+                          0.809017 0.587785 7.33693e-17,
+                          0.309017 0.951057 1.74225e-16,
+                          0.309017 0.951057 1.74225e-16,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          -0.309017 0.951057 2.08533e-16,
+                          -0.309017 0.951057 2.08533e-16,
+                          -0.809017 0.587785 1.63188e-16,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          0.309017 0.951057 1.74225e-16,
+                          -0.309017 0.951057 2.08533e-16,
+                          -0.309017 0.951057 2.08533e-16,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          -0.809017 0.587785 1.63188e-16,
+                          -0.809017 0.587785 1.63188e-16,
+                          -1 -1.01648e-16 5.55112e-17,
+                          -0.309017 0.951057 2.08533e-16,
+                          -0.809017 0.587785 1.63188e-16,
+                          -0.809017 0.587785 1.63188e-16,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          -1 -1.01648e-16 5.55112e-17,
+                          -1 -1.01648e-16 5.55112e-17,
+                          -0.809017 -0.587785 -7.33693e-17,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          -0.809017 0.587785 1.63188e-16,
+                          -1 -1.01648e-16 5.55112e-17,
+                          -1 -1.01648e-16 5.55112e-17,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          -0.809017 -0.587785 -7.33693e-17,
+                          -0.809017 -0.587785 -7.33693e-17,
+                          -0.309017 -0.951057 -1.74225e-16,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          -1 -1.01648e-16 5.55112e-17,
+                          -0.809017 -0.587785 -7.33693e-17,
+                          -0.809017 -0.587785 -7.33693e-17,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          -0.309017 -0.951057 -1.74225e-16,
+                          -0.309017 -0.951057 -1.74225e-16,
+                          0.309017 -0.951057 -2.08533e-16,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          -0.809017 -0.587785 -7.33693e-17,
+                          -0.309017 -0.951057 -1.74225e-16,
+                          -0.309017 -0.951057 -1.74225e-16,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          0.309017 -0.951057 -2.08533e-16,
+                          0.309017 -0.951057 -2.08533e-16,
+                          0.809017 -0.587785 -1.63188e-16,
+                          -0.309017 -0.951057 -1.74225e-16,
+                          0.309017 -0.951057 -2.08533e-16,
+                          0.309017 -0.951057 -2.08533e-16,
+                          0.309017 -0.951057 -2.08533e-16,
+                          0.809017 -0.587785 -1.63188e-16,
+                          0.809017 -0.587785 -1.63188e-16,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          0.382683 -0.92388 -2.07154e-16,
+                          0.382683 -0.92388 -2.07154e-16,
+                          -1.07369e-16 -1 -2.01228e-16,
+                          0.382683 -0.92388 -2.07154e-16,
+                          -1.07369e-16 -1 -2.01228e-16,
+                          -1.07369e-16 -1 -2.01228e-16,
+                          -1 2.08167e-17 5.55112e-17,
+                          -1 2.08167e-17 5.55112e-17,
+                          -1 2.08167e-17 5.55112e-17,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -1 2.08167e-17 5.55112e-17,
+                          -1 2.08167e-17 5.55112e-17,
+                          -1 2.08167e-17 5.55112e-17,
+                          1 -2.08167e-17 -5.55112e-17,
+                          1 -2.08167e-17 -5.55112e-17,
+                          1 -2.08167e-17 -5.55112e-17,
+                          1 -2.08167e-17 -5.55112e-17,
+                          1 -2.08167e-17 -5.55112e-17,
+                          1 -2.08167e-17 -5.55112e-17,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          1 -2.65746e-16 -5.55112e-17,
+                          1 -2.65746e-16 -5.55112e-17,
+                          0.92388 -0.382683 -1.28292e-16,
+                          0.92388 -0.382683 -1.28292e-16,
+                          0.92388 -0.382683 -1.28292e-16,
+                          0.707107 -0.707107 -1.81542e-16,
+                          0.92388 -0.382683 -1.28292e-16,
+                          1 -2.65746e-16 -5.55112e-17,
+                          0.92388 -0.382683 -1.28292e-16,
+                          0.707107 -0.707107 -1.81542e-16,
+                          0.707107 -0.707107 -1.81542e-16,
+                          0.382683 -0.92388 -2.07154e-16,
+                          0.92388 -0.382683 -1.28292e-16,
+                          0.707107 -0.707107 -1.81542e-16,
+                          0.707107 -0.707107 -1.81542e-16,
+                          0.707107 -0.707107 -1.81542e-16,
+                          0.382683 -0.92388 -2.07154e-16,
+                          0.382683 -0.92388 -2.07154e-16,
+                          -1 2.08167e-17 5.55112e-17,
+                          -1 2.08167e-17 5.55112e-17,
+                          -1 2.08167e-17 5.55112e-17,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -1 2.08167e-17 5.55112e-17,
+                          -1 2.08167e-17 5.55112e-17,
+                          -1 2.08167e-17 5.55112e-17,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          1 -2.08167e-17 -5.55112e-17,
+                          1 -2.08167e-17 -5.55112e-17,
+                          1 -2.08167e-17 -5.55112e-17,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          1 -2.08167e-17 -5.55112e-17,
+                          1 -2.08167e-17 -5.55112e-17,
+                          1 -2.08167e-17 -5.55112e-17,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          1.11022e-16 -5.20417e-17 1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          -1.11022e-16 5.20417e-17 -1,
+                          1 -2.08167e-17 -5.55112e-17,
+                          1 -2.08167e-17 -5.55112e-17,
+                          0.866025 -0.5 -1.48688e-16,
+                          0.866025 0.5 5.25399e-17,
+                          0.866025 0.5 5.25399e-17,
+                          1 2.24113e-16 -5.55112e-17,
+                          0.866025 0.5 5.25399e-17,
+                          1 2.24113e-16 -5.55112e-17,
+                          1 2.24113e-16 -5.55112e-17,
+                          0.866025 -0.5 -1.48688e-16,
+                          0.866025 -0.5 -1.48688e-16,
+                          0.5 -0.866025 -2.02024e-16,
+                          0.866025 -0.5 -1.48688e-16,
+                          1 -2.08167e-17 -5.55112e-17,
+                          0.866025 -0.5 -1.48688e-16,
+                          0.5 -0.866025 -2.02024e-16,
+                          0.5 -0.866025 -2.02024e-16,
+                          -4.74742e-15 -1 -2.01228e-16,
+                          0.866025 -0.5 -1.48688e-16,
+                          0.5 -0.866025 -2.02024e-16,
+                          0.5 -0.866025 -2.02024e-16,
+                          -4.74742e-15 -1 -2.01228e-16,
+                          -4.74742e-15 -1 -2.01228e-16,
+                          -0.5 -0.866025 -1.46513e-16,
+                          0.5 -0.866025 -2.02024e-16,
+                          -4.74742e-15 -1 -2.01228e-16,
+                          -4.74742e-15 -1 -2.01228e-16,
+                          -0.5 -0.866025 -1.46513e-16,
+                          -0.5 -0.866025 -1.46513e-16,
+                          -0.866025 -0.5 -5.25399e-17,
+                          -4.74742e-15 -1 -2.01228e-16,
+                          -0.5 -0.866025 -1.46513e-16,
+                          -0.5 -0.866025 -1.46513e-16,
+                          -0.866025 -0.5 -5.25399e-17,
+                          -0.866025 -0.5 -5.25399e-17,
+                          -1 -1.01648e-16 5.55112e-17,
+                          -0.5 -0.866025 -1.46513e-16,
+                          -0.866025 -0.5 -5.25399e-17,
+                          -0.866025 -0.5 -5.25399e-17,
+                          -1 -1.01648e-16 5.55112e-17,
+                          -1 -1.01648e-16 5.55112e-17,
+                          -0.866025 0.5 1.48688e-16,
+                          -0.866025 -0.5 -5.25399e-17,
+                          -1 -1.01648e-16 5.55112e-17,
+                          -1 -1.01648e-16 5.55112e-17,
+                          -0.866025 0.5 1.48688e-16,
+                          -0.866025 0.5 1.48688e-16,
+                          -0.5 0.866025 2.02024e-16,
+                          -1 -1.01648e-16 5.55112e-17,
+                          -0.866025 0.5 1.48688e-16,
+                          -0.866025 0.5 1.48688e-16,
+                          -0.5 0.866025 2.02024e-16,
+                          -0.5 0.866025 2.02024e-16,
+                          1.51633e-15 1 2.01228e-16,
+                          -0.866025 0.5 1.48688e-16,
+                          -0.5 0.866025 2.02024e-16,
+                          -0.5 0.866025 2.02024e-16,
+                          1.51633e-15 1 2.01228e-16,
+                          1.51633e-15 1 2.01228e-16,
+                          0.5 0.866025 1.46513e-16,
+                          -0.5 0.866025 2.02024e-16,
+                          1.51633e-15 1 2.01228e-16,
+                          1.51633e-15 1 2.01228e-16,
+                          0.5 0.866025 1.46513e-16,
+                          0.5 0.866025 1.46513e-16,
+                          0.866025 0.5 5.25399e-17,
+                          1.51633e-15 1 2.01228e-16,
+                          0.5 0.866025 1.46513e-16,
+                          0.5 0.866025 1.46513e-16,
+                          0.5 0.866025 1.46513e-16,
+                          0.866025 0.5 5.25399e-17,
+                          0.866025 0.5 5.25399e-17 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 0.856699 -2.0597 -5,
+                          0.598674 -0.434958 -5,
+                          0.74 -7.10543e-15 -5,
+                          0.74 -7.10543e-15 -2.8,
+                          0.74 -7.10543e-15 -5,
+                          0.598674 -0.434958 -5,
+                          2.4 2.25 -5,
+                          0.74 -7.10543e-15 -5,
+                          0.598674 0.434958 -5,
+                          0.598674 0.434958 -2.8,
+                          0.598674 0.434958 -5,
+                          0.74 -7.10543e-15 -5,
+                          2.4 2.25 -5,
+                          0.856699 -2.0597 -5,
+                          0.74 -7.10543e-15 -5,
+                          0.598674 0.434958 -2.8,
+                          0.74 -7.10543e-15 -5,
+                          0.74 -7.10543e-15 -2.8,
+                          -0.1 -2.25 -5,
+                          0.228666 -0.703784 -5,
+                          0.598674 -0.434958 -5,
+                          0.598674 -0.434958 -2.8,
+                          0.598674 -0.434958 -5,
+                          0.228666 -0.703784 -5,
+                          0.856699 -2.0597 -5,
+                          -0.1 -2.25 -5,
+                          0.598674 -0.434958 -5,
+                          0.598674 -0.434958 -2.8,
+                          0.74 -7.10543e-15 -2.8,
+                          0.598674 -0.434958 -5,
+                          -0.1 -2.25 -5,
+                          -0.228666 -0.703784 -5,
+                          0.228666 -0.703784 -5,
+                          0.228666 -0.703784 -2.8,
+                          0.228666 -0.703784 -5,
+                          -0.228666 -0.703784 -5,
+                          0.598674 -0.434958 -2.8,
+                          0.228666 -0.703784 -5,
+                          0.228666 -0.703784 -2.8,
+                          -37.6 -2.25 -5,
+                          -0.598674 -0.434958 -5,
+                          -0.228666 -0.703784 -5,
+                          -0.228666 -0.703784 -2.8,
+                          -0.228666 -0.703784 -5,
+                          -0.598674 -0.434958 -5,
+                          -0.1 -2.25 -5,
+                          -37.6 -2.25 -5,
+                          -0.228666 -0.703784 -5,
+                          0.228666 -0.703784 -2.8,
+                          -0.228666 -0.703784 -5,
+                          -0.228666 -0.703784 -2.8,
+                          -37.6 -2.25 -5,
+                          -0.74 -7.10543e-15 -5,
+                          -0.598674 -0.434958 -5,
+                          -0.598674 -0.434958 -2.8,
+                          -0.598674 -0.434958 -5,
+                          -0.74 -7.10543e-15 -5,
+                          -0.228666 -0.703784 -2.8,
+                          -0.598674 -0.434958 -5,
+                          -0.598674 -0.434958 -2.8,
+                          -37.6 -2.25 -5,
+                          -0.598674 0.434958 -5,
+                          -0.74 -7.10543e-15 -5,
+                          -0.74 -7.10543e-15 -2.8,
+                          -0.74 -7.10543e-15 -5,
+                          -0.598674 0.434958 -5,
+                          -0.598674 -0.434958 -2.8,
+                          -0.74 -7.10543e-15 -5,
+                          -0.74 -7.10543e-15 -2.8,
+                          -37.6 -2.25 -5,
+                          -0.228666 0.703784 -5,
+                          -0.598674 0.434958 -5,
+                          -0.598674 0.434958 -2.8,
+                          -0.598674 0.434958 -5,
+                          -0.228666 0.703784 -5,
+                          -0.74 -7.10543e-15 -2.8,
+                          -0.598674 0.434958 -5,
+                          -0.598674 0.434958 -2.8,
+                          2.4 2.25 -5,
+                          0.228666 0.703784 -5,
+                          -0.228666 0.703784 -5,
+                          -0.228666 0.703784 -2.8,
+                          -0.228666 0.703784 -5,
+                          0.228666 0.703784 -5,
+                          2.4 2.25 -5,
+                          -0.228666 0.703784 -5,
+                          -37.6 -2.25 -5,
+                          -0.598674 0.434958 -2.8,
+                          -0.228666 0.703784 -5,
+                          -0.228666 0.703784 -2.8,
+                          2.4 2.25 -5,
+                          0.598674 0.434958 -5,
+                          0.228666 0.703784 -5,
+                          0.228666 0.703784 -2.8,
+                          0.228666 0.703784 -5,
+                          0.598674 0.434958 -5,
+                          -0.228666 0.703784 -2.8,
+                          0.228666 0.703784 -5,
+                          0.228666 0.703784 -2.8,
+                          0.228666 0.703784 -2.8,
+                          0.598674 0.434958 -5,
+                          0.598674 0.434958 -2.8,
+                          -37.6 -2.25 -2.5,
+                          -37.6 -2.25 -5,
+                          -0.1 -2.25 -5,
+                          -37.6 2.25 -5,
+                          2.4 2.25 -5,
+                          -37.6 -2.25 -5,
+                          -37.6 2.25 -2.5,
+                          -37.6 2.25 -5,
+                          -37.6 -2.25 -5,
+                          -37.6 2.25 -2.5,
+                          -37.6 -2.25 -5,
+                          -37.6 -2.25 -2.5,
+                          -0.1 -2.25 -2.8,
+                          -0.1 -2.25 -5,
+                          0.856699 -2.0597 -5,
+                          -37.6 -2.25 2.5,
+                          -0.1 -2.25 -5,
+                          -37.6 -2.25 5,
+                          -2.25 -2.25 -2.8,
+                          -37.6 -2.25 5,
+                          -0.1 -2.25 -5,
+                          -2.25 -2.25 -2.8,
+                          -0.1 -2.25 -5,
+                          -0.1 -2.25 -2.8,
+                          -37.6 -2.25 2.5,
+                          -37.6 -2.25 -2.5,
+                          -0.1 -2.25 -5,
+                          2.4 2.25 -5,
+                          1.66777 -1.51777 -5,
+                          0.856699 -2.0597 -5,
+                          0.856699 -2.0597 -2.8,
+                          0.856699 -2.0597 -5,
+                          1.66777 -1.51777 -5,
+                          0.856699 -2.0597 -2.8,
+                          -0.1 -2.25 -2.8,
+                          0.856699 -2.0597 -5,
+                          2.4 2.25 -5,
+                          2.2097 -0.706699 -5,
+                          1.66777 -1.51777 -5,
+                          1.66777 -1.51777 -2.8,
+                          1.66777 -1.51777 -5,
+                          2.2097 -0.706699 -5,
+                          0.856699 -2.0597 -2.8,
+                          1.66777 -1.51777 -5,
+                          1.66777 -1.51777 -2.8,
+                          2.4 2.25 -5,
+                          2.4 0.25 -5,
+                          2.2097 -0.706699 -5,
+                          2.2097 -0.706699 -2.8,
+                          2.2097 -0.706699 -5,
+                          2.4 0.25 -5,
+                          1.66777 -1.51777 -2.8,
+                          2.2097 -0.706699 -5,
+                          2.2097 -0.706699 -2.8,
+                          2.4 2.25 -2.8,
+                          2.4 0.25 -5,
+                          2.4 2.25 -5,
+                          2.4 2.25 -2.8,
+                          2.4 0.25 -2.8,
+                          2.4 0.25 -5,
+                          2.2097 -0.706699 -2.8,
+                          2.4 0.25 -5,
+                          2.4 0.25 -2.8,
+                          2.4 2.25 -2.8,
+                          2.4 2.25 -5,
+                          -37.6 2.25 -5,
+                          -2.25 2.25 2.8,
+                          -37.6 2.25 -5,
+                          2.4 2.25 5,
+                          -37.6 2.25 -2.5,
+                          2.4 2.25 5,
+                          -37.6 2.25 -5,
+                          -2.25 2.25 -2.8,
+                          2.4 2.25 -2.8,
+                          -37.6 2.25 -5,
+                          -2.25 2.25 2.8,
+                          -2.25 2.25 -2.8,
+                          -37.6 2.25 -5,
+                          -0.1 -2.25 5,
+                          -0.606764 -0.440835 5,
+                          -0.75 -7.10543e-15 5,
+                          -0.75 -7.10543e-15 2.8,
+                          -0.75 -7.10543e-15 5,
+                          -0.606764 -0.440835 5,
+                          -37.6 2.25 5,
+                          -0.75 -7.10543e-15 5,
+                          -0.606764 0.440835 5,
+                          -0.606764 0.440835 2.8,
+                          -0.606764 0.440835 5,
+                          -0.75 -7.10543e-15 5,
+                          -37.6 2.25 5,
+                          -0.1 -2.25 5,
+                          -0.75 -7.10543e-15 5,
+                          -0.606764 0.440835 2.8,
+                          -0.75 -7.10543e-15 5,
+                          -0.75 -7.10543e-15 2.8,
+                          -0.1 -2.25 5,
+                          -0.231756 -0.713294 5,
+                          -0.606764 -0.440835 5,
+                          -0.606764 -0.440835 2.8,
+                          -0.606764 -0.440835 5,
+                          -0.231756 -0.713294 5,
+                          -0.606764 -0.440835 2.8,
+                          -0.75 -7.10543e-15 2.8,
+                          -0.606764 -0.440835 5,
+                          -0.1 -2.25 5,
+                          0.231756 -0.713294 5,
+                          -0.231756 -0.713294 5,
+                          -0.231756 -0.713294 2.8,
+                          -0.231756 -0.713294 5,
+                          0.231756 -0.713294 5,
+                          -0.606764 -0.440835 2.8,
+                          -0.231756 -0.713294 5,
+                          -0.231756 -0.713294 2.8,
+                          0.856699 -2.0597 5,
+                          0.606764 -0.440835 5,
+                          0.231756 -0.713294 5,
+                          0.231756 -0.713294 2.8,
+                          0.231756 -0.713294 5,
+                          0.606764 -0.440835 5,
+                          0.856699 -2.0597 5,
+                          0.231756 -0.713294 5,
+                          -0.1 -2.25 5,
+                          -0.231756 -0.713294 2.8,
+                          0.231756 -0.713294 5,
+                          0.231756 -0.713294 2.8,
+                          0.856699 -2.0597 5,
+                          0.75 -7.10543e-15 5,
+                          0.606764 -0.440835 5,
+                          0.606764 -0.440835 2.8,
+                          0.606764 -0.440835 5,
+                          0.75 -7.10543e-15 5,
+                          0.231756 -0.713294 2.8,
+                          0.606764 -0.440835 5,
+                          0.606764 -0.440835 2.8,
+                          1.66777 -1.51777 5,
+                          0.606764 0.440835 5,
+                          0.75 -7.10543e-15 5,
+                          0.75 -7.10543e-15 2.8,
+                          0.75 -7.10543e-15 5,
+                          0.606764 0.440835 5,
+                          0.856699 -2.0597 5,
+                          1.66777 -1.51777 5,
+                          0.75 -7.10543e-15 5,
+                          0.606764 -0.440835 2.8,
+                          0.75 -7.10543e-15 5,
+                          0.75 -7.10543e-15 2.8,
+                          2.2097 -0.706699 5,
+                          0.231756 0.713294 5,
+                          0.606764 0.440835 5,
+                          0.606764 0.440835 2.8,
+                          0.606764 0.440835 5,
+                          0.231756 0.713294 5,
+                          1.66777 -1.51777 5,
+                          2.2097 -0.706699 5,
+                          0.606764 0.440835 5,
+                          0.75 -7.10543e-15 2.8,
+                          0.606764 0.440835 5,
+                          0.606764 0.440835 2.8,
+                          -37.6 2.25 5,
+                          -0.231756 0.713294 5,
+                          0.231756 0.713294 5,
+                          0.231756 0.713294 2.8,
+                          0.231756 0.713294 5,
+                          -0.231756 0.713294 5,
+                          2.4 2.25 5,
+                          -37.6 2.25 5,
+                          0.231756 0.713294 5,
+                          2.4 0.25 5,
+                          2.4 2.25 5,
+                          0.231756 0.713294 5,
+                          2.2097 -0.706699 5,
+                          2.4 0.25 5,
+                          0.231756 0.713294 5,
+                          0.606764 0.440835 2.8,
+                          0.231756 0.713294 5,
+                          0.231756 0.713294 2.8,
+                          -37.6 2.25 5,
+                          -0.606764 0.440835 5,
+                          -0.231756 0.713294 5,
+                          -0.231756 0.713294 2.8,
+                          -0.231756 0.713294 5,
+                          -0.606764 0.440835 5,
+                          0.231756 0.713294 2.8,
+                          -0.231756 0.713294 5,
+                          -0.231756 0.713294 2.8,
+                          -0.231756 0.713294 2.8,
+                          -0.606764 0.440835 5,
+                          -0.606764 0.440835 2.8,
+                          -37.6 2.25 5,
+                          -37.6 -2.25 5,
+                          -0.1 -2.25 5,
+                          -0.1 -2.25 2.8,
+                          -0.1 -2.25 5,
+                          -37.6 -2.25 5,
+                          0.856699 -2.0597 2.8,
+                          0.856699 -2.0597 5,
+                          -0.1 -2.25 5,
+                          0.856699 -2.0597 2.8,
+                          -0.1 -2.25 5,
+                          -0.1 -2.25 2.8,
+                          -37.6 -2.25 2.5,
+                          -37.6 -2.25 5,
+                          -37.6 2.25 5,
+                          -2.25 -2.25 2.8,
+                          -0.1 -2.25 2.8,
+                          -37.6 -2.25 5,
+                          -2.25 -2.25 -2.8,
+                          -2.25 -2.25 2.8,
+                          -37.6 -2.25 5,
+                          -37.6 2.25 2.5,
+                          -37.6 2.25 5,
+                          2.4 2.25 5,
+                          -37.6 2.25 2.5,
+                          -37.6 -2.25 2.5,
+                          -37.6 2.25 5,
+                          2.4 0.25 2.8,
+                          2.4 2.25 5,
+                          2.4 0.25 5,
+                          2.4 2.25 2.8,
+                          2.4 2.25 5,
+                          2.4 0.25 2.8,
+                          -2.25 2.25 2.8,
+                          2.4 2.25 5,
+                          2.4 2.25 2.8,
+                          -37.6 2.25 -2.5,
+                          -37.6 2.25 2.5,
+                          2.4 2.25 5,
+                          2.4 0.25 2.8,
+                          2.4 0.25 5,
+                          2.2097 -0.706699 5,
+                          2.2097 -0.706699 2.8,
+                          2.2097 -0.706699 5,
+                          1.66777 -1.51777 5,
+                          2.2097 -0.706699 2.8,
+                          2.4 0.25 2.8,
+                          2.2097 -0.706699 5,
+                          1.66777 -1.51777 2.8,
+                          1.66777 -1.51777 5,
+                          0.856699 -2.0597 5,
+                          2.2097 -0.706699 2.8,
+                          1.66777 -1.51777 5,
+                          1.66777 -1.51777 2.8,
+                          1.66777 -1.51777 2.8,
+                          0.856699 -2.0597 5,
+                          0.856699 -2.0597 2.8,
+                          -42.25 -2.25 2.5,
+                          -42.25 2.25 2.5,
+                          -42.25 2.25 -2.5,
+                          -37.6 2.25 2.5,
+                          -42.25 2.25 -2.5,
+                          -42.25 2.25 2.5,
+                          -42.25 -2.25 -2.5,
+                          -42.25 -2.25 2.5,
+                          -42.25 2.25 -2.5,
+                          -40.9093 0.525005 -2.5,
+                          -42.25 -2.25 -2.5,
+                          -42.25 2.25 -2.5,
+                          -37.6 2.25 -2.5,
+                          -42.25 2.25 -2.5,
+                          -37.6 2.25 2.5,
+                          -40.525 0.909323 -2.5,
+                          -42.25 2.25 -2.5,
+                          -37.6 2.25 -2.5,
+                          -40.525 0.909323 -2.5,
+                          -40.9093 0.525005 -2.5,
+                          -42.25 2.25 -2.5,
+                          -40.9093 -0.525005 2.5,
+                          -42.25 2.25 2.5,
+                          -42.25 -2.25 2.5,
+                          -39.475 0.909323 2.5,
+                          -37.6 2.25 2.5,
+                          -42.25 2.25 2.5,
+                          -40.9093 -0.525005 2.5,
+                          -41.05 -7.10543e-15 2.5,
+                          -42.25 2.25 2.5,
+                          -40.9093 0.525005 2.5,
+                          -42.25 2.25 2.5,
+                          -41.05 -7.10543e-15 2.5,
+                          -40 1.05 2.5,
+                          -39.475 0.909323 2.5,
+                          -42.25 2.25 2.5,
+                          -40.525 0.909323 2.5,
+                          -40 1.05 2.5,
+                          -42.25 2.25 2.5,
+                          -40.9093 0.525005 2.5,
+                          -40.525 0.909323 2.5,
+                          -42.25 2.25 2.5,
+                          -37.6 -2.25 -2.5,
+                          -42.25 -2.25 2.5,
+                          -42.25 -2.25 -2.5,
+                          -37.6 -2.25 2.5,
+                          -42.25 -2.25 2.5,
+                          -37.6 -2.25 -2.5,
+                          -40.525 -0.909323 2.5,
+                          -42.25 -2.25 2.5,
+                          -37.6 -2.25 2.5,
+                          -40.525 -0.909323 2.5,
+                          -40.9093 -0.525005 2.5,
+                          -42.25 -2.25 2.5,
+                          -39.475 -0.909323 -2.5,
+                          -37.6 -2.25 -2.5,
+                          -42.25 -2.25 -2.5,
+                          -40.9093 0.525005 -2.5,
+                          -41.05 -7.10543e-15 -2.5,
+                          -42.25 -2.25 -2.5,
+                          -40.9093 -0.525005 -2.5,
+                          -42.25 -2.25 -2.5,
+                          -41.05 -7.10543e-15 -2.5,
+                          -40 -1.05 -2.5,
+                          -39.475 -0.909323 -2.5,
+                          -42.25 -2.25 -2.5,
+                          -40.525 -0.909323 -2.5,
+                          -40 -1.05 -2.5,
+                          -42.25 -2.25 -2.5,
+                          -40.9093 -0.525005 -2.5,
+                          -40.525 -0.909323 -2.5,
+                          -42.25 -2.25 -2.5,
+                          -2.25 2.25 -2.8,
+                          -2.25 -2.25 -2.8,
+                          -0.1 -2.25 -2.8,
+                          -0.74 -7.10543e-15 -2.8,
+                          -2.25 2.25 -2.8,
+                          -0.1 -2.25 -2.8,
+                          -0.598674 -0.434958 -2.8,
+                          -0.74 -7.10543e-15 -2.8,
+                          -0.1 -2.25 -2.8,
+                          -0.228666 -0.703784 -2.8,
+                          -0.598674 -0.434958 -2.8,
+                          -0.1 -2.25 -2.8,
+                          0.228666 -0.703784 -2.8,
+                          -0.228666 -0.703784 -2.8,
+                          -0.1 -2.25 -2.8,
+                          0.856699 -2.0597 -2.8,
+                          0.228666 -0.703784 -2.8,
+                          -0.1 -2.25 -2.8,
+                          -39.0907 -0.525005 -2.5,
+                          -37.6 2.25 -2.5,
+                          -37.6 -2.25 -2.5,
+                          -39.475 -0.909323 -2.5,
+                          -39.0907 -0.525005 -2.5,
+                          -37.6 -2.25 -2.5,
+                          -39.0907 0.525005 2.5,
+                          -37.6 -2.25 2.5,
+                          -37.6 2.25 2.5,
+                          -40 -1.05 2.5,
+                          -40.525 -0.909323 2.5,
+                          -37.6 -2.25 2.5,
+                          -39.475 -0.909323 2.5,
+                          -40 -1.05 2.5,
+                          -37.6 -2.25 2.5,
+                          -39.0907 -0.525005 2.5,
+                          -39.475 -0.909323 2.5,
+                          -37.6 -2.25 2.5,
+                          -38.95 -7.10543e-15 2.5,
+                          -39.0907 -0.525005 2.5,
+                          -37.6 -2.25 2.5,
+                          -39.0907 0.525005 2.5,
+                          -38.95 -7.10543e-15 2.5,
+                          -37.6 -2.25 2.5,
+                          -0.231756 -0.713294 2.8,
+                          -0.1 -2.25 2.8,
+                          -2.25 -2.25 2.8,
+                          0.231756 -0.713294 2.8,
+                          0.606764 -0.440835 2.8,
+                          -0.1 -2.25 2.8,
+                          0.856699 -2.0597 2.8,
+                          -0.1 -2.25 2.8,
+                          0.606764 -0.440835 2.8,
+                          -0.231756 -0.713294 2.8,
+                          0.231756 -0.713294 2.8,
+                          -0.1 -2.25 2.8,
+                          -2.25 2.25 2.8,
+                          -2.25 -2.25 2.8,
+                          -2.25 -2.25 -2.8,
+                          -0.606764 0.440835 2.8,
+                          -2.25 -2.25 2.8,
+                          -2.25 2.25 2.8,
+                          -0.606764 0.440835 2.8,
+                          -0.75 -7.10543e-15 2.8,
+                          -2.25 -2.25 2.8,
+                          -0.606764 -0.440835 2.8,
+                          -2.25 -2.25 2.8,
+                          -0.75 -7.10543e-15 2.8,
+                          -0.606764 -0.440835 2.8,
+                          -0.231756 -0.713294 2.8,
+                          -2.25 -2.25 2.8,
+                          -2.25 2.25 2.8,
+                          -2.25 -2.25 -2.8,
+                          -2.25 2.25 -2.8,
+                          -2.25 2.25 -2.8,
+                          2.4 0.25 -2.8,
+                          2.4 2.25 -2.8,
+                          0.228666 0.703784 -2.8,
+                          2.4 0.25 -2.8,
+                          -2.25 2.25 -2.8,
+                          2.2097 -0.706699 -2.8,
+                          2.4 0.25 -2.8,
+                          0.228666 0.703784 -2.8,
+                          2.2097 -0.706699 2.8,
+                          2.4 2.25 2.8,
+                          2.4 0.25 2.8,
+                          -0.231756 0.713294 2.8,
+                          -2.25 2.25 2.8,
+                          2.4 2.25 2.8,
+                          0.231756 0.713294 2.8,
+                          -0.231756 0.713294 2.8,
+                          2.4 2.25 2.8,
+                          0.606764 0.440835 2.8,
+                          0.231756 0.713294 2.8,
+                          2.4 2.25 2.8,
+                          0.75 -7.10543e-15 2.8,
+                          0.606764 0.440835 2.8,
+                          2.4 2.25 2.8,
+                          0.856699 -2.0597 2.8,
+                          0.75 -7.10543e-15 2.8,
+                          2.4 2.25 2.8,
+                          1.66777 -1.51777 2.8,
+                          0.856699 -2.0597 2.8,
+                          2.4 2.25 2.8,
+                          2.2097 -0.706699 2.8,
+                          1.66777 -1.51777 2.8,
+                          2.4 2.25 2.8,
+                          -0.228666 0.703784 -2.8,
+                          0.228666 0.703784 -2.8,
+                          -2.25 2.25 -2.8,
+                          -0.598674 0.434958 -2.8,
+                          -0.228666 0.703784 -2.8,
+                          -2.25 2.25 -2.8,
+                          -0.74 -7.10543e-15 -2.8,
+                          -0.598674 0.434958 -2.8,
+                          -2.25 2.25 -2.8,
+                          -0.231756 0.713294 2.8,
+                          -0.606764 0.440835 2.8,
+                          -2.25 2.25 2.8,
+                          -39.475 0.909323 2.5,
+                          -39.0907 0.525005 2.5,
+                          -37.6 2.25 2.5,
+                          -40 1.05 -2.5,
+                          -40.525 0.909323 -2.5,
+                          -37.6 2.25 -2.5,
+                          -39.475 0.909323 -2.5,
+                          -40 1.05 -2.5,
+                          -37.6 2.25 -2.5,
+                          -39.0907 0.525005 -2.5,
+                          -39.475 0.909323 -2.5,
+                          -37.6 2.25 -2.5,
+                          -38.95 -7.10543e-15 -2.5,
+                          -39.0907 0.525005 -2.5,
+                          -37.6 2.25 -2.5,
+                          -39.0907 -0.525005 -2.5,
+                          -38.95 -7.10543e-15 -2.5,
+                          -37.6 2.25 -2.5,
+                          1.66777 -1.51777 -2.8,
+                          0.598674 0.434958 -2.8,
+                          0.74 -7.10543e-15 -2.8,
+                          0.856699 -2.0597 -2.8,
+                          0.74 -7.10543e-15 -2.8,
+                          0.598674 -0.434958 -2.8,
+                          0.856699 -2.0597 -2.8,
+                          1.66777 -1.51777 -2.8,
+                          0.74 -7.10543e-15 -2.8,
+                          2.2097 -0.706699 -2.8,
+                          0.228666 0.703784 -2.8,
+                          0.598674 0.434958 -2.8,
+                          1.66777 -1.51777 -2.8,
+                          2.2097 -0.706699 -2.8,
+                          0.598674 0.434958 -2.8,
+                          0.856699 -2.0597 -2.8,
+                          0.598674 -0.434958 -2.8,
+                          0.228666 -0.703784 -2.8,
+                          0.856699 -2.0597 2.8,
+                          0.606764 -0.440835 2.8,
+                          0.75 -7.10543e-15 2.8,
+                          -41.05 -7.10543e-15 2.5,
+                          -41.05 -7.10543e-15 -2.5,
+                          -40.9093 0.525005 -2.5,
+                          -40.9093 -0.525005 2.5,
+                          -40.9093 -0.525005 -2.5,
+                          -41.05 -7.10543e-15 -2.5,
+                          -40.9093 -0.525005 2.5,
+                          -41.05 -7.10543e-15 -2.5,
+                          -41.05 -7.10543e-15 2.5,
+                          -40.9093 0.525005 2.5,
+                          -40.9093 0.525005 -2.5,
+                          -40.525 0.909323 -2.5,
+                          -40.9093 0.525005 2.5,
+                          -41.05 -7.10543e-15 2.5,
+                          -40.9093 0.525005 -2.5,
+                          -40.525 0.909323 2.5,
+                          -40.525 0.909323 -2.5,
+                          -40 1.05 -2.5,
+                          -40.9093 0.525005 2.5,
+                          -40.525 0.909323 -2.5,
+                          -40.525 0.909323 2.5,
+                          -40 1.05 2.5,
+                          -40 1.05 -2.5,
+                          -39.475 0.909323 -2.5,
+                          -40.525 0.909323 2.5,
+                          -40 1.05 -2.5,
+                          -40 1.05 2.5,
+                          -39.475 0.909323 2.5,
+                          -39.475 0.909323 -2.5,
+                          -39.0907 0.525005 -2.5,
+                          -40 1.05 2.5,
+                          -39.475 0.909323 -2.5,
+                          -39.475 0.909323 2.5,
+                          -39.0907 0.525005 2.5,
+                          -39.0907 0.525005 -2.5,
+                          -38.95 -7.10543e-15 -2.5,
+                          -39.475 0.909323 2.5,
+                          -39.0907 0.525005 -2.5,
+                          -39.0907 0.525005 2.5,
+                          -38.95 -7.10543e-15 2.5,
+                          -38.95 -7.10543e-15 -2.5,
+                          -39.0907 -0.525005 -2.5,
+                          -39.0907 0.525005 2.5,
+                          -38.95 -7.10543e-15 -2.5,
+                          -38.95 -7.10543e-15 2.5,
+                          -39.0907 -0.525005 2.5,
+                          -39.0907 -0.525005 -2.5,
+                          -39.475 -0.909323 -2.5,
+                          -38.95 -7.10543e-15 2.5,
+                          -39.0907 -0.525005 -2.5,
+                          -39.0907 -0.525005 2.5,
+                          -39.475 -0.909323 2.5,
+                          -39.475 -0.909323 -2.5,
+                          -40 -1.05 -2.5,
+                          -39.0907 -0.525005 2.5,
+                          -39.475 -0.909323 -2.5,
+                          -39.475 -0.909323 2.5,
+                          -40 -1.05 2.5,
+                          -40 -1.05 -2.5,
+                          -40.525 -0.909323 -2.5,
+                          -39.475 -0.909323 2.5,
+                          -40 -1.05 -2.5,
+                          -40 -1.05 2.5,
+                          -40.525 -0.909323 2.5,
+                          -40.525 -0.909323 -2.5,
+                          -40.9093 -0.525005 -2.5,
+                          -40 -1.05 2.5,
+                          -40.525 -0.909323 -2.5,
+                          -40.525 -0.909323 2.5,
+                          -40.525 -0.909323 2.5,
+                          -40.9093 -0.525005 -2.5,
+                          -40.9093 -0.525005 2.5 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0 0 1
+    }
+    Separator {
+        Normal {
+            vector      [ -1 0 2.77556e-16,
+                          -1 0 2.77556e-16,
+                          -1 0 2.77556e-16,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          -0.503871 -0.863779 5.29441e-17,
+                          -0.503871 -0.863779 5.29441e-17,
+                          -0.503871 -0.863779 5.29441e-17,
+                          -0.503871 -0.863779 5.29441e-17,
+                          -0.503871 -0.863779 5.29441e-17,
+                          -0.503871 -0.863779 5.29441e-17,
+                          -0.503871 -0.863779 5.29441e-17,
+                          -0.503871 -0.863779 5.29441e-17,
+                          -0.503871 -0.863779 5.29441e-17,
+                          -1 0 2.77556e-16,
+                          -1 0 2.77556e-16,
+                          -1 0 2.77556e-16,
+                          -0.291162 0.956674 1.77068e-16,
+                          -0.291162 0.956674 1.77068e-16,
+                          -0.291162 0.956674 1.77068e-16,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          -0.291162 0.956674 1.77068e-16,
+                          -0.291162 0.956674 1.77068e-16,
+                          -0.291162 0.956674 1.77068e-16,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.503871 -0.863779 5.29441e-17,
+                          -0.503871 -0.863779 5.29441e-17,
+                          -0.503871 -0.863779 5.29441e-17,
+                          -0.503871 -0.863779 5.29441e-17,
+                          -0.503871 -0.863779 5.29441e-17,
+                          -0.503871 -0.863779 5.29441e-17,
+                          1 0 -2.77556e-16,
+                          1 0 -2.77556e-16,
+                          1 0 -2.77556e-16,
+                          -6.93889e-18 -1 -1.00614e-16,
+                          -6.93889e-18 -1 -1.00614e-16,
+                          -6.93889e-18 -1 -1.00614e-16,
+                          1 0 -2.77556e-16,
+                          1 0 -2.77556e-16,
+                          1 0 -2.77556e-16,
+                          1 0 -2.77556e-16,
+                          1 0 -2.77556e-16,
+                          1 0 -2.77556e-16,
+                          -1.61916e-16 -0.707107 -0.707107,
+                          -1.61916e-16 -0.707107 -0.707107,
+                          -1.61916e-16 -0.707107 -0.707107,
+                          -6.93889e-18 -1 -1.00614e-16,
+                          -6.93889e-18 -1 -1.00614e-16,
+                          -6.93889e-18 -1 -1.00614e-16,
+                          1 0 -2.77556e-16,
+                          1 0 -2.77556e-16,
+                          1 0 -2.77556e-16,
+                          1.52103e-16 -0.707107 0.707107,
+                          1.52103e-16 -0.707107 0.707107,
+                          1.52103e-16 -0.707107 0.707107,
+                          1 0 -2.77556e-16,
+                          1 0 -2.77556e-16,
+                          1 0 -2.77556e-16,
+                          1.52103e-16 -0.707107 0.707107,
+                          1.52103e-16 -0.707107 0.707107,
+                          1.52103e-16 -0.707107 0.707107,
+                          2.22045e-16 1.38778e-17 1,
+                          2.22045e-16 1.38778e-17 1,
+                          2.22045e-16 1.38778e-17 1,
+                          2.22045e-16 1.38778e-17 1,
+                          2.22045e-16 1.38778e-17 1,
+                          2.22045e-16 1.38778e-17 1,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          6.93889e-18 1 1.00614e-16,
+                          6.93889e-18 1 1.00614e-16,
+                          6.93889e-18 1 1.00614e-16,
+                          6.93889e-18 1 1.00614e-16,
+                          6.93889e-18 1 1.00614e-16,
+                          6.93889e-18 1 1.00614e-16,
+                          1 0 -2.77556e-16,
+                          1 0 -2.77556e-16,
+                          1 0 -2.77556e-16,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          -2.22045e-16 -1.38778e-17 -1,
+                          -2.22045e-16 -1.38778e-17 -1,
+                          -2.22045e-16 -1.38778e-17 -1,
+                          -2.22045e-16 -1.38778e-17 -1,
+                          -2.22045e-16 -1.38778e-17 -1,
+                          -2.22045e-16 -1.38778e-17 -1,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          -1.61916e-16 -0.707107 -0.707107,
+                          -1.61916e-16 -0.707107 -0.707107,
+                          -1.61916e-16 -0.707107 -0.707107,
+                          -1.61916e-16 -0.707107 -0.707107,
+                          -1.61916e-16 -0.707107 -0.707107,
+                          -1.61916e-16 -0.707107 -0.707107,
+                          -0.503871 -0.863779 5.29441e-17,
+                          -0.503871 -0.863779 5.29441e-17,
+                          -0.503871 -0.863779 5.29441e-17,
+                          1.52103e-16 -0.707107 0.707107,
+                          1.52103e-16 -0.707107 0.707107,
+                          1.52103e-16 -0.707107 0.707107,
+                          -0.223376 -1.35271e-17 -0.974732,
+                          -0.223376 -1.35271e-17 -0.974732,
+                          -0.223376 -1.35271e-17 -0.974732,
+                          -0.223376 -1.35271e-17 -0.974732,
+                          -0.223376 -1.35271e-17 -0.974732,
+                          -0.223376 -1.35271e-17 -0.974732,
+                          -0.223376 1.35271e-17 0.974732,
+                          -0.223376 1.35271e-17 0.974732,
+                          -0.223376 1.35271e-17 0.974732,
+                          -0.223376 1.35271e-17 0.974732,
+                          -0.223376 1.35271e-17 0.974732,
+                          -0.223376 1.35271e-17 0.974732 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -58.75 2.75 7.11769,
+                          -58.75 5.75 -4.16326,
+                          -58.75 2.75 -7.11769,
+                          -58.495 2.60127 -7.30843,
+                          -58.75 2.75 -7.11769,
+                          -58.75 5.75 -4.16326,
+                          -46.75 -4.25 7,
+                          -58.75 2.75 7.11769,
+                          -58.75 2.75 -7.11769,
+                          -46.75 -4.25 7,
+                          -58.75 2.75 -7.11769,
+                          -46.75 -4.25 -7,
+                          -58.495 2.60127 -7.30843,
+                          -46.75 -4.25 -7,
+                          -58.75 2.75 -7.11769,
+                          -58.75 2.75 7.11769,
+                          -58.75 5.75 4.16326,
+                          -58.75 5.75 -4.16326,
+                          -35.75 12.75 1.26352,
+                          -58.75 5.75 -4.16326,
+                          -58.75 5.75 4.16326,
+                          -35.75 12.75 -1.26352,
+                          -46.75 1.93915 -10,
+                          -58.75 5.75 -4.16326,
+                          -58.495 2.60127 -7.30843,
+                          -58.75 5.75 -4.16326,
+                          -46.75 1.93915 -10,
+                          -35.75 12.75 -1.26352,
+                          -58.75 5.75 -4.16326,
+                          -35.75 12.75 1.26352,
+                          -58.495 2.60127 7.30843,
+                          -58.75 5.75 4.16326,
+                          -58.75 2.75 7.11769,
+                          -46.75 1.93915 10,
+                          -35.75 12.75 1.26352,
+                          -58.75 5.75 4.16326,
+                          -58.495 2.60127 7.30843,
+                          -46.75 1.93915 10,
+                          -58.75 5.75 4.16326,
+                          -50.4423 -2.09615 9.15385,
+                          -58.75 2.75 7.11769,
+                          -46.75 -4.25 7,
+                          -58.495 2.60127 7.30843,
+                          -58.75 2.75 7.11769,
+                          -50.4423 -2.09615 9.15385,
+                          -25.75 12.75 3,
+                          -25.75 -4.25 7,
+                          -25.75 -4.25 -7,
+                          -46.75 -4.25 7,
+                          -25.75 -4.25 -7,
+                          -25.75 -4.25 7,
+                          -25.75 12.75 -3,
+                          -25.75 12.75 3,
+                          -25.75 -4.25 -7,
+                          -25.75 -1.25 -10,
+                          -25.75 12.75 -3,
+                          -25.75 -4.25 -7,
+                          -46.75 -4.25 -7,
+                          -25.75 -1.25 -10,
+                          -25.75 -4.25 -7,
+                          -46.75 -4.25 7,
+                          -46.75 -4.25 -7,
+                          -25.75 -4.25 -7,
+                          -25.75 5.64201 10,
+                          -25.75 -1.25 10,
+                          -25.75 -4.25 7,
+                          -46.75 -1.25 10,
+                          -25.75 -4.25 7,
+                          -25.75 -1.25 10,
+                          -25.75 12.75 3,
+                          -25.75 5.64201 10,
+                          -25.75 -4.25 7,
+                          -46.75 -1.25 10,
+                          -46.75 -4.25 7,
+                          -25.75 -4.25 7,
+                          -46.75 1.93915 10,
+                          -25.75 -1.25 10,
+                          -25.75 5.64201 10,
+                          -46.75 1.93915 10,
+                          -46.75 -1.25 10,
+                          -25.75 -1.25 10,
+                          -35.75 12.75 1.26352,
+                          -25.75 5.64201 10,
+                          -25.75 12.75 3,
+                          -46.75 1.93915 10,
+                          -25.75 5.64201 10,
+                          -35.75 12.75 1.26352,
+                          -35.75 12.75 -1.26352,
+                          -25.75 12.75 3,
+                          -25.75 12.75 -3,
+                          -35.75 12.75 -1.26352,
+                          -35.75 12.75 1.26352,
+                          -25.75 12.75 3,
+                          -25.75 -1.25 -10,
+                          -25.75 5.64201 -10,
+                          -25.75 12.75 -3,
+                          -35.75 12.75 -1.26352,
+                          -25.75 12.75 -3,
+                          -25.75 5.64201 -10,
+                          -46.75 -1.25 -10,
+                          -25.75 5.64201 -10,
+                          -25.75 -1.25 -10,
+                          -46.75 -1.25 -10,
+                          -46.75 1.93915 -10,
+                          -25.75 5.64201 -10,
+                          -35.75 12.75 -1.26352,
+                          -25.75 5.64201 -10,
+                          -46.75 1.93915 -10,
+                          -46.75 -1.25 -10,
+                          -25.75 -1.25 -10,
+                          -46.75 -4.25 -7,
+                          -50.4423 -2.09615 -9.15385,
+                          -46.75 -1.25 -10,
+                          -46.75 -4.25 -7,
+                          -50.4423 -2.09615 -9.15385,
+                          -46.75 -4.25 -7,
+                          -58.495 2.60127 -7.30843,
+                          -50.4423 -2.09615 9.15385,
+                          -46.75 -4.25 7,
+                          -46.75 -1.25 10,
+                          -50.4423 -2.09615 -9.15385,
+                          -46.75 1.93915 -10,
+                          -46.75 -1.25 -10,
+                          -50.4423 -2.09615 -9.15385,
+                          -58.495 2.60127 -7.30843,
+                          -46.75 1.93915 -10,
+                          -58.495 2.60127 7.30843,
+                          -46.75 -1.25 10,
+                          -46.75 1.93915 10,
+                          -58.495 2.60127 7.30843,
+                          -50.4423 -2.09615 9.15385,
+                          -46.75 -1.25 10 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          1 -2.08167e-17 -5.55112e-17,
+                          1 -2.08167e-17 -5.55112e-17,
+                          0.92388 -3.91476e-17 0.382683,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          0.92388 6.83392e-19 -0.382683,
+                          0.92388 6.83392e-19 -0.382683,
+                          1 -2.08167e-17 -3.00441e-16,
+                          0.92388 6.83392e-19 -0.382683,
+                          1 -2.08167e-17 -3.00441e-16,
+                          1 -2.08167e-17 -3.00441e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          0.92388 -3.91476e-17 0.382683,
+                          0.92388 -3.91476e-17 0.382683,
+                          0.707107 -5.15187e-17 0.707107,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          0.92388 -3.91476e-17 0.382683,
+                          1 -2.08167e-17 -5.55112e-17,
+                          0.92388 -3.91476e-17 0.382683,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          0.707107 -5.15187e-17 0.707107,
+                          0.707107 -5.15187e-17 0.707107,
+                          0.382683 -5.60465e-17 0.92388,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          0.92388 -3.91476e-17 0.382683,
+                          0.707107 -5.15187e-17 0.707107,
+                          0.707107 -5.15187e-17 0.707107,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          0.382683 -5.60465e-17 0.92388,
+                          0.382683 -5.60465e-17 0.92388,
+                          1.72255e-16 -5.20417e-17 1,
+                          0.707107 -5.15187e-17 0.707107,
+                          0.382683 -5.60465e-17 0.92388,
+                          0.382683 -5.60465e-17 0.92388,
+                          1.72255e-16 -5.20417e-17 1,
+                          1.72255e-16 -5.20417e-17 1,
+                          -0.382683 -4.01141e-17 0.92388,
+                          0.382683 -5.60465e-17 0.92388,
+                          1.72255e-16 -5.20417e-17 1,
+                          1.72255e-16 -5.20417e-17 1,
+                          -0.382683 -4.01141e-17 0.92388,
+                          -0.382683 -4.01141e-17 0.92388,
+                          -0.707107 -2.20794e-17 0.707107,
+                          1.72255e-16 -5.20417e-17 1,
+                          -0.382683 -4.01141e-17 0.92388,
+                          -0.382683 -4.01141e-17 0.92388,
+                          -0.707107 -2.20794e-17 0.707107,
+                          -0.707107 -2.20794e-17 0.707107,
+                          -0.92388 -6.83392e-19 0.382683,
+                          -0.382683 -4.01141e-17 0.92388,
+                          -0.707107 -2.20794e-17 0.707107,
+                          -0.707107 -2.20794e-17 0.707107,
+                          -0.92388 -6.83392e-19 0.382683,
+                          -0.92388 -6.83392e-19 0.382683,
+                          -1 2.08167e-17 1.77976e-16,
+                          -0.707107 -2.20794e-17 0.707107,
+                          -0.92388 -6.83392e-19 0.382683,
+                          -0.92388 -6.83392e-19 0.382683,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -1 2.08167e-17 1.77976e-16,
+                          -1 2.08167e-17 1.77976e-16,
+                          -0.92388 3.91476e-17 -0.382683,
+                          -0.92388 -6.83392e-19 0.382683,
+                          -1 2.08167e-17 1.77976e-16,
+                          -1 2.08167e-17 1.77976e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -0.92388 3.91476e-17 -0.382683,
+                          -0.92388 3.91476e-17 -0.382683,
+                          -0.707107 5.15187e-17 -0.707107,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -1 2.08167e-17 1.77976e-16,
+                          -0.92388 3.91476e-17 -0.382683,
+                          -0.92388 3.91476e-17 -0.382683,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -0.707107 5.15187e-17 -0.707107,
+                          -0.707107 5.15187e-17 -0.707107,
+                          -0.382683 5.60465e-17 -0.92388,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -0.92388 3.91476e-17 -0.382683,
+                          -0.707107 5.15187e-17 -0.707107,
+                          -0.707107 5.15187e-17 -0.707107,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -7.63278e-17 1 2.01228e-16,
+                          -0.382683 5.60465e-17 -0.92388,
+                          -0.382683 5.60465e-17 -0.92388,
+                          -2.94719e-16 5.20417e-17 -1,
+                          -0.707107 5.15187e-17 -0.707107,
+                          -0.382683 5.60465e-17 -0.92388,
+                          -0.382683 5.60465e-17 -0.92388,
+                          -2.94719e-16 5.20417e-17 -1,
+                          -2.94719e-16 5.20417e-17 -1,
+                          0.382683 4.01141e-17 -0.92388,
+                          -0.382683 5.60465e-17 -0.92388,
+                          -2.94719e-16 5.20417e-17 -1,
+                          -2.94719e-16 5.20417e-17 -1,
+                          0.382683 4.01141e-17 -0.92388,
+                          0.382683 4.01141e-17 -0.92388,
+                          0.707107 2.20794e-17 -0.707107,
+                          -2.94719e-16 5.20417e-17 -1,
+                          0.382683 4.01141e-17 -0.92388,
+                          0.382683 4.01141e-17 -0.92388,
+                          0.707107 2.20794e-17 -0.707107,
+                          0.707107 2.20794e-17 -0.707107,
+                          0.92388 6.83392e-19 -0.382683,
+                          0.382683 4.01141e-17 -0.92388,
+                          0.707107 2.20794e-17 -0.707107,
+                          0.707107 2.20794e-17 -0.707107,
+                          0.707107 2.20794e-17 -0.707107,
+                          0.92388 6.83392e-19 -0.382683,
+                          0.92388 6.83392e-19 -0.382683,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16,
+                          7.63278e-17 -1 -2.01228e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -16.6194 -2.25 1.91342,
+                          -7.3806 -2.25 1.91342,
+                          -7 -2.25 -1.51007e-14,
+                          -7 -3.75 -1.54026e-14,
+                          -7 -2.25 -1.51007e-14,
+                          -7.3806 -2.25 1.91342,
+                          -17 -2.25 -1.3321e-14,
+                          -16.6194 -2.25 1.91342,
+                          -7 -2.25 -1.51007e-14,
+                          -7.3806 -2.25 -1.91342,
+                          -17 -2.25 -1.3321e-14,
+                          -7 -2.25 -1.51007e-14,
+                          -7.3806 -3.75 -1.91342,
+                          -7.3806 -2.25 -1.91342,
+                          -7 -2.25 -1.51007e-14,
+                          -7.3806 -3.75 -1.91342,
+                          -7 -2.25 -1.51007e-14,
+                          -7 -3.75 -1.54026e-14,
+                          -15.5355 -2.25 3.53553,
+                          -8.46447 -2.25 3.53553,
+                          -7.3806 -2.25 1.91342,
+                          -7.3806 -3.75 1.91342,
+                          -7.3806 -2.25 1.91342,
+                          -8.46447 -2.25 3.53553,
+                          -16.6194 -2.25 1.91342,
+                          -15.5355 -2.25 3.53553,
+                          -7.3806 -2.25 1.91342,
+                          -7.3806 -3.75 1.91342,
+                          -7 -3.75 -1.54026e-14,
+                          -7.3806 -2.25 1.91342,
+                          -13.9134 -2.25 4.6194,
+                          -10.0866 -2.25 4.6194,
+                          -8.46447 -2.25 3.53553,
+                          -8.46447 -3.75 3.53553,
+                          -8.46447 -2.25 3.53553,
+                          -10.0866 -2.25 4.6194,
+                          -15.5355 -2.25 3.53553,
+                          -13.9134 -2.25 4.6194,
+                          -8.46447 -2.25 3.53553,
+                          -7.3806 -3.75 1.91342,
+                          -8.46447 -2.25 3.53553,
+                          -8.46447 -3.75 3.53553,
+                          -13.9134 -2.25 4.6194,
+                          -12 -2.25 5,
+                          -10.0866 -2.25 4.6194,
+                          -10.0866 -3.75 4.6194,
+                          -10.0866 -2.25 4.6194,
+                          -12 -2.25 5,
+                          -8.46447 -3.75 3.53553,
+                          -10.0866 -2.25 4.6194,
+                          -10.0866 -3.75 4.6194,
+                          -12 -3.75 5,
+                          -12 -2.25 5,
+                          -13.9134 -2.25 4.6194,
+                          -10.0866 -3.75 4.6194,
+                          -12 -2.25 5,
+                          -12 -3.75 5,
+                          -13.9134 -3.75 4.6194,
+                          -13.9134 -2.25 4.6194,
+                          -15.5355 -2.25 3.53553,
+                          -12 -3.75 5,
+                          -13.9134 -2.25 4.6194,
+                          -13.9134 -3.75 4.6194,
+                          -15.5355 -3.75 3.53553,
+                          -15.5355 -2.25 3.53553,
+                          -16.6194 -2.25 1.91342,
+                          -13.9134 -3.75 4.6194,
+                          -15.5355 -2.25 3.53553,
+                          -15.5355 -3.75 3.53553,
+                          -16.6194 -3.75 1.91342,
+                          -16.6194 -2.25 1.91342,
+                          -17 -2.25 -1.3321e-14,
+                          -15.5355 -3.75 3.53553,
+                          -16.6194 -2.25 1.91342,
+                          -16.6194 -3.75 1.91342,
+                          -7.3806 -2.25 -1.91342,
+                          -16.6194 -2.25 -1.91342,
+                          -17 -2.25 -1.3321e-14,
+                          -17 -3.75 -1.36228e-14,
+                          -17 -2.25 -1.3321e-14,
+                          -16.6194 -2.25 -1.91342,
+                          -16.6194 -3.75 1.91342,
+                          -17 -2.25 -1.3321e-14,
+                          -17 -3.75 -1.36228e-14,
+                          -8.46447 -2.25 -3.53553,
+                          -15.5355 -2.25 -3.53553,
+                          -16.6194 -2.25 -1.91342,
+                          -16.6194 -3.75 -1.91342,
+                          -16.6194 -2.25 -1.91342,
+                          -15.5355 -2.25 -3.53553,
+                          -7.3806 -2.25 -1.91342,
+                          -8.46447 -2.25 -3.53553,
+                          -16.6194 -2.25 -1.91342,
+                          -17 -3.75 -1.36228e-14,
+                          -16.6194 -2.25 -1.91342,
+                          -16.6194 -3.75 -1.91342,
+                          -10.0866 -2.25 -4.6194,
+                          -13.9134 -2.25 -4.6194,
+                          -15.5355 -2.25 -3.53553,
+                          -15.5355 -3.75 -3.53553,
+                          -15.5355 -2.25 -3.53553,
+                          -13.9134 -2.25 -4.6194,
+                          -8.46447 -2.25 -3.53553,
+                          -10.0866 -2.25 -4.6194,
+                          -15.5355 -2.25 -3.53553,
+                          -16.6194 -3.75 -1.91342,
+                          -15.5355 -2.25 -3.53553,
+                          -15.5355 -3.75 -3.53553,
+                          -10.0866 -2.25 -4.6194,
+                          -12 -2.25 -5,
+                          -13.9134 -2.25 -4.6194,
+                          -13.9134 -3.75 -4.6194,
+                          -13.9134 -2.25 -4.6194,
+                          -12 -2.25 -5,
+                          -15.5355 -3.75 -3.53553,
+                          -13.9134 -2.25 -4.6194,
+                          -13.9134 -3.75 -4.6194,
+                          -12 -3.75 -5,
+                          -12 -2.25 -5,
+                          -10.0866 -2.25 -4.6194,
+                          -13.9134 -3.75 -4.6194,
+                          -12 -2.25 -5,
+                          -12 -3.75 -5,
+                          -10.0866 -3.75 -4.6194,
+                          -10.0866 -2.25 -4.6194,
+                          -8.46447 -2.25 -3.53553,
+                          -12 -3.75 -5,
+                          -10.0866 -2.25 -4.6194,
+                          -10.0866 -3.75 -4.6194,
+                          -8.46447 -3.75 -3.53553,
+                          -8.46447 -2.25 -3.53553,
+                          -7.3806 -2.25 -1.91342,
+                          -10.0866 -3.75 -4.6194,
+                          -8.46447 -2.25 -3.53553,
+                          -8.46447 -3.75 -3.53553,
+                          -8.46447 -3.75 -3.53553,
+                          -7.3806 -2.25 -1.91342,
+                          -7.3806 -3.75 -1.91342,
+                          -16.6194 -3.75 -1.91342,
+                          -7.3806 -3.75 -1.91342,
+                          -7 -3.75 -1.54026e-14,
+                          -17 -3.75 -1.36228e-14,
+                          -16.6194 -3.75 -1.91342,
+                          -7 -3.75 -1.54026e-14,
+                          -7.3806 -3.75 1.91342,
+                          -17 -3.75 -1.36228e-14,
+                          -7 -3.75 -1.54026e-14,
+                          -15.5355 -3.75 -3.53553,
+                          -8.46447 -3.75 -3.53553,
+                          -7.3806 -3.75 -1.91342,
+                          -16.6194 -3.75 -1.91342,
+                          -15.5355 -3.75 -3.53553,
+                          -7.3806 -3.75 -1.91342,
+                          -13.9134 -3.75 -4.6194,
+                          -10.0866 -3.75 -4.6194,
+                          -8.46447 -3.75 -3.53553,
+                          -15.5355 -3.75 -3.53553,
+                          -13.9134 -3.75 -4.6194,
+                          -8.46447 -3.75 -3.53553,
+                          -13.9134 -3.75 -4.6194,
+                          -12 -3.75 -5,
+                          -10.0866 -3.75 -4.6194,
+                          -7.3806 -3.75 1.91342,
+                          -16.6194 -3.75 1.91342,
+                          -17 -3.75 -1.36228e-14,
+                          -8.46447 -3.75 3.53553,
+                          -15.5355 -3.75 3.53553,
+                          -16.6194 -3.75 1.91342,
+                          -7.3806 -3.75 1.91342,
+                          -8.46447 -3.75 3.53553,
+                          -16.6194 -3.75 1.91342,
+                          -10.0866 -3.75 4.6194,
+                          -13.9134 -3.75 4.6194,
+                          -15.5355 -3.75 3.53553,
+                          -8.46447 -3.75 3.53553,
+                          -10.0866 -3.75 4.6194,
+                          -15.5355 -3.75 3.53553,
+                          -10.0866 -3.75 4.6194,
+                          -12 -3.75 5,
+                          -13.9134 -3.75 4.6194 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/proximal_pinky.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/proximal_pinky.iv
new file mode 100644
index 0000000000000000000000000000000000000000..229e19227e87c60e6df638eb0696c8728902c9a3
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/proximal_pinky.iv
@@ -0,0 +1,1215 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+    Separator {
+        Normal {
+            vector      [ 1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          -1 2.44929e-16 -7.34031e-17,
+                          -1 2.44929e-16 -7.34031e-17,
+                          -0.809017 0.587785 -3.78302e-17,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          -0.809017 -0.587785 -8.09384e-17,
+                          -0.809017 -0.587785 -8.09384e-17,
+                          -1 0 -7.34031e-17,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          -0.809017 -0.587785 -8.09384e-17,
+                          -1 0 -7.34031e-17,
+                          -1 0 -7.34031e-17,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          -0.809017 0.587785 -3.78302e-17,
+                          -0.809017 0.587785 -3.78302e-17,
+                          -0.309017 0.951057 1.21924e-17,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          -0.809017 0.587785 -3.78302e-17,
+                          -1 2.44929e-16 -7.34031e-17,
+                          -0.809017 0.587785 -3.78302e-17,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          -0.309017 0.951057 1.21924e-17,
+                          -0.309017 0.951057 1.21924e-17,
+                          0.309017 0.951057 5.7558e-17,
+                          -0.809017 0.587785 -3.78302e-17,
+                          -0.309017 0.951057 1.21924e-17,
+                          -0.309017 0.951057 1.21924e-17,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          0.309017 0.951057 5.7558e-17,
+                          0.309017 0.951057 5.7558e-17,
+                          0.809017 0.587785 8.09384e-17,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          -0.309017 0.951057 1.21924e-17,
+                          0.309017 0.951057 5.7558e-17,
+                          0.309017 0.951057 5.7558e-17,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          0.809017 0.587785 8.09384e-17,
+                          0.809017 0.587785 8.09384e-17,
+                          1 -1.22465e-16 7.34031e-17,
+                          0.309017 0.951057 5.7558e-17,
+                          0.809017 0.587785 8.09384e-17,
+                          0.809017 0.587785 8.09384e-17,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1 -1.22465e-16 7.34031e-17,
+                          1 -1.22465e-16 7.34031e-17,
+                          0.809017 -0.587785 3.78302e-17,
+                          0.809017 0.587785 8.09384e-17,
+                          1 -1.22465e-16 7.34031e-17,
+                          1 -1.22465e-16 7.34031e-17,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          0.809017 -0.587785 3.78302e-17,
+                          0.809017 -0.587785 3.78302e-17,
+                          0.309017 -0.951057 -1.21924e-17,
+                          1 -1.22465e-16 7.34031e-17,
+                          0.809017 -0.587785 3.78302e-17,
+                          0.809017 -0.587785 3.78302e-17,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          0.309017 -0.951057 -1.21924e-17,
+                          0.309017 -0.951057 -1.21924e-17,
+                          -0.309017 -0.951057 -5.7558e-17,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          0.809017 -0.587785 3.78302e-17,
+                          0.309017 -0.951057 -1.21924e-17,
+                          0.309017 -0.951057 -1.21924e-17,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          -0.309017 -0.951057 -5.7558e-17,
+                          -0.309017 -0.951057 -5.7558e-17,
+                          -0.809017 -0.587785 -8.09384e-17,
+                          0.309017 -0.951057 -1.21924e-17,
+                          -0.309017 -0.951057 -5.7558e-17,
+                          -0.309017 -0.951057 -5.7558e-17,
+                          -0.309017 -0.951057 -5.7558e-17,
+                          -0.809017 -0.587785 -8.09384e-17,
+                          -0.809017 -0.587785 -8.09384e-17,
+                          -5.55112e-17 -1 -3.667e-17,
+                          -5.55112e-17 -1 -3.667e-17,
+                          -5.55112e-17 -1 -3.667e-17,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          -1 0 -7.34031e-17,
+                          -1 0 -7.34031e-17,
+                          -1 0 -7.34031e-17,
+                          -2.39208e-16 -1 -3.667e-17,
+                          -2.39208e-16 -1 -3.667e-17,
+                          0.382683 -0.92388 -5.78851e-18,
+                          -5.55112e-17 -1 -3.667e-17,
+                          -5.55112e-17 -1 -3.667e-17,
+                          -5.55112e-17 -1 -3.667e-17,
+                          -5.55112e-17 -1 -3.667e-17,
+                          -5.55112e-17 -1 -3.667e-17,
+                          -5.55112e-17 -1 -3.667e-17,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          0.382683 -0.92388 -5.78851e-18,
+                          0.382683 -0.92388 -5.78851e-18,
+                          0.707107 -0.707107 2.59742e-17,
+                          0.382683 -0.92388 -5.78851e-18,
+                          -2.39208e-16 -1 -3.667e-17,
+                          0.382683 -0.92388 -5.78851e-18,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          0.707107 -0.707107 2.59742e-17,
+                          0.707107 -0.707107 2.59742e-17,
+                          0.92388 -0.382683 5.37826e-17,
+                          0.382683 -0.92388 -5.78851e-18,
+                          0.707107 -0.707107 2.59742e-17,
+                          0.707107 -0.707107 2.59742e-17,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          0.92388 -0.382683 5.37826e-17,
+                          0.92388 -0.382683 5.37826e-17,
+                          1 -2.44929e-16 7.34031e-17,
+                          0.707107 -0.707107 2.59742e-17,
+                          0.92388 -0.382683 5.37826e-17,
+                          0.92388 -0.382683 5.37826e-17,
+                          1 0 7.34031e-17,
+                          1 0 7.34031e-17,
+                          1 0 7.34031e-17,
+                          1 0 7.34031e-17,
+                          1 0 7.34031e-17,
+                          1 0 7.34031e-17,
+                          0.92388 -0.382683 5.37826e-17,
+                          1 -2.44929e-16 7.34031e-17,
+                          1 -2.44929e-16 7.34031e-17,
+                          5.55112e-17 1 3.667e-17,
+                          5.55112e-17 1 3.667e-17,
+                          5.55112e-17 1 3.667e-17,
+                          -1 0 -7.34031e-17,
+                          -1 0 -7.34031e-17,
+                          -1 0 -7.34031e-17,
+                          5.55112e-17 1 3.667e-17,
+                          5.55112e-17 1 3.667e-17,
+                          5.55112e-17 1 3.667e-17,
+                          5.55112e-17 1 3.667e-17,
+                          5.55112e-17 1 3.667e-17,
+                          5.55112e-17 1 3.667e-17,
+                          5.55112e-17 1 3.667e-17,
+                          5.55112e-17 1 3.667e-17,
+                          5.55112e-17 1 3.667e-17,
+                          5.55112e-17 1 3.667e-17,
+                          5.55112e-17 1 3.667e-17,
+                          5.55112e-17 1 3.667e-17,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          1 2.44929e-16 7.34031e-17,
+                          1 2.44929e-16 7.34031e-17,
+                          0.809017 0.587785 8.09384e-17,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          0.809017 -0.587785 3.78302e-17,
+                          0.809017 -0.587785 3.78302e-17,
+                          1 0 7.34031e-17,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          0.809017 -0.587785 3.78302e-17,
+                          1 0 7.34031e-17,
+                          1 0 7.34031e-17,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          0.809017 0.587785 8.09384e-17,
+                          0.809017 0.587785 8.09384e-17,
+                          0.309017 0.951057 5.7558e-17,
+                          0.809017 0.587785 8.09384e-17,
+                          1 2.44929e-16 7.34031e-17,
+                          0.809017 0.587785 8.09384e-17,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          0.309017 0.951057 5.7558e-17,
+                          0.309017 0.951057 5.7558e-17,
+                          -0.309017 0.951057 1.21924e-17,
+                          0.809017 0.587785 8.09384e-17,
+                          0.309017 0.951057 5.7558e-17,
+                          0.309017 0.951057 5.7558e-17,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -0.309017 0.951057 1.21924e-17,
+                          -0.309017 0.951057 1.21924e-17,
+                          -0.809017 0.587785 -3.78302e-17,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          0.309017 0.951057 5.7558e-17,
+                          -0.309017 0.951057 1.21924e-17,
+                          -0.309017 0.951057 1.21924e-17,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -0.809017 0.587785 -3.78302e-17,
+                          -0.809017 0.587785 -3.78302e-17,
+                          -1 -1.22465e-16 -7.34031e-17,
+                          -0.309017 0.951057 1.21924e-17,
+                          -0.809017 0.587785 -3.78302e-17,
+                          -0.809017 0.587785 -3.78302e-17,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1 -1.22465e-16 -7.34031e-17,
+                          -1 -1.22465e-16 -7.34031e-17,
+                          -0.809017 -0.587785 -8.09384e-17,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -0.809017 0.587785 -3.78302e-17,
+                          -1 -1.22465e-16 -7.34031e-17,
+                          -1 -1.22465e-16 -7.34031e-17,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -0.809017 -0.587785 -8.09384e-17,
+                          -0.809017 -0.587785 -8.09384e-17,
+                          -0.309017 -0.951057 -5.7558e-17,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1 -1.22465e-16 -7.34031e-17,
+                          -0.809017 -0.587785 -8.09384e-17,
+                          -0.809017 -0.587785 -8.09384e-17,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -0.309017 -0.951057 -5.7558e-17,
+                          -0.309017 -0.951057 -5.7558e-17,
+                          0.309017 -0.951057 -1.21924e-17,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -0.809017 -0.587785 -8.09384e-17,
+                          -0.309017 -0.951057 -5.7558e-17,
+                          -0.309017 -0.951057 -5.7558e-17,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          0.309017 -0.951057 -1.21924e-17,
+                          0.309017 -0.951057 -1.21924e-17,
+                          0.809017 -0.587785 3.78302e-17,
+                          -0.309017 -0.951057 -5.7558e-17,
+                          0.309017 -0.951057 -1.21924e-17,
+                          0.309017 -0.951057 -1.21924e-17,
+                          0.309017 -0.951057 -1.21924e-17,
+                          0.809017 -0.587785 3.78302e-17,
+                          0.809017 -0.587785 3.78302e-17,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -5.55112e-17 -1 -3.667e-17,
+                          -5.55112e-17 -1 -3.667e-17,
+                          -5.55112e-17 -1 -3.667e-17,
+                          -5.55112e-17 -1 -3.667e-17,
+                          -5.55112e-17 -1 -3.667e-17,
+                          -5.55112e-17 -1 -3.667e-17,
+                          -5.55112e-17 -1 -3.667e-17,
+                          -5.55112e-17 -1 -3.667e-17,
+                          -5.55112e-17 -1 -3.667e-17,
+                          1 0 7.34031e-17,
+                          1 0 7.34031e-17,
+                          1 0 7.34031e-17,
+                          1 0 7.34031e-17,
+                          1 0 7.34031e-17,
+                          1 0 7.34031e-17,
+                          5.55112e-17 1 3.667e-17,
+                          5.55112e-17 1 3.667e-17,
+                          5.55112e-17 1 3.667e-17,
+                          1 -2.44929e-16 7.34031e-17,
+                          1 -2.44929e-16 7.34031e-17,
+                          0.92388 -0.382683 5.37826e-17,
+                          0.92388 -0.382683 5.37826e-17,
+                          0.92388 -0.382683 5.37826e-17,
+                          0.707107 -0.707107 2.59742e-17,
+                          0.92388 -0.382683 5.37826e-17,
+                          1 -2.44929e-16 7.34031e-17,
+                          0.92388 -0.382683 5.37826e-17,
+                          0.707107 -0.707107 2.59742e-17,
+                          0.707107 -0.707107 2.59742e-17,
+                          0.382683 -0.92388 -5.78851e-18,
+                          0.92388 -0.382683 5.37826e-17,
+                          0.707107 -0.707107 2.59742e-17,
+                          0.707107 -0.707107 2.59742e-17,
+                          0.382683 -0.92388 -5.78851e-18,
+                          0.382683 -0.92388 -5.78851e-18,
+                          -2.39208e-16 -1 -3.667e-17,
+                          0.707107 -0.707107 2.59742e-17,
+                          0.382683 -0.92388 -5.78851e-18,
+                          0.382683 -0.92388 -5.78851e-18,
+                          0.382683 -0.92388 -5.78851e-18,
+                          -2.39208e-16 -1 -3.667e-17,
+                          -2.39208e-16 -1 -3.667e-17,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1 0 7.34031e-17,
+                          1 0 7.34031e-17,
+                          1 0 7.34031e-17,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          1 0 7.34031e-17,
+                          1 0 7.34031e-17,
+                          1 0 7.34031e-17,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          -1.46891e-16 9.56194e-17 1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1,
+                          1.46891e-16 -9.56194e-17 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 0.856699 -2.0597 -5,
+                          0.598674 -0.434958 -5,
+                          0.74 -7.10543e-15 -5,
+                          0.74 -7.10543e-15 -2.8,
+                          0.74 -7.10543e-15 -5,
+                          0.598674 -0.434958 -5,
+                          2.4 2.25 -5,
+                          0.74 -7.10543e-15 -5,
+                          0.598674 0.434958 -5,
+                          0.598674 0.434958 -2.8,
+                          0.598674 0.434958 -5,
+                          0.74 -7.10543e-15 -5,
+                          2.4 2.25 -5,
+                          0.856699 -2.0597 -5,
+                          0.74 -7.10543e-15 -5,
+                          0.598674 0.434958 -2.8,
+                          0.74 -7.10543e-15 -5,
+                          0.74 -7.10543e-15 -2.8,
+                          -0.1 -2.25 -5,
+                          0.228666 -0.703784 -5,
+                          0.598674 -0.434958 -5,
+                          0.598674 -0.434958 -2.8,
+                          0.598674 -0.434958 -5,
+                          0.228666 -0.703784 -5,
+                          0.856699 -2.0597 -5,
+                          -0.1 -2.25 -5,
+                          0.598674 -0.434958 -5,
+                          0.598674 -0.434958 -2.8,
+                          0.74 -7.10543e-15 -2.8,
+                          0.598674 -0.434958 -5,
+                          -0.1 -2.25 -5,
+                          -0.228666 -0.703784 -5,
+                          0.228666 -0.703784 -5,
+                          0.228666 -0.703784 -2.8,
+                          0.228666 -0.703784 -5,
+                          -0.228666 -0.703784 -5,
+                          0.598674 -0.434958 -2.8,
+                          0.228666 -0.703784 -5,
+                          0.228666 -0.703784 -2.8,
+                          -32.25 -2.25 -5,
+                          -0.598674 -0.434958 -5,
+                          -0.228666 -0.703784 -5,
+                          -0.228666 -0.703784 -2.8,
+                          -0.228666 -0.703784 -5,
+                          -0.598674 -0.434958 -5,
+                          -0.1 -2.25 -5,
+                          -32.25 -2.25 -5,
+                          -0.228666 -0.703784 -5,
+                          0.228666 -0.703784 -2.8,
+                          -0.228666 -0.703784 -5,
+                          -0.228666 -0.703784 -2.8,
+                          -32.25 -2.25 -5,
+                          -0.74 -7.10543e-15 -5,
+                          -0.598674 -0.434958 -5,
+                          -0.598674 -0.434958 -2.8,
+                          -0.598674 -0.434958 -5,
+                          -0.74 -7.10543e-15 -5,
+                          -0.228666 -0.703784 -2.8,
+                          -0.598674 -0.434958 -5,
+                          -0.598674 -0.434958 -2.8,
+                          -32.25 -2.25 -5,
+                          -0.598674 0.434958 -5,
+                          -0.74 -7.10543e-15 -5,
+                          -0.74 -7.10543e-15 -2.8,
+                          -0.74 -7.10543e-15 -5,
+                          -0.598674 0.434958 -5,
+                          -0.598674 -0.434958 -2.8,
+                          -0.74 -7.10543e-15 -5,
+                          -0.74 -7.10543e-15 -2.8,
+                          -32.25 -2.25 -5,
+                          -0.228666 0.703784 -5,
+                          -0.598674 0.434958 -5,
+                          -0.598674 0.434958 -2.8,
+                          -0.598674 0.434958 -5,
+                          -0.228666 0.703784 -5,
+                          -0.74 -7.10543e-15 -2.8,
+                          -0.598674 0.434958 -5,
+                          -0.598674 0.434958 -2.8,
+                          2.4 2.25 -5,
+                          0.228666 0.703784 -5,
+                          -0.228666 0.703784 -5,
+                          -0.228666 0.703784 -2.8,
+                          -0.228666 0.703784 -5,
+                          0.228666 0.703784 -5,
+                          2.4 2.25 -5,
+                          -0.228666 0.703784 -5,
+                          -32.25 -2.25 -5,
+                          -0.598674 0.434958 -2.8,
+                          -0.228666 0.703784 -5,
+                          -0.228666 0.703784 -2.8,
+                          2.4 2.25 -5,
+                          0.598674 0.434958 -5,
+                          0.228666 0.703784 -5,
+                          0.228666 0.703784 -2.8,
+                          0.228666 0.703784 -5,
+                          0.598674 0.434958 -5,
+                          -0.228666 0.703784 -2.8,
+                          0.228666 0.703784 -5,
+                          0.228666 0.703784 -2.8,
+                          0.228666 0.703784 -2.8,
+                          0.598674 0.434958 -5,
+                          0.598674 0.434958 -2.8,
+                          -32.25 -2.25 5,
+                          -32.25 -2.25 -5,
+                          -0.1 -2.25 -5,
+                          -32.25 2.25 -5,
+                          2.4 2.25 -5,
+                          -32.25 -2.25 -5,
+                          -32.25 -2.25 5,
+                          -32.25 2.25 -5,
+                          -32.25 -2.25 -5,
+                          -0.1 -2.25 -2.8,
+                          -0.1 -2.25 -5,
+                          0.856699 -2.0597 -5,
+                          -2.25 -2.25 -2.8,
+                          -32.25 -2.25 5,
+                          -0.1 -2.25 -5,
+                          -0.1 -2.25 -2.8,
+                          -2.25 -2.25 -2.8,
+                          -0.1 -2.25 -5,
+                          2.4 2.25 -5,
+                          1.66777 -1.51777 -5,
+                          0.856699 -2.0597 -5,
+                          0.856699 -2.0597 -2.8,
+                          0.856699 -2.0597 -5,
+                          1.66777 -1.51777 -5,
+                          0.856699 -2.0597 -2.8,
+                          -0.1 -2.25 -2.8,
+                          0.856699 -2.0597 -5,
+                          2.4 2.25 -5,
+                          2.2097 -0.706699 -5,
+                          1.66777 -1.51777 -5,
+                          1.66777 -1.51777 -2.8,
+                          1.66777 -1.51777 -5,
+                          2.2097 -0.706699 -5,
+                          0.856699 -2.0597 -2.8,
+                          1.66777 -1.51777 -5,
+                          1.66777 -1.51777 -2.8,
+                          2.4 2.25 -5,
+                          2.4 0.25 -5,
+                          2.2097 -0.706699 -5,
+                          2.2097 -0.706699 -2.8,
+                          2.2097 -0.706699 -5,
+                          2.4 0.25 -5,
+                          1.66777 -1.51777 -2.8,
+                          2.2097 -0.706699 -5,
+                          2.2097 -0.706699 -2.8,
+                          2.4 2.25 -2.8,
+                          2.4 0.25 -5,
+                          2.4 2.25 -5,
+                          2.4 2.25 -2.8,
+                          2.4 0.25 -2.8,
+                          2.4 0.25 -5,
+                          2.2097 -0.706699 -2.8,
+                          2.4 0.25 -5,
+                          2.4 0.25 -2.8,
+                          2.4 2.25 -2.8,
+                          2.4 2.25 -5,
+                          -32.25 2.25 -5,
+                          -32.25 2.25 5,
+                          -32.25 2.25 -5,
+                          -32.25 -2.25 5,
+                          2.4 2.25 5,
+                          -32.25 2.25 -5,
+                          -32.25 2.25 5,
+                          -2.25 2.25 2.8,
+                          -32.25 2.25 -5,
+                          2.4 2.25 5,
+                          -2.25 2.25 -2.8,
+                          2.4 2.25 -2.8,
+                          -32.25 2.25 -5,
+                          -2.25 2.25 2.8,
+                          -2.25 2.25 -2.8,
+                          -32.25 2.25 -5,
+                          -0.1 -2.25 5,
+                          -0.606764 -0.440835 5,
+                          -0.75 -7.10543e-15 5,
+                          -0.75 -7.10543e-15 2.8,
+                          -0.75 -7.10543e-15 5,
+                          -0.606764 -0.440835 5,
+                          -32.25 2.25 5,
+                          -0.75 -7.10543e-15 5,
+                          -0.606764 0.440835 5,
+                          -0.606764 0.440835 2.8,
+                          -0.606764 0.440835 5,
+                          -0.75 -7.10543e-15 5,
+                          -0.1 -2.25 5,
+                          -0.75 -7.10543e-15 5,
+                          -32.25 2.25 5,
+                          -0.606764 0.440835 2.8,
+                          -0.75 -7.10543e-15 5,
+                          -0.75 -7.10543e-15 2.8,
+                          -0.1 -2.25 5,
+                          -0.231756 -0.713294 5,
+                          -0.606764 -0.440835 5,
+                          -0.606764 -0.440835 2.8,
+                          -0.606764 -0.440835 5,
+                          -0.231756 -0.713294 5,
+                          -0.606764 -0.440835 2.8,
+                          -0.75 -7.10543e-15 2.8,
+                          -0.606764 -0.440835 5,
+                          -0.1 -2.25 5,
+                          0.231756 -0.713294 5,
+                          -0.231756 -0.713294 5,
+                          -0.231756 -0.713294 2.8,
+                          -0.231756 -0.713294 5,
+                          0.231756 -0.713294 5,
+                          -0.606764 -0.440835 2.8,
+                          -0.231756 -0.713294 5,
+                          -0.231756 -0.713294 2.8,
+                          0.856699 -2.0597 5,
+                          0.606764 -0.440835 5,
+                          0.231756 -0.713294 5,
+                          0.231756 -0.713294 2.8,
+                          0.231756 -0.713294 5,
+                          0.606764 -0.440835 5,
+                          -0.1 -2.25 5,
+                          0.856699 -2.0597 5,
+                          0.231756 -0.713294 5,
+                          -0.231756 -0.713294 2.8,
+                          0.231756 -0.713294 5,
+                          0.231756 -0.713294 2.8,
+                          0.856699 -2.0597 5,
+                          0.75 -7.10543e-15 5,
+                          0.606764 -0.440835 5,
+                          0.606764 -0.440835 2.8,
+                          0.606764 -0.440835 5,
+                          0.75 -7.10543e-15 5,
+                          0.231756 -0.713294 2.8,
+                          0.606764 -0.440835 5,
+                          0.606764 -0.440835 2.8,
+                          1.66777 -1.51777 5,
+                          0.606764 0.440835 5,
+                          0.75 -7.10543e-15 5,
+                          0.75 -7.10543e-15 2.8,
+                          0.75 -7.10543e-15 5,
+                          0.606764 0.440835 5,
+                          0.856699 -2.0597 5,
+                          1.66777 -1.51777 5,
+                          0.75 -7.10543e-15 5,
+                          0.606764 -0.440835 2.8,
+                          0.75 -7.10543e-15 5,
+                          0.75 -7.10543e-15 2.8,
+                          2.2097 -0.706699 5,
+                          0.231756 0.713294 5,
+                          0.606764 0.440835 5,
+                          0.606764 0.440835 2.8,
+                          0.606764 0.440835 5,
+                          0.231756 0.713294 5,
+                          1.66777 -1.51777 5,
+                          2.2097 -0.706699 5,
+                          0.606764 0.440835 5,
+                          0.75 -7.10543e-15 2.8,
+                          0.606764 0.440835 5,
+                          0.606764 0.440835 2.8,
+                          -32.25 2.25 5,
+                          -0.231756 0.713294 5,
+                          0.231756 0.713294 5,
+                          0.231756 0.713294 2.8,
+                          0.231756 0.713294 5,
+                          -0.231756 0.713294 5,
+                          2.4 2.25 5,
+                          -32.25 2.25 5,
+                          0.231756 0.713294 5,
+                          2.4 0.25 5,
+                          2.4 2.25 5,
+                          0.231756 0.713294 5,
+                          2.2097 -0.706699 5,
+                          2.4 0.25 5,
+                          0.231756 0.713294 5,
+                          0.606764 0.440835 2.8,
+                          0.231756 0.713294 5,
+                          0.231756 0.713294 2.8,
+                          -32.25 2.25 5,
+                          -0.606764 0.440835 5,
+                          -0.231756 0.713294 5,
+                          -0.231756 0.713294 2.8,
+                          -0.231756 0.713294 5,
+                          -0.606764 0.440835 5,
+                          0.231756 0.713294 2.8,
+                          -0.231756 0.713294 5,
+                          -0.231756 0.713294 2.8,
+                          -0.231756 0.713294 2.8,
+                          -0.606764 0.440835 5,
+                          -0.606764 0.440835 2.8,
+                          -0.1 -2.25 5,
+                          -32.25 2.25 5,
+                          -32.25 -2.25 5,
+                          -0.1 -2.25 2.8,
+                          -0.1 -2.25 5,
+                          -32.25 -2.25 5,
+                          -2.25 -2.25 2.8,
+                          -0.1 -2.25 2.8,
+                          -32.25 -2.25 5,
+                          -2.25 -2.25 -2.8,
+                          -2.25 -2.25 2.8,
+                          -32.25 -2.25 5,
+                          2.4 0.25 2.8,
+                          2.4 2.25 5,
+                          2.4 0.25 5,
+                          2.4 2.25 2.8,
+                          2.4 2.25 5,
+                          2.4 0.25 2.8,
+                          -2.25 2.25 2.8,
+                          2.4 2.25 5,
+                          2.4 2.25 2.8,
+                          2.4 0.25 2.8,
+                          2.4 0.25 5,
+                          2.2097 -0.706699 5,
+                          2.2097 -0.706699 2.8,
+                          2.2097 -0.706699 5,
+                          1.66777 -1.51777 5,
+                          2.2097 -0.706699 2.8,
+                          2.4 0.25 2.8,
+                          2.2097 -0.706699 5,
+                          1.66777 -1.51777 2.8,
+                          1.66777 -1.51777 5,
+                          0.856699 -2.0597 5,
+                          2.2097 -0.706699 2.8,
+                          1.66777 -1.51777 5,
+                          1.66777 -1.51777 2.8,
+                          0.856699 -2.0597 2.8,
+                          0.856699 -2.0597 5,
+                          -0.1 -2.25 5,
+                          1.66777 -1.51777 2.8,
+                          0.856699 -2.0597 5,
+                          0.856699 -2.0597 2.8,
+                          0.856699 -2.0597 2.8,
+                          -0.1 -2.25 5,
+                          -0.1 -2.25 2.8,
+                          -0.231756 -0.713294 2.8,
+                          -0.1 -2.25 2.8,
+                          -2.25 -2.25 2.8,
+                          0.231756 -0.713294 2.8,
+                          0.606764 -0.440835 2.8,
+                          -0.1 -2.25 2.8,
+                          0.856699 -2.0597 2.8,
+                          -0.1 -2.25 2.8,
+                          0.606764 -0.440835 2.8,
+                          -0.231756 -0.713294 2.8,
+                          0.231756 -0.713294 2.8,
+                          -0.1 -2.25 2.8,
+                          -2.25 2.25 2.8,
+                          -2.25 -2.25 2.8,
+                          -2.25 -2.25 -2.8,
+                          -0.606764 0.440835 2.8,
+                          -2.25 -2.25 2.8,
+                          -2.25 2.25 2.8,
+                          -0.606764 0.440835 2.8,
+                          -0.75 -7.10543e-15 2.8,
+                          -2.25 -2.25 2.8,
+                          -0.606764 -0.440835 2.8,
+                          -2.25 -2.25 2.8,
+                          -0.75 -7.10543e-15 2.8,
+                          -0.606764 -0.440835 2.8,
+                          -0.231756 -0.713294 2.8,
+                          -2.25 -2.25 2.8,
+                          -2.25 2.25 -2.8,
+                          -2.25 -2.25 -2.8,
+                          -0.1 -2.25 -2.8,
+                          -2.25 2.25 2.8,
+                          -2.25 -2.25 -2.8,
+                          -2.25 2.25 -2.8,
+                          -0.74 -7.10543e-15 -2.8,
+                          -2.25 2.25 -2.8,
+                          -0.1 -2.25 -2.8,
+                          -0.598674 -0.434958 -2.8,
+                          -0.74 -7.10543e-15 -2.8,
+                          -0.1 -2.25 -2.8,
+                          -0.228666 -0.703784 -2.8,
+                          -0.598674 -0.434958 -2.8,
+                          -0.1 -2.25 -2.8,
+                          0.228666 -0.703784 -2.8,
+                          -0.228666 -0.703784 -2.8,
+                          -0.1 -2.25 -2.8,
+                          0.856699 -2.0597 -2.8,
+                          0.228666 -0.703784 -2.8,
+                          -0.1 -2.25 -2.8,
+                          -2.25 2.25 -2.8,
+                          2.4 0.25 -2.8,
+                          2.4 2.25 -2.8,
+                          0.228666 0.703784 -2.8,
+                          2.4 0.25 -2.8,
+                          -2.25 2.25 -2.8,
+                          2.2097 -0.706699 -2.8,
+                          2.4 0.25 -2.8,
+                          0.228666 0.703784 -2.8,
+                          2.2097 -0.706699 2.8,
+                          2.4 2.25 2.8,
+                          2.4 0.25 2.8,
+                          -0.231756 0.713294 2.8,
+                          -2.25 2.25 2.8,
+                          2.4 2.25 2.8,
+                          0.231756 0.713294 2.8,
+                          -0.231756 0.713294 2.8,
+                          2.4 2.25 2.8,
+                          0.606764 0.440835 2.8,
+                          0.231756 0.713294 2.8,
+                          2.4 2.25 2.8,
+                          0.75 -7.10543e-15 2.8,
+                          0.606764 0.440835 2.8,
+                          2.4 2.25 2.8,
+                          0.856699 -2.0597 2.8,
+                          0.75 -7.10543e-15 2.8,
+                          2.4 2.25 2.8,
+                          1.66777 -1.51777 2.8,
+                          0.856699 -2.0597 2.8,
+                          2.4 2.25 2.8,
+                          2.2097 -0.706699 2.8,
+                          1.66777 -1.51777 2.8,
+                          2.4 2.25 2.8,
+                          -0.228666 0.703784 -2.8,
+                          0.228666 0.703784 -2.8,
+                          -2.25 2.25 -2.8,
+                          -0.598674 0.434958 -2.8,
+                          -0.228666 0.703784 -2.8,
+                          -2.25 2.25 -2.8,
+                          -0.74 -7.10543e-15 -2.8,
+                          -0.598674 0.434958 -2.8,
+                          -2.25 2.25 -2.8,
+                          -0.231756 0.713294 2.8,
+                          -0.606764 0.440835 2.8,
+                          -2.25 2.25 2.8,
+                          1.66777 -1.51777 -2.8,
+                          0.598674 0.434958 -2.8,
+                          0.74 -7.10543e-15 -2.8,
+                          0.856699 -2.0597 -2.8,
+                          0.74 -7.10543e-15 -2.8,
+                          0.598674 -0.434958 -2.8,
+                          0.856699 -2.0597 -2.8,
+                          1.66777 -1.51777 -2.8,
+                          0.74 -7.10543e-15 -2.8,
+                          2.2097 -0.706699 -2.8,
+                          0.228666 0.703784 -2.8,
+                          0.598674 0.434958 -2.8,
+                          1.66777 -1.51777 -2.8,
+                          2.2097 -0.706699 -2.8,
+                          0.598674 0.434958 -2.8,
+                          0.856699 -2.0597 -2.8,
+                          0.598674 -0.434958 -2.8,
+                          0.228666 -0.703784 -2.8,
+                          0.856699 -2.0597 2.8,
+                          0.606764 -0.440835 2.8,
+                          0.75 -7.10543e-15 2.8 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0 0 1
+    }
+    Separator {
+        Normal {
+            vector      [ -1 0 -6.88349e-17,
+                          -1 0 -6.88349e-17,
+                          -1 0 -6.88349e-17,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          -0.503871 -0.863779 4.05576e-17,
+                          -0.503871 -0.863779 4.05576e-17,
+                          -0.503871 -0.863779 4.05576e-17,
+                          -0.503871 -0.863779 4.05576e-17,
+                          -0.503871 -0.863779 4.05576e-17,
+                          -0.503871 -0.863779 4.05576e-17,
+                          -0.503871 -0.863779 4.05576e-17,
+                          -0.503871 -0.863779 4.05576e-17,
+                          -0.503871 -0.863779 4.05576e-17,
+                          -1 0 -6.88349e-17,
+                          -1 0 -6.88349e-17,
+                          -1 0 -6.88349e-17,
+                          -0.291162 0.956674 -1.03375e-16,
+                          -0.291162 0.956674 -1.03375e-16,
+                          -0.291162 0.956674 -1.03375e-16,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          -0.291162 0.956674 -1.03375e-16,
+                          -0.291162 0.956674 -1.03375e-16,
+                          -0.291162 0.956674 -1.03375e-16,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.503871 -0.863779 4.05576e-17,
+                          -0.503871 -0.863779 4.05576e-17,
+                          -0.503871 -0.863779 4.05576e-17,
+                          -0.503871 -0.863779 4.05576e-17,
+                          -0.503871 -0.863779 4.05576e-17,
+                          -0.503871 -0.863779 4.05576e-17,
+                          1 0 6.88349e-17,
+                          1 0 6.88349e-17,
+                          1 0 6.88349e-17,
+                          -5.55112e-17 -1 8.71074e-17,
+                          -5.55112e-17 -1 8.71074e-17,
+                          -5.55112e-17 -1 8.71074e-17,
+                          1 0 6.88349e-17,
+                          1 0 6.88349e-17,
+                          1 0 6.88349e-17,
+                          1 0 6.88349e-17,
+                          1 0 6.88349e-17,
+                          1 0 6.88349e-17,
+                          6.13853e-17 -0.707107 -0.707107,
+                          6.13853e-17 -0.707107 -0.707107,
+                          6.13853e-17 -0.707107 -0.707107,
+                          -5.55112e-17 -1 8.71074e-17,
+                          -5.55112e-17 -1 8.71074e-17,
+                          -5.55112e-17 -1 8.71074e-17,
+                          1 0 6.88349e-17,
+                          1 0 6.88349e-17,
+                          1 0 6.88349e-17,
+                          -1.3989e-16 -0.707107 0.707107,
+                          -1.3989e-16 -0.707107 0.707107,
+                          -1.3989e-16 -0.707107 0.707107,
+                          1 0 6.88349e-17,
+                          1 0 6.88349e-17,
+                          1 0 6.88349e-17,
+                          -1.3989e-16 -0.707107 0.707107,
+                          -1.3989e-16 -0.707107 0.707107,
+                          -1.3989e-16 -0.707107 0.707107,
+                          -1.42323e-16 1.34605e-16 1,
+                          -1.42323e-16 1.34605e-16 1,
+                          -1.42323e-16 1.34605e-16 1,
+                          -1.42323e-16 1.34605e-16 1,
+                          -1.42323e-16 1.34605e-16 1,
+                          -1.42323e-16 1.34605e-16 1,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          5.55112e-17 1 -8.71074e-17,
+                          5.55112e-17 1 -8.71074e-17,
+                          5.55112e-17 1 -8.71074e-17,
+                          5.55112e-17 1 -8.71074e-17,
+                          5.55112e-17 1 -8.71074e-17,
+                          5.55112e-17 1 -8.71074e-17,
+                          1 0 6.88349e-17,
+                          1 0 6.88349e-17,
+                          1 0 6.88349e-17,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          1.42323e-16 -1.34605e-16 -1,
+                          1.42323e-16 -1.34605e-16 -1,
+                          1.42323e-16 -1.34605e-16 -1,
+                          1.42323e-16 -1.34605e-16 -1,
+                          1.42323e-16 -1.34605e-16 -1,
+                          1.42323e-16 -1.34605e-16 -1,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          6.13853e-17 -0.707107 -0.707107,
+                          6.13853e-17 -0.707107 -0.707107,
+                          6.13853e-17 -0.707107 -0.707107,
+                          6.13853e-17 -0.707107 -0.707107,
+                          6.13853e-17 -0.707107 -0.707107,
+                          6.13853e-17 -0.707107 -0.707107,
+                          -0.503871 -0.863779 4.05576e-17,
+                          -0.503871 -0.863779 4.05576e-17,
+                          -0.503871 -0.863779 4.05576e-17,
+                          -1.3989e-16 -0.707107 0.707107,
+                          -1.3989e-16 -0.707107 0.707107,
+                          -1.3989e-16 -0.707107 0.707107,
+                          -0.223376 -1.31204e-16 -0.974732,
+                          -0.223376 -1.31204e-16 -0.974732,
+                          -0.223376 -1.31204e-16 -0.974732,
+                          -0.223376 -1.31204e-16 -0.974732,
+                          -0.223376 -1.31204e-16 -0.974732,
+                          -0.223376 -1.31204e-16 -0.974732,
+                          -0.223376 1.31204e-16 0.974732,
+                          -0.223376 1.31204e-16 0.974732,
+                          -0.223376 1.31204e-16 0.974732,
+                          -0.223376 1.31204e-16 0.974732,
+                          -0.223376 1.31204e-16 0.974732,
+                          -0.223376 1.31204e-16 0.974732 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -43.75 2.75 7.11769,
+                          -43.75 5.75 -4.16326,
+                          -43.75 2.75 -7.11769,
+                          -43.495 2.60127 -7.30843,
+                          -43.75 2.75 -7.11769,
+                          -43.75 5.75 -4.16326,
+                          -31.75 -4.25 7,
+                          -43.75 2.75 7.11769,
+                          -43.75 2.75 -7.11769,
+                          -31.75 -4.25 7,
+                          -43.75 2.75 -7.11769,
+                          -31.75 -4.25 -7,
+                          -43.495 2.60127 -7.30843,
+                          -31.75 -4.25 -7,
+                          -43.75 2.75 -7.11769,
+                          -43.75 2.75 7.11769,
+                          -43.75 5.75 4.16326,
+                          -43.75 5.75 -4.16326,
+                          -20.75 12.75 1.26352,
+                          -43.75 5.75 -4.16326,
+                          -43.75 5.75 4.16326,
+                          -20.75 12.75 -1.26352,
+                          -31.75 1.93915 -10,
+                          -43.75 5.75 -4.16326,
+                          -43.495 2.60127 -7.30843,
+                          -43.75 5.75 -4.16326,
+                          -31.75 1.93915 -10,
+                          -20.75 12.75 -1.26352,
+                          -43.75 5.75 -4.16326,
+                          -20.75 12.75 1.26352,
+                          -43.495 2.60127 7.30843,
+                          -43.75 5.75 4.16326,
+                          -43.75 2.75 7.11769,
+                          -31.75 1.93915 10,
+                          -20.75 12.75 1.26352,
+                          -43.75 5.75 4.16326,
+                          -43.495 2.60127 7.30843,
+                          -31.75 1.93915 10,
+                          -43.75 5.75 4.16326,
+                          -35.4423 -2.09615 9.15385,
+                          -43.75 2.75 7.11769,
+                          -31.75 -4.25 7,
+                          -43.495 2.60127 7.30843,
+                          -43.75 2.75 7.11769,
+                          -35.4423 -2.09615 9.15385,
+                          -10.75 12.75 3,
+                          -10.75 -4.25 7,
+                          -10.75 -4.25 -7,
+                          -31.75 -4.25 7,
+                          -10.75 -4.25 -7,
+                          -10.75 -4.25 7,
+                          -10.75 12.75 -3,
+                          -10.75 12.75 3,
+                          -10.75 -4.25 -7,
+                          -10.75 -1.25 -10,
+                          -10.75 12.75 -3,
+                          -10.75 -4.25 -7,
+                          -31.75 -4.25 -7,
+                          -10.75 -1.25 -10,
+                          -10.75 -4.25 -7,
+                          -31.75 -4.25 7,
+                          -31.75 -4.25 -7,
+                          -10.75 -4.25 -7,
+                          -10.75 5.64201 10,
+                          -10.75 -1.25 10,
+                          -10.75 -4.25 7,
+                          -31.75 -1.25 10,
+                          -10.75 -4.25 7,
+                          -10.75 -1.25 10,
+                          -10.75 12.75 3,
+                          -10.75 5.64201 10,
+                          -10.75 -4.25 7,
+                          -31.75 -1.25 10,
+                          -31.75 -4.25 7,
+                          -10.75 -4.25 7,
+                          -31.75 1.93915 10,
+                          -10.75 -1.25 10,
+                          -10.75 5.64201 10,
+                          -31.75 1.93915 10,
+                          -31.75 -1.25 10,
+                          -10.75 -1.25 10,
+                          -20.75 12.75 1.26352,
+                          -10.75 5.64201 10,
+                          -10.75 12.75 3,
+                          -31.75 1.93915 10,
+                          -10.75 5.64201 10,
+                          -20.75 12.75 1.26352,
+                          -20.75 12.75 -1.26352,
+                          -10.75 12.75 3,
+                          -10.75 12.75 -3,
+                          -20.75 12.75 -1.26352,
+                          -20.75 12.75 1.26352,
+                          -10.75 12.75 3,
+                          -10.75 -1.25 -10,
+                          -10.75 5.64201 -10,
+                          -10.75 12.75 -3,
+                          -20.75 12.75 -1.26352,
+                          -10.75 12.75 -3,
+                          -10.75 5.64201 -10,
+                          -31.75 -1.25 -10,
+                          -10.75 5.64201 -10,
+                          -10.75 -1.25 -10,
+                          -31.75 -1.25 -10,
+                          -31.75 1.93915 -10,
+                          -10.75 5.64201 -10,
+                          -20.75 12.75 -1.26352,
+                          -10.75 5.64201 -10,
+                          -31.75 1.93915 -10,
+                          -31.75 -1.25 -10,
+                          -10.75 -1.25 -10,
+                          -31.75 -4.25 -7,
+                          -35.4423 -2.09615 -9.15385,
+                          -31.75 -1.25 -10,
+                          -31.75 -4.25 -7,
+                          -35.4423 -2.09615 -9.15385,
+                          -31.75 -4.25 -7,
+                          -43.495 2.60127 -7.30843,
+                          -35.4423 -2.09615 9.15385,
+                          -31.75 -4.25 7,
+                          -31.75 -1.25 10,
+                          -35.4423 -2.09615 -9.15385,
+                          -31.75 1.93915 -10,
+                          -31.75 -1.25 -10,
+                          -35.4423 -2.09615 -9.15385,
+                          -43.495 2.60127 -7.30843,
+                          -31.75 1.93915 -10,
+                          -43.495 2.60127 7.30843,
+                          -31.75 -1.25 10,
+                          -31.75 1.93915 10,
+                          -43.495 2.60127 7.30843,
+                          -35.4423 -2.09615 9.15385,
+                          -31.75 -1.25 10 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/proximal_ring.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/proximal_ring.iv
new file mode 100644
index 0000000000000000000000000000000000000000..46ee278564f281a7fdd15d80bd92a4a13080d868
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/hands/proximal_ring.iv
@@ -0,0 +1,1215 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0 0 1
+    }
+    Separator {
+        Normal {
+            vector      [ -1 -5.55112e-17 -7.89425e-17,
+                          -1 -5.55112e-17 -7.89425e-17,
+                          -1 -5.55112e-17 -7.89425e-17,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          -0.503871 -0.863779 -9.96299e-17,
+                          -0.503871 -0.863779 -9.96299e-17,
+                          -0.503871 -0.863779 -9.96299e-17,
+                          -0.503871 -0.863779 -9.96299e-17,
+                          -0.503871 -0.863779 -9.96299e-17,
+                          -0.503871 -0.863779 -9.96299e-17,
+                          -0.503871 -0.863779 -9.96299e-17,
+                          -0.503871 -0.863779 -9.96299e-17,
+                          -0.503871 -0.863779 -9.96299e-17,
+                          -1 -5.55112e-17 -7.89425e-17,
+                          -1 -5.55112e-17 -7.89425e-17,
+                          -1 -5.55112e-17 -7.89425e-17,
+                          -0.291162 0.956674 4.33049e-17,
+                          -0.291162 0.956674 4.33049e-17,
+                          -0.291162 0.956674 4.33049e-17,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          -0.291162 0.956674 4.33049e-17,
+                          -0.291162 0.956674 4.33049e-17,
+                          -0.291162 0.956674 4.33049e-17,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.503871 -0.863779 -9.96299e-17,
+                          -0.503871 -0.863779 -9.96299e-17,
+                          -0.503871 -0.863779 -9.96299e-17,
+                          -0.503871 -0.863779 -9.96299e-17,
+                          -0.503871 -0.863779 -9.96299e-17,
+                          -0.503871 -0.863779 -9.96299e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          -5.55112e-17 -1 -6.92921e-17,
+                          -5.55112e-17 -1 -6.92921e-17,
+                          -5.55112e-17 -1 -6.92921e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          1.41274e-16 -0.707107 -0.707107,
+                          1.41274e-16 -0.707107 -0.707107,
+                          1.41274e-16 -0.707107 -0.707107,
+                          -5.55112e-17 -1 -6.92921e-17,
+                          -5.55112e-17 -1 -6.92921e-17,
+                          -5.55112e-17 -1 -6.92921e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          -2.19779e-16 -0.707107 0.707107,
+                          -2.19779e-16 -0.707107 0.707107,
+                          -2.19779e-16 -0.707107 0.707107,
+                          1 5.55112e-17 7.89425e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          -2.19779e-16 -0.707107 0.707107,
+                          -2.19779e-16 -0.707107 0.707107,
+                          -2.19779e-16 -0.707107 0.707107,
+                          -2.55303e-16 -3.81639e-17 1,
+                          -2.55303e-16 -3.81639e-17 1,
+                          -2.55303e-16 -3.81639e-17 1,
+                          -2.55303e-16 -3.81639e-17 1,
+                          -2.55303e-16 -3.81639e-17 1,
+                          -2.55303e-16 -3.81639e-17 1,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          -0.122788 0.696364 0.707107,
+                          5.55112e-17 1 6.92921e-17,
+                          5.55112e-17 1 6.92921e-17,
+                          5.55112e-17 1 6.92921e-17,
+                          5.55112e-17 1 6.92921e-17,
+                          5.55112e-17 1 6.92921e-17,
+                          5.55112e-17 1 6.92921e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          2.55303e-16 3.81639e-17 -1,
+                          2.55303e-16 3.81639e-17 -1,
+                          2.55303e-16 3.81639e-17 -1,
+                          2.55303e-16 3.81639e-17 -1,
+                          2.55303e-16 3.81639e-17 -1,
+                          2.55303e-16 3.81639e-17 -1,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          -0.122788 0.696364 -0.707107,
+                          1.41274e-16 -0.707107 -0.707107,
+                          1.41274e-16 -0.707107 -0.707107,
+                          1.41274e-16 -0.707107 -0.707107,
+                          1.41274e-16 -0.707107 -0.707107,
+                          1.41274e-16 -0.707107 -0.707107,
+                          1.41274e-16 -0.707107 -0.707107,
+                          -0.503871 -0.863779 -9.96299e-17,
+                          -0.503871 -0.863779 -9.96299e-17,
+                          -0.503871 -0.863779 -9.96299e-17,
+                          -2.19779e-16 -0.707107 0.707107,
+                          -2.19779e-16 -0.707107 0.707107,
+                          -2.19779e-16 -0.707107 0.707107,
+                          -0.223376 2.47997e-17 -0.974732,
+                          -0.223376 2.47997e-17 -0.974732,
+                          -0.223376 2.47997e-17 -0.974732,
+                          -0.223376 2.47997e-17 -0.974732,
+                          -0.223376 2.47997e-17 -0.974732,
+                          -0.223376 2.47997e-17 -0.974732,
+                          -0.223376 -4.95995e-17 0.974732,
+                          -0.223376 -4.95995e-17 0.974732,
+                          -0.223376 -4.95995e-17 0.974732,
+                          -0.223376 -4.95995e-17 0.974732,
+                          -0.223376 -4.95995e-17 0.974732,
+                          -0.223376 -4.95995e-17 0.974732 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -51.25 2.75 7.11769,
+                          -51.25 5.75 -4.16326,
+                          -51.25 2.75 -7.11769,
+                          -50.995 2.60127 -7.30843,
+                          -51.25 2.75 -7.11769,
+                          -51.25 5.75 -4.16326,
+                          -39.25 -4.25 7,
+                          -51.25 2.75 7.11769,
+                          -51.25 2.75 -7.11769,
+                          -39.25 -4.25 7,
+                          -51.25 2.75 -7.11769,
+                          -39.25 -4.25 -7,
+                          -50.995 2.60127 -7.30843,
+                          -39.25 -4.25 -7,
+                          -51.25 2.75 -7.11769,
+                          -51.25 2.75 7.11769,
+                          -51.25 5.75 4.16326,
+                          -51.25 5.75 -4.16326,
+                          -28.25 12.75 1.26352,
+                          -51.25 5.75 -4.16326,
+                          -51.25 5.75 4.16326,
+                          -28.25 12.75 -1.26352,
+                          -39.25 1.93915 -10,
+                          -51.25 5.75 -4.16326,
+                          -50.995 2.60127 -7.30843,
+                          -51.25 5.75 -4.16326,
+                          -39.25 1.93915 -10,
+                          -28.25 12.75 -1.26352,
+                          -51.25 5.75 -4.16326,
+                          -28.25 12.75 1.26352,
+                          -50.995 2.60127 7.30843,
+                          -51.25 5.75 4.16326,
+                          -51.25 2.75 7.11769,
+                          -39.25 1.93915 10,
+                          -28.25 12.75 1.26352,
+                          -51.25 5.75 4.16326,
+                          -50.995 2.60127 7.30843,
+                          -39.25 1.93915 10,
+                          -51.25 5.75 4.16326,
+                          -42.9423 -2.09615 9.15385,
+                          -51.25 2.75 7.11769,
+                          -39.25 -4.25 7,
+                          -50.995 2.60127 7.30843,
+                          -51.25 2.75 7.11769,
+                          -42.9423 -2.09615 9.15385,
+                          -18.25 12.75 3,
+                          -18.25 -4.25 7,
+                          -18.25 -4.25 -7,
+                          -39.25 -4.25 7,
+                          -18.25 -4.25 -7,
+                          -18.25 -4.25 7,
+                          -18.25 12.75 -3,
+                          -18.25 12.75 3,
+                          -18.25 -4.25 -7,
+                          -18.25 -1.25 -10,
+                          -18.25 12.75 -3,
+                          -18.25 -4.25 -7,
+                          -39.25 -4.25 -7,
+                          -18.25 -1.25 -10,
+                          -18.25 -4.25 -7,
+                          -39.25 -4.25 7,
+                          -39.25 -4.25 -7,
+                          -18.25 -4.25 -7,
+                          -18.25 5.64201 10,
+                          -18.25 -1.25 10,
+                          -18.25 -4.25 7,
+                          -39.25 -1.25 10,
+                          -18.25 -4.25 7,
+                          -18.25 -1.25 10,
+                          -18.25 12.75 3,
+                          -18.25 5.64201 10,
+                          -18.25 -4.25 7,
+                          -39.25 -1.25 10,
+                          -39.25 -4.25 7,
+                          -18.25 -4.25 7,
+                          -39.25 1.93915 10,
+                          -18.25 -1.25 10,
+                          -18.25 5.64201 10,
+                          -39.25 1.93915 10,
+                          -39.25 -1.25 10,
+                          -18.25 -1.25 10,
+                          -28.25 12.75 1.26352,
+                          -18.25 5.64201 10,
+                          -18.25 12.75 3,
+                          -39.25 1.93915 10,
+                          -18.25 5.64201 10,
+                          -28.25 12.75 1.26352,
+                          -28.25 12.75 -1.26352,
+                          -18.25 12.75 3,
+                          -18.25 12.75 -3,
+                          -28.25 12.75 -1.26352,
+                          -28.25 12.75 1.26352,
+                          -18.25 12.75 3,
+                          -18.25 -1.25 -10,
+                          -18.25 5.64201 -10,
+                          -18.25 12.75 -3,
+                          -28.25 12.75 -1.26352,
+                          -18.25 12.75 -3,
+                          -18.25 5.64201 -10,
+                          -39.25 -1.25 -10,
+                          -18.25 5.64201 -10,
+                          -18.25 -1.25 -10,
+                          -39.25 -1.25 -10,
+                          -39.25 1.93915 -10,
+                          -18.25 5.64201 -10,
+                          -28.25 12.75 -1.26352,
+                          -18.25 5.64201 -10,
+                          -39.25 1.93915 -10,
+                          -39.25 -1.25 -10,
+                          -18.25 -1.25 -10,
+                          -39.25 -4.25 -7,
+                          -42.9423 -2.09615 -9.15385,
+                          -39.25 -1.25 -10,
+                          -39.25 -4.25 -7,
+                          -42.9423 -2.09615 -9.15385,
+                          -39.25 -4.25 -7,
+                          -50.995 2.60127 -7.30843,
+                          -42.9423 -2.09615 9.15385,
+                          -39.25 -4.25 7,
+                          -39.25 -1.25 10,
+                          -42.9423 -2.09615 -9.15385,
+                          -39.25 1.93915 -10,
+                          -39.25 -1.25 -10,
+                          -42.9423 -2.09615 -9.15385,
+                          -50.995 2.60127 -7.30843,
+                          -39.25 1.93915 -10,
+                          -50.995 2.60127 7.30843,
+                          -39.25 -1.25 10,
+                          -39.25 1.93915 10,
+                          -50.995 2.60127 7.30843,
+                          -42.9423 -2.09615 9.15385,
+                          -39.25 -1.25 10 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+    Separator {
+        Normal {
+            vector      [ 2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          -1 1.89418e-16 -7.89425e-17,
+                          -1 1.89418e-16 -7.89425e-17,
+                          -0.809017 0.587785 -2.3137e-17,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          -0.809017 -0.587785 -1.04595e-16,
+                          -0.809017 -0.587785 -1.04595e-16,
+                          -1 -5.55112e-17 -7.89425e-17,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          -0.809017 -0.587785 -1.04595e-16,
+                          -1 -5.55112e-17 -7.89425e-17,
+                          -1 -5.55112e-17 -7.89425e-17,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          -0.809017 0.587785 -2.3137e-17,
+                          -0.809017 0.587785 -2.3137e-17,
+                          -0.309017 0.951057 4.15061e-17,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          -0.809017 0.587785 -2.3137e-17,
+                          -1 1.89418e-16 -7.89425e-17,
+                          -0.809017 0.587785 -2.3137e-17,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          -0.309017 0.951057 4.15061e-17,
+                          -0.309017 0.951057 4.15061e-17,
+                          0.309017 0.951057 9.02952e-17,
+                          -0.809017 0.587785 -2.3137e-17,
+                          -0.309017 0.951057 4.15061e-17,
+                          -0.309017 0.951057 4.15061e-17,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          0.309017 0.951057 9.02952e-17,
+                          0.309017 0.951057 9.02952e-17,
+                          0.809017 0.587785 1.04595e-16,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          -0.309017 0.951057 4.15061e-17,
+                          0.309017 0.951057 9.02952e-17,
+                          0.309017 0.951057 9.02952e-17,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          0.809017 0.587785 1.04595e-16,
+                          0.809017 0.587785 1.04595e-16,
+                          1 -6.69535e-17 7.89425e-17,
+                          0.309017 0.951057 9.02952e-17,
+                          0.809017 0.587785 1.04595e-16,
+                          0.809017 0.587785 1.04595e-16,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          1 -6.69535e-17 7.89425e-17,
+                          1 -6.69535e-17 7.89425e-17,
+                          0.809017 -0.587785 2.3137e-17,
+                          0.809017 0.587785 1.04595e-16,
+                          1 -6.69535e-17 7.89425e-17,
+                          1 -6.69535e-17 7.89425e-17,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          0.809017 -0.587785 2.3137e-17,
+                          0.809017 -0.587785 2.3137e-17,
+                          0.309017 -0.951057 -4.15061e-17,
+                          1 -6.69535e-17 7.89425e-17,
+                          0.809017 -0.587785 2.3137e-17,
+                          0.809017 -0.587785 2.3137e-17,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          0.309017 -0.951057 -4.15061e-17,
+                          0.309017 -0.951057 -4.15061e-17,
+                          -0.309017 -0.951057 -9.02952e-17,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          0.809017 -0.587785 2.3137e-17,
+                          0.309017 -0.951057 -4.15061e-17,
+                          0.309017 -0.951057 -4.15061e-17,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          -0.309017 -0.951057 -9.02952e-17,
+                          -0.309017 -0.951057 -9.02952e-17,
+                          -0.809017 -0.587785 -1.04595e-16,
+                          0.309017 -0.951057 -4.15061e-17,
+                          -0.309017 -0.951057 -9.02952e-17,
+                          -0.309017 -0.951057 -9.02952e-17,
+                          -0.309017 -0.951057 -9.02952e-17,
+                          -0.809017 -0.587785 -1.04595e-16,
+                          -0.809017 -0.587785 -1.04595e-16,
+                          -5.55112e-17 -1 -6.92921e-17,
+                          -5.55112e-17 -1 -6.92921e-17,
+                          -5.55112e-17 -1 -6.92921e-17,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          -1 -5.55112e-17 -7.89425e-17,
+                          -1 -5.55112e-17 -7.89425e-17,
+                          -1 -5.55112e-17 -7.89425e-17,
+                          -2.39208e-16 -1 -6.92921e-17,
+                          -2.39208e-16 -1 -6.92921e-17,
+                          0.382683 -0.92388 -3.38075e-17,
+                          -5.55112e-17 -1 -6.92921e-17,
+                          -5.55112e-17 -1 -6.92921e-17,
+                          -5.55112e-17 -1 -6.92921e-17,
+                          -5.55112e-17 -1 -6.92921e-17,
+                          -5.55112e-17 -1 -6.92921e-17,
+                          -5.55112e-17 -1 -6.92921e-17,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          0.382683 -0.92388 -3.38075e-17,
+                          0.382683 -0.92388 -3.38075e-17,
+                          0.707107 -0.707107 6.82391e-18,
+                          0.382683 -0.92388 -3.38075e-17,
+                          -2.39208e-16 -1 -6.92921e-17,
+                          0.382683 -0.92388 -3.38075e-17,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          0.707107 -0.707107 6.82391e-18,
+                          0.707107 -0.707107 6.82391e-18,
+                          0.92388 -0.382683 4.64165e-17,
+                          0.382683 -0.92388 -3.38075e-17,
+                          0.707107 -0.707107 6.82391e-18,
+                          0.707107 -0.707107 6.82391e-18,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          0.92388 -0.382683 4.64165e-17,
+                          0.92388 -0.382683 4.64165e-17,
+                          1 -1.89418e-16 7.89425e-17,
+                          0.707107 -0.707107 6.82391e-18,
+                          0.92388 -0.382683 4.64165e-17,
+                          0.92388 -0.382683 4.64165e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          0.92388 -0.382683 4.64165e-17,
+                          1 -1.89418e-16 7.89425e-17,
+                          1 -1.89418e-16 7.89425e-17,
+                          5.55112e-17 1 6.92921e-17,
+                          5.55112e-17 1 6.92921e-17,
+                          5.55112e-17 1 6.92921e-17,
+                          -1 -5.55112e-17 -7.89425e-17,
+                          -1 -5.55112e-17 -7.89425e-17,
+                          -1 -5.55112e-17 -7.89425e-17,
+                          5.55112e-17 1 6.92921e-17,
+                          5.55112e-17 1 6.92921e-17,
+                          5.55112e-17 1 6.92921e-17,
+                          5.55112e-17 1 6.92921e-17,
+                          5.55112e-17 1 6.92921e-17,
+                          5.55112e-17 1 6.92921e-17,
+                          5.55112e-17 1 6.92921e-17,
+                          5.55112e-17 1 6.92921e-17,
+                          5.55112e-17 1 6.92921e-17,
+                          5.55112e-17 1 6.92921e-17,
+                          5.55112e-17 1 6.92921e-17,
+                          5.55112e-17 1 6.92921e-17,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          1 3.00441e-16 7.89425e-17,
+                          1 3.00441e-16 7.89425e-17,
+                          0.809017 0.587785 1.04595e-16,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          0.809017 -0.587785 2.3137e-17,
+                          0.809017 -0.587785 2.3137e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          0.809017 -0.587785 2.3137e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          0.809017 0.587785 1.04595e-16,
+                          0.809017 0.587785 1.04595e-16,
+                          0.309017 0.951057 9.02952e-17,
+                          0.809017 0.587785 1.04595e-16,
+                          1 3.00441e-16 7.89425e-17,
+                          0.809017 0.587785 1.04595e-16,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          0.309017 0.951057 9.02952e-17,
+                          0.309017 0.951057 9.02952e-17,
+                          -0.309017 0.951057 4.15061e-17,
+                          0.809017 0.587785 1.04595e-16,
+                          0.309017 0.951057 9.02952e-17,
+                          0.309017 0.951057 9.02952e-17,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -0.309017 0.951057 4.15061e-17,
+                          -0.309017 0.951057 4.15061e-17,
+                          -0.809017 0.587785 -2.3137e-17,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          0.309017 0.951057 9.02952e-17,
+                          -0.309017 0.951057 4.15061e-17,
+                          -0.309017 0.951057 4.15061e-17,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -0.809017 0.587785 -2.3137e-17,
+                          -0.809017 0.587785 -2.3137e-17,
+                          -1 -1.77976e-16 -7.89425e-17,
+                          -0.309017 0.951057 4.15061e-17,
+                          -0.809017 0.587785 -2.3137e-17,
+                          -0.809017 0.587785 -2.3137e-17,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -1 -1.77976e-16 -7.89425e-17,
+                          -1 -1.77976e-16 -7.89425e-17,
+                          -0.809017 -0.587785 -1.04595e-16,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -0.809017 0.587785 -2.3137e-17,
+                          -1 -1.77976e-16 -7.89425e-17,
+                          -1 -1.77976e-16 -7.89425e-17,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -0.809017 -0.587785 -1.04595e-16,
+                          -0.809017 -0.587785 -1.04595e-16,
+                          -0.309017 -0.951057 -9.02952e-17,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -1 -1.77976e-16 -7.89425e-17,
+                          -0.809017 -0.587785 -1.04595e-16,
+                          -0.809017 -0.587785 -1.04595e-16,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -0.309017 -0.951057 -9.02952e-17,
+                          -0.309017 -0.951057 -9.02952e-17,
+                          0.309017 -0.951057 -4.15061e-17,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -0.809017 -0.587785 -1.04595e-16,
+                          -0.309017 -0.951057 -9.02952e-17,
+                          -0.309017 -0.951057 -9.02952e-17,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          0.309017 -0.951057 -4.15061e-17,
+                          0.309017 -0.951057 -4.15061e-17,
+                          0.809017 -0.587785 2.3137e-17,
+                          -0.309017 -0.951057 -9.02952e-17,
+                          0.309017 -0.951057 -4.15061e-17,
+                          0.309017 -0.951057 -4.15061e-17,
+                          0.309017 -0.951057 -4.15061e-17,
+                          0.809017 -0.587785 2.3137e-17,
+                          0.809017 -0.587785 2.3137e-17,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -5.55112e-17 -1 -6.92921e-17,
+                          -5.55112e-17 -1 -6.92921e-17,
+                          -5.55112e-17 -1 -6.92921e-17,
+                          -5.55112e-17 -1 -6.92921e-17,
+                          -5.55112e-17 -1 -6.92921e-17,
+                          -5.55112e-17 -1 -6.92921e-17,
+                          -5.55112e-17 -1 -6.92921e-17,
+                          -5.55112e-17 -1 -6.92921e-17,
+                          -5.55112e-17 -1 -6.92921e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          5.55112e-17 1 6.92921e-17,
+                          5.55112e-17 1 6.92921e-17,
+                          5.55112e-17 1 6.92921e-17,
+                          1 -1.89418e-16 7.89425e-17,
+                          1 -1.89418e-16 7.89425e-17,
+                          0.92388 -0.382683 4.64165e-17,
+                          0.92388 -0.382683 4.64165e-17,
+                          0.92388 -0.382683 4.64165e-17,
+                          0.707107 -0.707107 6.82391e-18,
+                          0.92388 -0.382683 4.64165e-17,
+                          1 -1.89418e-16 7.89425e-17,
+                          0.92388 -0.382683 4.64165e-17,
+                          0.707107 -0.707107 6.82391e-18,
+                          0.707107 -0.707107 6.82391e-18,
+                          0.382683 -0.92388 -3.38075e-17,
+                          0.92388 -0.382683 4.64165e-17,
+                          0.707107 -0.707107 6.82391e-18,
+                          0.707107 -0.707107 6.82391e-18,
+                          0.382683 -0.92388 -3.38075e-17,
+                          0.382683 -0.92388 -3.38075e-17,
+                          -2.39208e-16 -1 -6.92921e-17,
+                          0.707107 -0.707107 6.82391e-18,
+                          0.382683 -0.92388 -3.38075e-17,
+                          0.382683 -0.92388 -3.38075e-17,
+                          0.382683 -0.92388 -3.38075e-17,
+                          -2.39208e-16 -1 -6.92921e-17,
+                          -2.39208e-16 -1 -6.92921e-17,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          1 5.55112e-17 7.89425e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          1 5.55112e-17 7.89425e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          1 5.55112e-17 7.89425e-17,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          -2.55303e-16 -5.46953e-18 1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1,
+                          2.55303e-16 5.46953e-18 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 0.856699 -2.0597 -5,
+                          0.598674 -0.434958 -5,
+                          0.74 -2.13163e-14 -5,
+                          0.74 -2.13163e-14 -2.8,
+                          0.74 -2.13163e-14 -5,
+                          0.598674 -0.434958 -5,
+                          2.4 2.25 -5,
+                          0.74 -2.13163e-14 -5,
+                          0.598674 0.434958 -5,
+                          0.598674 0.434958 -2.8,
+                          0.598674 0.434958 -5,
+                          0.74 -2.13163e-14 -5,
+                          2.4 2.25 -5,
+                          0.856699 -2.0597 -5,
+                          0.74 -2.13163e-14 -5,
+                          0.598674 0.434958 -2.8,
+                          0.74 -2.13163e-14 -5,
+                          0.74 -2.13163e-14 -2.8,
+                          -0.1 -2.25 -5,
+                          0.228666 -0.703784 -5,
+                          0.598674 -0.434958 -5,
+                          0.598674 -0.434958 -2.8,
+                          0.598674 -0.434958 -5,
+                          0.228666 -0.703784 -5,
+                          0.856699 -2.0597 -5,
+                          -0.1 -2.25 -5,
+                          0.598674 -0.434958 -5,
+                          0.598674 -0.434958 -2.8,
+                          0.74 -2.13163e-14 -2.8,
+                          0.598674 -0.434958 -5,
+                          -0.1 -2.25 -5,
+                          -0.228666 -0.703784 -5,
+                          0.228666 -0.703784 -5,
+                          0.228666 -0.703784 -2.8,
+                          0.228666 -0.703784 -5,
+                          -0.228666 -0.703784 -5,
+                          0.598674 -0.434958 -2.8,
+                          0.228666 -0.703784 -5,
+                          0.228666 -0.703784 -2.8,
+                          -37.25 -2.25 -5,
+                          -0.598674 -0.434958 -5,
+                          -0.228666 -0.703784 -5,
+                          -0.228666 -0.703784 -2.8,
+                          -0.228666 -0.703784 -5,
+                          -0.598674 -0.434958 -5,
+                          -0.1 -2.25 -5,
+                          -37.25 -2.25 -5,
+                          -0.228666 -0.703784 -5,
+                          0.228666 -0.703784 -2.8,
+                          -0.228666 -0.703784 -5,
+                          -0.228666 -0.703784 -2.8,
+                          -37.25 -2.25 -5,
+                          -0.74 -2.13163e-14 -5,
+                          -0.598674 -0.434958 -5,
+                          -0.598674 -0.434958 -2.8,
+                          -0.598674 -0.434958 -5,
+                          -0.74 -2.13163e-14 -5,
+                          -0.228666 -0.703784 -2.8,
+                          -0.598674 -0.434958 -5,
+                          -0.598674 -0.434958 -2.8,
+                          -37.25 -2.25 -5,
+                          -0.598674 0.434958 -5,
+                          -0.74 -2.13163e-14 -5,
+                          -0.74 -2.13163e-14 -2.8,
+                          -0.74 -2.13163e-14 -5,
+                          -0.598674 0.434958 -5,
+                          -0.598674 -0.434958 -2.8,
+                          -0.74 -2.13163e-14 -5,
+                          -0.74 -2.13163e-14 -2.8,
+                          -37.25 -2.25 -5,
+                          -0.228666 0.703784 -5,
+                          -0.598674 0.434958 -5,
+                          -0.598674 0.434958 -2.8,
+                          -0.598674 0.434958 -5,
+                          -0.228666 0.703784 -5,
+                          -0.74 -2.13163e-14 -2.8,
+                          -0.598674 0.434958 -5,
+                          -0.598674 0.434958 -2.8,
+                          2.4 2.25 -5,
+                          0.228666 0.703784 -5,
+                          -0.228666 0.703784 -5,
+                          -0.228666 0.703784 -2.8,
+                          -0.228666 0.703784 -5,
+                          0.228666 0.703784 -5,
+                          2.4 2.25 -5,
+                          -0.228666 0.703784 -5,
+                          -37.25 -2.25 -5,
+                          -0.598674 0.434958 -2.8,
+                          -0.228666 0.703784 -5,
+                          -0.228666 0.703784 -2.8,
+                          2.4 2.25 -5,
+                          0.598674 0.434958 -5,
+                          0.228666 0.703784 -5,
+                          0.228666 0.703784 -2.8,
+                          0.228666 0.703784 -5,
+                          0.598674 0.434958 -5,
+                          -0.228666 0.703784 -2.8,
+                          0.228666 0.703784 -5,
+                          0.228666 0.703784 -2.8,
+                          0.228666 0.703784 -2.8,
+                          0.598674 0.434958 -5,
+                          0.598674 0.434958 -2.8,
+                          -37.25 -2.25 5,
+                          -37.25 -2.25 -5,
+                          -0.1 -2.25 -5,
+                          -37.25 2.25 -5,
+                          2.4 2.25 -5,
+                          -37.25 -2.25 -5,
+                          -37.25 -2.25 5,
+                          -37.25 2.25 -5,
+                          -37.25 -2.25 -5,
+                          -0.1 -2.25 -2.8,
+                          -0.1 -2.25 -5,
+                          0.856699 -2.0597 -5,
+                          -2.25 -2.25 -2.8,
+                          -37.25 -2.25 5,
+                          -0.1 -2.25 -5,
+                          -0.1 -2.25 -2.8,
+                          -2.25 -2.25 -2.8,
+                          -0.1 -2.25 -5,
+                          2.4 2.25 -5,
+                          1.66777 -1.51777 -5,
+                          0.856699 -2.0597 -5,
+                          0.856699 -2.0597 -2.8,
+                          0.856699 -2.0597 -5,
+                          1.66777 -1.51777 -5,
+                          0.856699 -2.0597 -2.8,
+                          -0.1 -2.25 -2.8,
+                          0.856699 -2.0597 -5,
+                          2.4 2.25 -5,
+                          2.2097 -0.706699 -5,
+                          1.66777 -1.51777 -5,
+                          1.66777 -1.51777 -2.8,
+                          1.66777 -1.51777 -5,
+                          2.2097 -0.706699 -5,
+                          0.856699 -2.0597 -2.8,
+                          1.66777 -1.51777 -5,
+                          1.66777 -1.51777 -2.8,
+                          2.4 2.25 -5,
+                          2.4 0.25 -5,
+                          2.2097 -0.706699 -5,
+                          2.2097 -0.706699 -2.8,
+                          2.2097 -0.706699 -5,
+                          2.4 0.25 -5,
+                          1.66777 -1.51777 -2.8,
+                          2.2097 -0.706699 -5,
+                          2.2097 -0.706699 -2.8,
+                          2.4 2.25 -2.8,
+                          2.4 0.25 -5,
+                          2.4 2.25 -5,
+                          2.4 2.25 -2.8,
+                          2.4 0.25 -2.8,
+                          2.4 0.25 -5,
+                          2.2097 -0.706699 -2.8,
+                          2.4 0.25 -5,
+                          2.4 0.25 -2.8,
+                          2.4 2.25 -2.8,
+                          2.4 2.25 -5,
+                          -37.25 2.25 -5,
+                          -37.25 2.25 5,
+                          -37.25 2.25 -5,
+                          -37.25 -2.25 5,
+                          2.4 2.25 5,
+                          -37.25 2.25 -5,
+                          -37.25 2.25 5,
+                          -2.25 2.25 2.8,
+                          -37.25 2.25 -5,
+                          2.4 2.25 5,
+                          -2.25 2.25 -2.8,
+                          2.4 2.25 -2.8,
+                          -37.25 2.25 -5,
+                          -2.25 2.25 2.8,
+                          -2.25 2.25 -2.8,
+                          -37.25 2.25 -5,
+                          -0.1 -2.25 5,
+                          -0.606764 -0.440835 5,
+                          -0.75 -2.13163e-14 5,
+                          -0.75 -2.13163e-14 2.8,
+                          -0.75 -2.13163e-14 5,
+                          -0.606764 -0.440835 5,
+                          -37.25 2.25 5,
+                          -0.75 -2.13163e-14 5,
+                          -0.606764 0.440835 5,
+                          -0.606764 0.440835 2.8,
+                          -0.606764 0.440835 5,
+                          -0.75 -2.13163e-14 5,
+                          -0.1 -2.25 5,
+                          -0.75 -2.13163e-14 5,
+                          -37.25 2.25 5,
+                          -0.606764 0.440835 2.8,
+                          -0.75 -2.13163e-14 5,
+                          -0.75 -2.13163e-14 2.8,
+                          -0.1 -2.25 5,
+                          -0.231756 -0.713294 5,
+                          -0.606764 -0.440835 5,
+                          -0.606764 -0.440835 2.8,
+                          -0.606764 -0.440835 5,
+                          -0.231756 -0.713294 5,
+                          -0.606764 -0.440835 2.8,
+                          -0.75 -2.13163e-14 2.8,
+                          -0.606764 -0.440835 5,
+                          -0.1 -2.25 5,
+                          0.231756 -0.713294 5,
+                          -0.231756 -0.713294 5,
+                          -0.231756 -0.713294 2.8,
+                          -0.231756 -0.713294 5,
+                          0.231756 -0.713294 5,
+                          -0.606764 -0.440835 2.8,
+                          -0.231756 -0.713294 5,
+                          -0.231756 -0.713294 2.8,
+                          0.856699 -2.0597 5,
+                          0.606764 -0.440835 5,
+                          0.231756 -0.713294 5,
+                          0.231756 -0.713294 2.8,
+                          0.231756 -0.713294 5,
+                          0.606764 -0.440835 5,
+                          -0.1 -2.25 5,
+                          0.856699 -2.0597 5,
+                          0.231756 -0.713294 5,
+                          -0.231756 -0.713294 2.8,
+                          0.231756 -0.713294 5,
+                          0.231756 -0.713294 2.8,
+                          0.856699 -2.0597 5,
+                          0.75 -2.13163e-14 5,
+                          0.606764 -0.440835 5,
+                          0.606764 -0.440835 2.8,
+                          0.606764 -0.440835 5,
+                          0.75 -2.13163e-14 5,
+                          0.231756 -0.713294 2.8,
+                          0.606764 -0.440835 5,
+                          0.606764 -0.440835 2.8,
+                          1.66777 -1.51777 5,
+                          0.606764 0.440835 5,
+                          0.75 -2.13163e-14 5,
+                          0.75 -2.13163e-14 2.8,
+                          0.75 -2.13163e-14 5,
+                          0.606764 0.440835 5,
+                          0.856699 -2.0597 5,
+                          1.66777 -1.51777 5,
+                          0.75 -2.13163e-14 5,
+                          0.606764 -0.440835 2.8,
+                          0.75 -2.13163e-14 5,
+                          0.75 -2.13163e-14 2.8,
+                          2.2097 -0.706699 5,
+                          0.231756 0.713294 5,
+                          0.606764 0.440835 5,
+                          0.606764 0.440835 2.8,
+                          0.606764 0.440835 5,
+                          0.231756 0.713294 5,
+                          1.66777 -1.51777 5,
+                          2.2097 -0.706699 5,
+                          0.606764 0.440835 5,
+                          0.75 -2.13163e-14 2.8,
+                          0.606764 0.440835 5,
+                          0.606764 0.440835 2.8,
+                          -37.25 2.25 5,
+                          -0.231756 0.713294 5,
+                          0.231756 0.713294 5,
+                          0.231756 0.713294 2.8,
+                          0.231756 0.713294 5,
+                          -0.231756 0.713294 5,
+                          2.4 2.25 5,
+                          -37.25 2.25 5,
+                          0.231756 0.713294 5,
+                          2.4 0.25 5,
+                          2.4 2.25 5,
+                          0.231756 0.713294 5,
+                          2.2097 -0.706699 5,
+                          2.4 0.25 5,
+                          0.231756 0.713294 5,
+                          0.606764 0.440835 2.8,
+                          0.231756 0.713294 5,
+                          0.231756 0.713294 2.8,
+                          -37.25 2.25 5,
+                          -0.606764 0.440835 5,
+                          -0.231756 0.713294 5,
+                          -0.231756 0.713294 2.8,
+                          -0.231756 0.713294 5,
+                          -0.606764 0.440835 5,
+                          0.231756 0.713294 2.8,
+                          -0.231756 0.713294 5,
+                          -0.231756 0.713294 2.8,
+                          -0.231756 0.713294 2.8,
+                          -0.606764 0.440835 5,
+                          -0.606764 0.440835 2.8,
+                          -0.1 -2.25 5,
+                          -37.25 2.25 5,
+                          -37.25 -2.25 5,
+                          -0.1 -2.25 2.8,
+                          -0.1 -2.25 5,
+                          -37.25 -2.25 5,
+                          -2.25 -2.25 2.8,
+                          -0.1 -2.25 2.8,
+                          -37.25 -2.25 5,
+                          -2.25 -2.25 -2.8,
+                          -2.25 -2.25 2.8,
+                          -37.25 -2.25 5,
+                          2.4 0.25 2.8,
+                          2.4 2.25 5,
+                          2.4 0.25 5,
+                          2.4 2.25 2.8,
+                          2.4 2.25 5,
+                          2.4 0.25 2.8,
+                          -2.25 2.25 2.8,
+                          2.4 2.25 5,
+                          2.4 2.25 2.8,
+                          2.4 0.25 2.8,
+                          2.4 0.25 5,
+                          2.2097 -0.706699 5,
+                          2.2097 -0.706699 2.8,
+                          2.2097 -0.706699 5,
+                          1.66777 -1.51777 5,
+                          2.2097 -0.706699 2.8,
+                          2.4 0.25 2.8,
+                          2.2097 -0.706699 5,
+                          1.66777 -1.51777 2.8,
+                          1.66777 -1.51777 5,
+                          0.856699 -2.0597 5,
+                          2.2097 -0.706699 2.8,
+                          1.66777 -1.51777 5,
+                          1.66777 -1.51777 2.8,
+                          0.856699 -2.0597 2.8,
+                          0.856699 -2.0597 5,
+                          -0.1 -2.25 5,
+                          1.66777 -1.51777 2.8,
+                          0.856699 -2.0597 5,
+                          0.856699 -2.0597 2.8,
+                          0.856699 -2.0597 2.8,
+                          -0.1 -2.25 5,
+                          -0.1 -2.25 2.8,
+                          -0.231756 -0.713294 2.8,
+                          -0.1 -2.25 2.8,
+                          -2.25 -2.25 2.8,
+                          0.231756 -0.713294 2.8,
+                          0.606764 -0.440835 2.8,
+                          -0.1 -2.25 2.8,
+                          0.856699 -2.0597 2.8,
+                          -0.1 -2.25 2.8,
+                          0.606764 -0.440835 2.8,
+                          -0.231756 -0.713294 2.8,
+                          0.231756 -0.713294 2.8,
+                          -0.1 -2.25 2.8,
+                          -2.25 2.25 2.8,
+                          -2.25 -2.25 2.8,
+                          -2.25 -2.25 -2.8,
+                          -0.606764 0.440835 2.8,
+                          -2.25 -2.25 2.8,
+                          -2.25 2.25 2.8,
+                          -0.606764 0.440835 2.8,
+                          -0.75 -2.13163e-14 2.8,
+                          -2.25 -2.25 2.8,
+                          -0.606764 -0.440835 2.8,
+                          -2.25 -2.25 2.8,
+                          -0.75 -2.13163e-14 2.8,
+                          -0.606764 -0.440835 2.8,
+                          -0.231756 -0.713294 2.8,
+                          -2.25 -2.25 2.8,
+                          -2.25 2.25 -2.8,
+                          -2.25 -2.25 -2.8,
+                          -0.1 -2.25 -2.8,
+                          -2.25 2.25 2.8,
+                          -2.25 -2.25 -2.8,
+                          -2.25 2.25 -2.8,
+                          -0.74 -2.13163e-14 -2.8,
+                          -2.25 2.25 -2.8,
+                          -0.1 -2.25 -2.8,
+                          -0.598674 -0.434958 -2.8,
+                          -0.74 -2.13163e-14 -2.8,
+                          -0.1 -2.25 -2.8,
+                          -0.228666 -0.703784 -2.8,
+                          -0.598674 -0.434958 -2.8,
+                          -0.1 -2.25 -2.8,
+                          0.228666 -0.703784 -2.8,
+                          -0.228666 -0.703784 -2.8,
+                          -0.1 -2.25 -2.8,
+                          0.856699 -2.0597 -2.8,
+                          0.228666 -0.703784 -2.8,
+                          -0.1 -2.25 -2.8,
+                          -2.25 2.25 -2.8,
+                          2.4 0.25 -2.8,
+                          2.4 2.25 -2.8,
+                          0.228666 0.703784 -2.8,
+                          2.4 0.25 -2.8,
+                          -2.25 2.25 -2.8,
+                          2.2097 -0.706699 -2.8,
+                          2.4 0.25 -2.8,
+                          0.228666 0.703784 -2.8,
+                          2.2097 -0.706699 2.8,
+                          2.4 2.25 2.8,
+                          2.4 0.25 2.8,
+                          -0.231756 0.713294 2.8,
+                          -2.25 2.25 2.8,
+                          2.4 2.25 2.8,
+                          0.231756 0.713294 2.8,
+                          -0.231756 0.713294 2.8,
+                          2.4 2.25 2.8,
+                          0.606764 0.440835 2.8,
+                          0.231756 0.713294 2.8,
+                          2.4 2.25 2.8,
+                          0.75 -2.13163e-14 2.8,
+                          0.606764 0.440835 2.8,
+                          2.4 2.25 2.8,
+                          0.856699 -2.0597 2.8,
+                          0.75 -2.13163e-14 2.8,
+                          2.4 2.25 2.8,
+                          1.66777 -1.51777 2.8,
+                          0.856699 -2.0597 2.8,
+                          2.4 2.25 2.8,
+                          2.2097 -0.706699 2.8,
+                          1.66777 -1.51777 2.8,
+                          2.4 2.25 2.8,
+                          -0.228666 0.703784 -2.8,
+                          0.228666 0.703784 -2.8,
+                          -2.25 2.25 -2.8,
+                          -0.598674 0.434958 -2.8,
+                          -0.228666 0.703784 -2.8,
+                          -2.25 2.25 -2.8,
+                          -0.74 -2.13163e-14 -2.8,
+                          -0.598674 0.434958 -2.8,
+                          -2.25 2.25 -2.8,
+                          -0.231756 0.713294 2.8,
+                          -0.606764 0.440835 2.8,
+                          -2.25 2.25 2.8,
+                          1.66777 -1.51777 -2.8,
+                          0.598674 0.434958 -2.8,
+                          0.74 -2.13163e-14 -2.8,
+                          0.856699 -2.0597 -2.8,
+                          0.74 -2.13163e-14 -2.8,
+                          0.598674 -0.434958 -2.8,
+                          0.856699 -2.0597 -2.8,
+                          1.66777 -1.51777 -2.8,
+                          0.74 -2.13163e-14 -2.8,
+                          2.2097 -0.706699 -2.8,
+                          0.228666 0.703784 -2.8,
+                          0.598674 0.434958 -2.8,
+                          1.66777 -1.51777 -2.8,
+                          2.2097 -0.706699 -2.8,
+                          0.598674 0.434958 -2.8,
+                          0.856699 -2.0597 -2.8,
+                          0.598674 -0.434958 -2.8,
+                          0.228666 -0.703784 -2.8,
+                          0.856699 -2.0597 2.8,
+                          0.606764 -0.440835 2.8,
+                          0.75 -2.13163e-14 2.8 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/head/head.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/head/head.iv
new file mode 100644
index 0000000000000000000000000000000000000000..945602a08bb91715820adedb57d984e5fd624659
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/head/head.iv
@@ -0,0 +1,11164 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+
+    Material {
+        diffuseColor    1 1 1
+    }
+    Separator {
+        Normal {
+            vector      [ -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          5.59019e-17 2.44921e-16 1,
+                          5.59019e-17 2.44921e-16 1,
+                          3.95286e-17 0.707107 0.707107,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          3.95286e-17 -0.707107 0.707107,
+                          3.95286e-17 -0.707107 0.707107,
+                          5.59019e-17 1.1221e-30 1,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          3.95286e-17 -0.707107 0.707107,
+                          5.59019e-17 1.1221e-30 1,
+                          5.59019e-17 1.1221e-30 1,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          3.95286e-17 0.707107 0.707107,
+                          3.95286e-17 0.707107 0.707107,
+                          0 1 -1.83691e-16,
+                          3.95286e-17 0.707107 0.707107,
+                          5.59019e-17 2.44921e-16 1,
+                          3.95286e-17 0.707107 0.707107,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          0 1 -1.83691e-16,
+                          0 1 -1.83691e-16,
+                          -3.95286e-17 0.707107 -0.707107,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          3.95286e-17 0.707107 0.707107,
+                          0 1 -1.83691e-16,
+                          0 1 -1.83691e-16,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -3.95286e-17 0.707107 -0.707107,
+                          -3.95286e-17 0.707107 -0.707107,
+                          -5.59019e-17 -1.22461e-16 -1,
+                          0 1 -1.83691e-16,
+                          -3.95286e-17 0.707107 -0.707107,
+                          -3.95286e-17 0.707107 -0.707107,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -5.59019e-17 -1.22461e-16 -1,
+                          -5.59019e-17 -1.22461e-16 -1,
+                          -3.95286e-17 -0.707107 -0.707107,
+                          -3.95286e-17 0.707107 -0.707107,
+                          -5.59019e-17 -1.22461e-16 -1,
+                          -5.59019e-17 -1.22461e-16 -1,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -3.95286e-17 -0.707107 -0.707107,
+                          -3.95286e-17 -0.707107 -0.707107,
+                          0 -1 6.12303e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -5.59019e-17 -1.22461e-16 -1,
+                          -3.95286e-17 -0.707107 -0.707107,
+                          -3.95286e-17 -0.707107 -0.707107,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          3.95286e-17 -0.707107 0.707107,
+                          -3.95286e-17 -0.707107 -0.707107,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          3.95286e-17 -0.707107 0.707107,
+                          3.95286e-17 -0.707107 0.707107,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          5.59019e-17 2.44921e-16 1,
+                          5.59019e-17 2.44921e-16 1,
+                          0 1 -1.83691e-16,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          5.59019e-17 1.1221e-30 1,
+                          0 -1 6.12303e-17,
+                          5.59019e-17 1.1221e-30 1,
+                          5.59019e-17 1.1221e-30 1,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          0 1 -1.83691e-16,
+                          0 1 -1.83691e-16,
+                          -5.59019e-17 -1.22461e-16 -1,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          0 1 -1.83691e-16,
+                          5.59019e-17 2.44921e-16 1,
+                          0 1 -1.83691e-16,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -5.59019e-17 -1.22461e-16 -1,
+                          -5.59019e-17 -1.22461e-16 -1,
+                          0 -1 6.12303e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          0 1 -1.83691e-16,
+                          -5.59019e-17 -1.22461e-16 -1,
+                          -5.59019e-17 -1.22461e-16 -1,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -5.59019e-17 -1.22461e-16 -1,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          -5.59019e-17 -1.1221e-30 -1,
+                          -5.59019e-17 -1.1221e-30 -1,
+                          -5.59019e-17 -1.1221e-30 -1,
+                          0 -1 1.08468e-30,
+                          0 -1 1.08468e-30,
+                          0 -1 1.08468e-30,
+                          0 -1 1.08468e-30,
+                          0 -1 1.08468e-30,
+                          0 -1 1.08468e-30,
+                          0 1 -1.08468e-30,
+                          0 1 -1.08468e-30,
+                          0 1 -1.08468e-30,
+                          -5.59019e-17 -1.1221e-30 -1,
+                          -5.59019e-17 -1.1221e-30 -1,
+                          -5.59019e-17 -1.1221e-30 -1,
+                          -1.91196e-17 0.939693 -0.34202,
+                          -1.91196e-17 0.939693 -0.34202,
+                          -1.91196e-17 0.939693 -0.34202,
+                          0 1 -1.08468e-30,
+                          0 1 -1.08468e-30,
+                          0 1 -1.08468e-30,
+                          0 1 -1.08468e-30,
+                          0 1 -1.08468e-30,
+                          0 1 -1.08468e-30,
+                          -1.91196e-17 0.939693 -0.34202,
+                          -1.91196e-17 0.939693 -0.34202,
+                          -1.91196e-17 0.939693 -0.34202,
+                          5.59019e-17 1.1221e-30 1,
+                          5.59019e-17 1.1221e-30 1,
+                          5.59019e-17 1.1221e-30 1,
+                          0 1 -1.08468e-30,
+                          0 1 -1.08468e-30,
+                          0 1 -1.08468e-30,
+                          1.91196e-17 -0.939693 0.34202,
+                          1.91196e-17 -0.939693 0.34202,
+                          1.91196e-17 -0.939693 0.34202,
+                          5.59019e-17 1.1221e-30 1,
+                          5.59019e-17 1.1221e-30 1,
+                          5.59019e-17 1.1221e-30 1,
+                          1.91196e-17 -0.939693 0.34202,
+                          1.91196e-17 -0.939693 0.34202,
+                          1.91196e-17 -0.939693 0.34202,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 6 58.5 49,
+                          6 48.4899 93.9899,
+                          6 54.5 91.5,
+                          9 54.5 91.5,
+                          6 54.5 91.5,
+                          6 48.4899 93.9899,
+                          6 73.5 90.2122,
+                          6 54.5 91.5,
+                          6 60.5101 93.9899,
+                          9 60.5101 93.9899,
+                          6 60.5101 93.9899,
+                          6 54.5 91.5,
+                          6 73.5 90.2122,
+                          6 58.5 49,
+                          6 54.5 91.5,
+                          9 60.5101 93.9899,
+                          6 54.5 91.5,
+                          9 54.5 91.5,
+                          6 58.5 49,
+                          6 46 100,
+                          6 48.4899 93.9899,
+                          9 48.4899 93.9899,
+                          6 48.4899 93.9899,
+                          6 46 100,
+                          9 48.4899 93.9899,
+                          9 54.5 91.5,
+                          6 48.4899 93.9899,
+                          6 47.4301 112,
+                          6 48.4899 106.01,
+                          6 46 100,
+                          9 46 100,
+                          6 46 100,
+                          6 48.4899 106.01,
+                          6 24.5 49,
+                          6 46 100,
+                          6 58.5 49,
+                          6 24.5 49,
+                          6 47.4301 112,
+                          6 46 100,
+                          9 48.4899 93.9899,
+                          6 46 100,
+                          9 46 100,
+                          6 47.4301 112,
+                          6 54.5 108.5,
+                          6 48.4899 106.01,
+                          9 48.4899 106.01,
+                          6 48.4899 106.01,
+                          6 54.5 108.5,
+                          9 46 100,
+                          6 48.4899 106.01,
+                          9 48.4899 106.01,
+                          6 47.4301 112,
+                          6 60.5101 106.01,
+                          6 54.5 108.5,
+                          9 54.5 108.5,
+                          6 54.5 108.5,
+                          6 60.5101 106.01,
+                          9 48.4899 106.01,
+                          6 54.5 108.5,
+                          9 54.5 108.5,
+                          6 73.5 90.2122,
+                          6 63 100,
+                          6 60.5101 106.01,
+                          9 60.5101 106.01,
+                          6 60.5101 106.01,
+                          6 63 100,
+                          6 73.5 112,
+                          6 73.5 90.2122,
+                          6 60.5101 106.01,
+                          6 47.4301 112,
+                          6 73.5 112,
+                          6 60.5101 106.01,
+                          9 54.5 108.5,
+                          6 60.5101 106.01,
+                          9 60.5101 106.01,
+                          6 73.5 90.2122,
+                          6 60.5101 93.9899,
+                          6 63 100,
+                          9 63 100,
+                          6 63 100,
+                          6 60.5101 93.9899,
+                          9 60.5101 106.01,
+                          6 63 100,
+                          9 63 100,
+                          9 63 100,
+                          6 60.5101 93.9899,
+                          9 60.5101 93.9899,
+                          6 58.5 -16,
+                          6 34.7505 28.5,
+                          6 41.5 21.75,
+                          9 41.5 21.75,
+                          6 41.5 21.75,
+                          6 34.7505 28.5,
+                          6 58.5 -16,
+                          6 41.5 21.75,
+                          6 48.2495 28.5,
+                          9 48.2495 28.5,
+                          6 48.2495 28.5,
+                          6 41.5 21.75,
+                          9 48.2495 28.5,
+                          6 41.5 21.75,
+                          9 41.5 21.75,
+                          6 24.5 49,
+                          6 41.5 35.25,
+                          6 34.7505 28.5,
+                          9 34.7505 28.5,
+                          6 34.7505 28.5,
+                          6 41.5 35.25,
+                          6 58.5 -16,
+                          6 24.5 -16,
+                          6 34.7505 28.5,
+                          6 24.5 49,
+                          6 34.7505 28.5,
+                          6 24.5 -16,
+                          9 34.7505 28.5,
+                          9 41.5 21.75,
+                          6 34.7505 28.5,
+                          6 58.5 49,
+                          6 48.2495 28.5,
+                          6 41.5 35.25,
+                          9 41.5 35.25,
+                          6 41.5 35.25,
+                          6 48.2495 28.5,
+                          6 24.5 49,
+                          6 58.5 49,
+                          6 41.5 35.25,
+                          9 34.7505 28.5,
+                          6 41.5 35.25,
+                          9 41.5 35.25,
+                          6 58.5 49,
+                          6 58.5 -16,
+                          6 48.2495 28.5,
+                          9 41.5 35.25,
+                          6 48.2495 28.5,
+                          9 48.2495 28.5,
+                          9 24.5 -16,
+                          6 24.5 -16,
+                          6 58.5 -16,
+                          9 24.5 49,
+                          6 24.5 49,
+                          6 24.5 -16,
+                          9 24.5 49,
+                          6 24.5 -16,
+                          9 24.5 -16,
+                          9 58.5 -16,
+                          6 58.5 -16,
+                          6 58.5 49,
+                          9 58.5 -16,
+                          9 24.5 -16,
+                          6 58.5 -16,
+                          9 58.5 49,
+                          6 58.5 49,
+                          6 73.5 90.2122,
+                          9 58.5 -16,
+                          6 58.5 49,
+                          9 58.5 49,
+                          9 73.5 90.2122,
+                          6 73.5 90.2122,
+                          6 73.5 112,
+                          9 58.5 49,
+                          6 73.5 90.2122,
+                          9 73.5 90.2122,
+                          9 73.5 112,
+                          6 73.5 112,
+                          6 47.4301 112,
+                          9 73.5 90.2122,
+                          6 73.5 112,
+                          9 73.5 112,
+                          9 47.4301 112,
+                          6 47.4301 112,
+                          6 24.5 49,
+                          9 73.5 112,
+                          6 47.4301 112,
+                          9 47.4301 112,
+                          9 47.4301 112,
+                          6 24.5 49,
+                          9 24.5 49,
+                          9 73.5 90.2122,
+                          9 60.5101 93.9899,
+                          9 54.5 91.5,
+                          9 24.5 49,
+                          9 54.5 91.5,
+                          9 48.4899 93.9899,
+                          9 73.5 90.2122,
+                          9 54.5 91.5,
+                          9 24.5 49,
+                          9 73.5 112,
+                          9 63 100,
+                          9 60.5101 93.9899,
+                          9 73.5 90.2122,
+                          9 73.5 112,
+                          9 60.5101 93.9899,
+                          9 73.5 112,
+                          9 60.5101 106.01,
+                          9 63 100,
+                          9 73.5 112,
+                          9 54.5 108.5,
+                          9 60.5101 106.01,
+                          9 47.4301 112,
+                          9 48.4899 106.01,
+                          9 54.5 108.5,
+                          9 73.5 112,
+                          9 47.4301 112,
+                          9 54.5 108.5,
+                          9 24.5 49,
+                          9 46 100,
+                          9 48.4899 106.01,
+                          9 47.4301 112,
+                          9 24.5 49,
+                          9 48.4899 106.01,
+                          9 24.5 49,
+                          9 48.4899 93.9899,
+                          9 46 100,
+                          9 24.5 -16,
+                          9 48.2495 28.5,
+                          9 41.5 21.75,
+                          9 24.5 -16,
+                          9 41.5 21.75,
+                          9 34.7505 28.5,
+                          9 58.5 49,
+                          9 41.5 35.25,
+                          9 48.2495 28.5,
+                          9 58.5 -16,
+                          9 48.2495 28.5,
+                          9 24.5 -16,
+                          9 58.5 -16,
+                          9 58.5 49,
+                          9 48.2495 28.5,
+                          9 24.5 49,
+                          9 34.7505 28.5,
+                          9 41.5 35.25,
+                          9 58.5 49,
+                          9 24.5 49,
+                          9 41.5 35.25,
+                          9 24.5 49,
+                          9 24.5 -16,
+                          9 34.7505 28.5,
+                          9 58.5 49,
+                          9 73.5 90.2122,
+                          9 24.5 49 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          5.59019e-17 2.44921e-16 1,
+                          5.59019e-17 2.44921e-16 1,
+                          3.95286e-17 0.707107 0.707107,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          3.95286e-17 -0.707107 0.707107,
+                          3.95286e-17 -0.707107 0.707107,
+                          5.59019e-17 1.1221e-30 1,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          3.95286e-17 -0.707107 0.707107,
+                          5.59019e-17 1.1221e-30 1,
+                          5.59019e-17 1.1221e-30 1,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          3.95286e-17 0.707107 0.707107,
+                          3.95286e-17 0.707107 0.707107,
+                          0 1 -1.83691e-16,
+                          3.95286e-17 0.707107 0.707107,
+                          5.59019e-17 2.44921e-16 1,
+                          3.95286e-17 0.707107 0.707107,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          0 1 -1.83691e-16,
+                          0 1 -1.83691e-16,
+                          -3.95286e-17 0.707107 -0.707107,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          3.95286e-17 0.707107 0.707107,
+                          0 1 -1.83691e-16,
+                          0 1 -1.83691e-16,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -3.95286e-17 0.707107 -0.707107,
+                          -3.95286e-17 0.707107 -0.707107,
+                          -5.59019e-17 -1.22461e-16 -1,
+                          0 1 -1.83691e-16,
+                          -3.95286e-17 0.707107 -0.707107,
+                          -3.95286e-17 0.707107 -0.707107,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -5.59019e-17 -1.22461e-16 -1,
+                          -5.59019e-17 -1.22461e-16 -1,
+                          -3.95286e-17 -0.707107 -0.707107,
+                          -3.95286e-17 0.707107 -0.707107,
+                          -5.59019e-17 -1.22461e-16 -1,
+                          -5.59019e-17 -1.22461e-16 -1,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -3.95286e-17 -0.707107 -0.707107,
+                          -3.95286e-17 -0.707107 -0.707107,
+                          0 -1 6.12303e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -5.59019e-17 -1.22461e-16 -1,
+                          -3.95286e-17 -0.707107 -0.707107,
+                          -3.95286e-17 -0.707107 -0.707107,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          3.95286e-17 -0.707107 0.707107,
+                          -3.95286e-17 -0.707107 -0.707107,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          3.95286e-17 -0.707107 0.707107,
+                          3.95286e-17 -0.707107 0.707107,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          5.59019e-17 2.44921e-16 1,
+                          5.59019e-17 2.44921e-16 1,
+                          3.95286e-17 0.707107 0.707107,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          3.95286e-17 -0.707107 0.707107,
+                          3.95286e-17 -0.707107 0.707107,
+                          5.59019e-17 1.1221e-30 1,
+                          3.95286e-17 -0.707107 0.707107,
+                          5.59019e-17 1.1221e-30 1,
+                          5.59019e-17 1.1221e-30 1,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          3.95286e-17 0.707107 0.707107,
+                          3.95286e-17 0.707107 0.707107,
+                          0 1 -1.83691e-16,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          3.95286e-17 0.707107 0.707107,
+                          5.59019e-17 2.44921e-16 1,
+                          3.95286e-17 0.707107 0.707107,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          0 1 -1.83691e-16,
+                          0 1 -1.83691e-16,
+                          -3.95286e-17 0.707107 -0.707107,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          3.95286e-17 0.707107 0.707107,
+                          0 1 -1.83691e-16,
+                          0 1 -1.83691e-16,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -3.95286e-17 0.707107 -0.707107,
+                          -3.95286e-17 0.707107 -0.707107,
+                          -5.59019e-17 -1.22461e-16 -1,
+                          0 1 -1.83691e-16,
+                          -3.95286e-17 0.707107 -0.707107,
+                          -3.95286e-17 0.707107 -0.707107,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -5.59019e-17 -1.22461e-16 -1,
+                          -5.59019e-17 -1.22461e-16 -1,
+                          -3.95286e-17 -0.707107 -0.707107,
+                          -3.95286e-17 0.707107 -0.707107,
+                          -5.59019e-17 -1.22461e-16 -1,
+                          -5.59019e-17 -1.22461e-16 -1,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -3.95286e-17 -0.707107 -0.707107,
+                          -3.95286e-17 -0.707107 -0.707107,
+                          0 -1 6.12303e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -5.59019e-17 -1.22461e-16 -1,
+                          -3.95286e-17 -0.707107 -0.707107,
+                          -3.95286e-17 -0.707107 -0.707107,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          3.95286e-17 -0.707107 0.707107,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -3.95286e-17 -0.707107 -0.707107,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          3.95286e-17 -0.707107 0.707107,
+                          3.95286e-17 -0.707107 0.707107,
+                          -5.59019e-17 -1.1221e-30 -1,
+                          -5.59019e-17 -1.1221e-30 -1,
+                          -5.59019e-17 -1.1221e-30 -1,
+                          0 -1 1.08468e-30,
+                          0 -1 1.08468e-30,
+                          0 -1 1.08468e-30,
+                          0 -1 1.08468e-30,
+                          0 -1 1.08468e-30,
+                          0 -1 1.08468e-30,
+                          0 1 -1.08468e-30,
+                          0 1 -1.08468e-30,
+                          0 1 -1.08468e-30,
+                          -5.59019e-17 -1.1221e-30 -1,
+                          -5.59019e-17 -1.1221e-30 -1,
+                          -5.59019e-17 -1.1221e-30 -1,
+                          -1.91196e-17 0.939693 -0.34202,
+                          -1.91196e-17 0.939693 -0.34202,
+                          -1.91196e-17 0.939693 -0.34202,
+                          0 1 -1.08468e-30,
+                          0 1 -1.08468e-30,
+                          0 1 -1.08468e-30,
+                          0 1 -1.08468e-30,
+                          0 1 -1.08468e-30,
+                          0 1 -1.08468e-30,
+                          -1.91196e-17 0.939693 -0.34202,
+                          -1.91196e-17 0.939693 -0.34202,
+                          -1.91196e-17 0.939693 -0.34202,
+                          5.59019e-17 1.1221e-30 1,
+                          5.59019e-17 1.1221e-30 1,
+                          5.59019e-17 1.1221e-30 1,
+                          0 1 -1.08468e-30,
+                          0 1 -1.08468e-30,
+                          0 1 -1.08468e-30,
+                          1.91196e-17 -0.939693 0.34202,
+                          1.91196e-17 -0.939693 0.34202,
+                          1.91196e-17 -0.939693 0.34202,
+                          5.59019e-17 1.1221e-30 1,
+                          5.59019e-17 1.1221e-30 1,
+                          5.59019e-17 1.1221e-30 1,
+                          1.91196e-17 -0.939693 0.34202,
+                          1.91196e-17 -0.939693 0.34202,
+                          1.91196e-17 -0.939693 0.34202,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -9 58.5 49,
+                          -9 48.4899 93.9899,
+                          -9 54.5 91.5,
+                          -6 54.5 91.5,
+                          -9 54.5 91.5,
+                          -9 48.4899 93.9899,
+                          -9 73.5 90.2122,
+                          -9 54.5 91.5,
+                          -9 60.5101 93.9899,
+                          -6 60.5101 93.9899,
+                          -9 60.5101 93.9899,
+                          -9 54.5 91.5,
+                          -9 73.5 90.2122,
+                          -9 58.5 49,
+                          -9 54.5 91.5,
+                          -6 60.5101 93.9899,
+                          -9 54.5 91.5,
+                          -6 54.5 91.5,
+                          -9 58.5 49,
+                          -9 46 100,
+                          -9 48.4899 93.9899,
+                          -6 48.4899 93.9899,
+                          -9 48.4899 93.9899,
+                          -9 46 100,
+                          -6 48.4899 93.9899,
+                          -6 54.5 91.5,
+                          -9 48.4899 93.9899,
+                          -9 47.4301 112,
+                          -9 48.4899 106.01,
+                          -9 46 100,
+                          -6 46 100,
+                          -9 46 100,
+                          -9 48.4899 106.01,
+                          -9 24.5 49,
+                          -9 46 100,
+                          -9 58.5 49,
+                          -9 24.5 49,
+                          -9 47.4301 112,
+                          -9 46 100,
+                          -6 48.4899 93.9899,
+                          -9 46 100,
+                          -6 46 100,
+                          -9 47.4301 112,
+                          -9 54.5 108.5,
+                          -9 48.4899 106.01,
+                          -6 48.4899 106.01,
+                          -9 48.4899 106.01,
+                          -9 54.5 108.5,
+                          -6 46 100,
+                          -9 48.4899 106.01,
+                          -6 48.4899 106.01,
+                          -9 47.4301 112,
+                          -9 60.5101 106.01,
+                          -9 54.5 108.5,
+                          -6 54.5 108.5,
+                          -9 54.5 108.5,
+                          -9 60.5101 106.01,
+                          -6 48.4899 106.01,
+                          -9 54.5 108.5,
+                          -6 54.5 108.5,
+                          -9 73.5 90.2122,
+                          -9 63 100,
+                          -9 60.5101 106.01,
+                          -6 60.5101 106.01,
+                          -9 60.5101 106.01,
+                          -9 63 100,
+                          -9 73.5 112,
+                          -9 73.5 90.2122,
+                          -9 60.5101 106.01,
+                          -9 47.4301 112,
+                          -9 73.5 112,
+                          -9 60.5101 106.01,
+                          -6 54.5 108.5,
+                          -9 60.5101 106.01,
+                          -6 60.5101 106.01,
+                          -9 73.5 90.2122,
+                          -9 60.5101 93.9899,
+                          -9 63 100,
+                          -6 63 100,
+                          -9 63 100,
+                          -9 60.5101 93.9899,
+                          -6 60.5101 106.01,
+                          -9 63 100,
+                          -6 63 100,
+                          -6 63 100,
+                          -9 60.5101 93.9899,
+                          -6 60.5101 93.9899,
+                          -9 58.5 -16,
+                          -9 34.4294 21.4293,
+                          -9 41.5 18.5,
+                          -6 41.5 18.5,
+                          -9 41.5 18.5,
+                          -9 34.4294 21.4293,
+                          -9 58.5 -16,
+                          -9 41.5 18.5,
+                          -9 48.5706 21.4293,
+                          -6 48.5706 21.4293,
+                          -9 48.5706 21.4293,
+                          -9 41.5 18.5,
+                          -6 48.5706 21.4293,
+                          -9 41.5 18.5,
+                          -6 41.5 18.5,
+                          -9 24.5 -16,
+                          -9 31.5 28.5,
+                          -9 34.4294 21.4293,
+                          -6 34.4294 21.4293,
+                          -9 34.4294 21.4293,
+                          -9 31.5 28.5,
+                          -9 58.5 -16,
+                          -9 24.5 -16,
+                          -9 34.4294 21.4293,
+                          -6 34.4294 21.4293,
+                          -6 41.5 18.5,
+                          -9 34.4294 21.4293,
+                          -9 24.5 49,
+                          -9 34.4294 35.5706,
+                          -9 31.5 28.5,
+                          -6 31.5 28.5,
+                          -9 31.5 28.5,
+                          -9 34.4294 35.5706,
+                          -9 24.5 49,
+                          -9 31.5 28.5,
+                          -9 24.5 -16,
+                          -6 34.4294 21.4293,
+                          -9 31.5 28.5,
+                          -6 31.5 28.5,
+                          -9 24.5 49,
+                          -9 41.5 38.5,
+                          -9 34.4294 35.5706,
+                          -6 34.4294 35.5706,
+                          -9 34.4294 35.5706,
+                          -9 41.5 38.5,
+                          -6 31.5 28.5,
+                          -9 34.4294 35.5706,
+                          -6 34.4294 35.5706,
+                          -9 24.5 49,
+                          -9 48.5706 35.5706,
+                          -9 41.5 38.5,
+                          -6 41.5 38.5,
+                          -9 41.5 38.5,
+                          -9 48.5706 35.5706,
+                          -6 34.4294 35.5706,
+                          -9 41.5 38.5,
+                          -6 41.5 38.5,
+                          -9 58.5 49,
+                          -9 51.5 28.5,
+                          -9 48.5706 35.5706,
+                          -6 48.5706 35.5706,
+                          -9 48.5706 35.5706,
+                          -9 51.5 28.5,
+                          -9 24.5 49,
+                          -9 58.5 49,
+                          -9 48.5706 35.5706,
+                          -6 41.5 38.5,
+                          -9 48.5706 35.5706,
+                          -6 48.5706 35.5706,
+                          -9 58.5 -16,
+                          -9 48.5706 21.4293,
+                          -9 51.5 28.5,
+                          -6 51.5 28.5,
+                          -9 51.5 28.5,
+                          -9 48.5706 21.4293,
+                          -9 58.5 49,
+                          -9 58.5 -16,
+                          -9 51.5 28.5,
+                          -6 48.5706 35.5706,
+                          -9 51.5 28.5,
+                          -6 51.5 28.5,
+                          -6 51.5 28.5,
+                          -9 48.5706 21.4293,
+                          -6 48.5706 21.4293,
+                          -6 24.5 -16,
+                          -9 24.5 -16,
+                          -9 58.5 -16,
+                          -6 24.5 49,
+                          -9 24.5 49,
+                          -9 24.5 -16,
+                          -6 24.5 49,
+                          -9 24.5 -16,
+                          -6 24.5 -16,
+                          -6 58.5 -16,
+                          -9 58.5 -16,
+                          -9 58.5 49,
+                          -6 58.5 -16,
+                          -6 24.5 -16,
+                          -9 58.5 -16,
+                          -6 58.5 49,
+                          -9 58.5 49,
+                          -9 73.5 90.2122,
+                          -6 58.5 -16,
+                          -9 58.5 49,
+                          -6 58.5 49,
+                          -6 73.5 90.2122,
+                          -9 73.5 90.2122,
+                          -9 73.5 112,
+                          -6 58.5 49,
+                          -9 73.5 90.2122,
+                          -6 73.5 90.2122,
+                          -6 73.5 112,
+                          -9 73.5 112,
+                          -9 47.4301 112,
+                          -6 73.5 90.2122,
+                          -9 73.5 112,
+                          -6 73.5 112,
+                          -6 47.4301 112,
+                          -9 47.4301 112,
+                          -9 24.5 49,
+                          -6 73.5 112,
+                          -9 47.4301 112,
+                          -6 47.4301 112,
+                          -6 47.4301 112,
+                          -9 24.5 49,
+                          -6 24.5 49,
+                          -6 73.5 90.2122,
+                          -6 60.5101 93.9899,
+                          -6 54.5 91.5,
+                          -6 24.5 49,
+                          -6 54.5 91.5,
+                          -6 48.4899 93.9899,
+                          -6 73.5 90.2122,
+                          -6 54.5 91.5,
+                          -6 24.5 49,
+                          -6 73.5 112,
+                          -6 63 100,
+                          -6 60.5101 93.9899,
+                          -6 73.5 90.2122,
+                          -6 73.5 112,
+                          -6 60.5101 93.9899,
+                          -6 73.5 112,
+                          -6 60.5101 106.01,
+                          -6 63 100,
+                          -6 73.5 112,
+                          -6 54.5 108.5,
+                          -6 60.5101 106.01,
+                          -6 47.4301 112,
+                          -6 48.4899 106.01,
+                          -6 54.5 108.5,
+                          -6 73.5 112,
+                          -6 47.4301 112,
+                          -6 54.5 108.5,
+                          -6 24.5 49,
+                          -6 46 100,
+                          -6 48.4899 106.01,
+                          -6 47.4301 112,
+                          -6 24.5 49,
+                          -6 48.4899 106.01,
+                          -6 24.5 49,
+                          -6 48.4899 93.9899,
+                          -6 46 100,
+                          -6 24.5 -16,
+                          -6 48.5706 21.4293,
+                          -6 41.5 18.5,
+                          -6 24.5 -16,
+                          -6 41.5 18.5,
+                          -6 34.4294 21.4293,
+                          -6 58.5 -16,
+                          -6 51.5 28.5,
+                          -6 48.5706 21.4293,
+                          -6 58.5 -16,
+                          -6 48.5706 21.4293,
+                          -6 24.5 -16,
+                          -6 58.5 49,
+                          -6 48.5706 35.5706,
+                          -6 51.5 28.5,
+                          -6 58.5 -16,
+                          -6 58.5 49,
+                          -6 51.5 28.5,
+                          -6 58.5 49,
+                          -6 41.5 38.5,
+                          -6 48.5706 35.5706,
+                          -6 58.5 49,
+                          -6 34.4294 35.5706,
+                          -6 41.5 38.5,
+                          -6 24.5 49,
+                          -6 31.5 28.5,
+                          -6 34.4294 35.5706,
+                          -6 58.5 49,
+                          -6 24.5 49,
+                          -6 34.4294 35.5706,
+                          -6 24.5 -16,
+                          -6 34.4294 21.4293,
+                          -6 31.5 28.5,
+                          -6 24.5 49,
+                          -6 24.5 -16,
+                          -6 31.5 28.5,
+                          -6 58.5 49,
+                          -6 73.5 90.2122,
+                          -6 24.5 49 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 0 -1 1.08468e-30,
+                          0 -1 1.08468e-30,
+                          0 -1 1.08468e-30,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          0 -1 1.08468e-30,
+                          0 -1 1.08468e-30,
+                          0 -1 1.08468e-30,
+                          5.59019e-17 1.30614e-17 1,
+                          5.59019e-17 1.30614e-17 1,
+                          5.59019e-17 1.30614e-17 1,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          5.59019e-17 1.30614e-17 1,
+                          5.59019e-17 1.30614e-17 1,
+                          5.59019e-17 1.30614e-17 1,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          0 1 -1.08468e-30,
+                          0 1 -1.08468e-30,
+                          0 1 -1.08468e-30,
+                          0 1 -1.08468e-30,
+                          0 1 -1.08468e-30,
+                          0 1 -1.08468e-30 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 50 58.5 -22,
+                          -50 58.5 30,
+                          -50 58.5 -22,
+                          -50 61.5 -22,
+                          -50 58.5 -22,
+                          -50 58.5 30,
+                          50 61.5 -22,
+                          50 58.5 -22,
+                          -50 58.5 -22,
+                          50 61.5 -22,
+                          -50 58.5 -22,
+                          -50 61.5 -22,
+                          50 58.5 -22,
+                          50 58.5 30,
+                          -50 58.5 30,
+                          -50 61.5 30,
+                          -50 58.5 30,
+                          50 58.5 30,
+                          -50 61.5 30,
+                          -50 61.5 -22,
+                          -50 58.5 30,
+                          50 61.5 30,
+                          50 58.5 30,
+                          50 58.5 -22,
+                          -50 61.5 30,
+                          50 58.5 30,
+                          50 61.5 30,
+                          50 61.5 30,
+                          50 58.5 -22,
+                          50 61.5 -22,
+                          50 61.5 30,
+                          50 61.5 -22,
+                          -50 61.5 -22,
+                          -50 61.5 30,
+                          50 61.5 30,
+                          -50 61.5 -22 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.14 0.97 0.09
+    }
+    Separator {
+        Normal {
+            vector      [ 1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          5.59019e-17 1.30614e-17 1,
+                          5.59019e-17 1.30614e-17 1,
+                          5.59019e-17 1.30614e-17 1,
+                          5.59019e-17 1.30614e-17 1,
+                          5.59019e-17 1.30614e-17 1,
+                          5.59019e-17 1.30614e-17 1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          0.707107 -9.23584e-18 -0.707107,
+                          0.707107 -9.23584e-18 -0.707107,
+                          0.707107 -9.23584e-18 -0.707107,
+                          0.707107 -9.23584e-18 -0.707107,
+                          0.707107 -9.23584e-18 -0.707107,
+                          0.707107 -9.23584e-18 -0.707107,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          5.59019e-17 1.30614e-17 1,
+                          5.59019e-17 1.30614e-17 1,
+                          5.59019e-17 1.30614e-17 1,
+                          5.59019e-17 1.30614e-17 1,
+                          5.59019e-17 1.30614e-17 1,
+                          5.59019e-17 1.30614e-17 1,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -0.759352 8.49882e-18 0.65068,
+                          -0.759352 8.49882e-18 0.65068,
+                          -0.759352 8.49882e-18 0.65068,
+                          -0.759352 8.49882e-18 0.65068,
+                          -0.759352 8.49882e-18 0.65068,
+                          -0.759352 8.49882e-18 0.65068,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          -0.65068 -9.91824e-18 -0.759352,
+                          -0.65068 -9.91824e-18 -0.759352,
+                          -0.65068 -9.91824e-18 -0.759352,
+                          -0.65068 -9.91824e-18 -0.759352,
+                          -0.65068 -9.91824e-18 -0.759352,
+                          -0.65068 -9.91824e-18 -0.759352 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -22 61.5 -37,
+                          -22 130.5 -37,
+                          -22 130.5 40,
+                          -23.5 130.5 40,
+                          -22 130.5 40,
+                          -22 130.5 -37,
+                          -22 61.5 40,
+                          -22 61.5 -37,
+                          -22 130.5 40,
+                          -23.5 61.5 40,
+                          -22 61.5 40,
+                          -22 130.5 40,
+                          -23.5 61.5 40,
+                          -22 130.5 40,
+                          -23.5 130.5 40,
+                          -23.5 130.5 -37,
+                          -22 130.5 -37,
+                          -22 61.5 -37,
+                          -23.5 130.5 40,
+                          -22 130.5 -37,
+                          -23.5 130.5 30,
+                          -42.5 130.5 30,
+                          -23.5 130.5 30,
+                          -22 130.5 -37,
+                          -29 130.5 -27,
+                          -42.5 130.5 30,
+                          -22 130.5 -37,
+                          -34.8561 130.5 -33.8342,
+                          -29 130.5 -27,
+                          -22 130.5 -37,
+                          -23.5 130.5 -37,
+                          -34.8561 130.5 -33.8342,
+                          -22 130.5 -37,
+                          -23.5 61.5 -37,
+                          -22 61.5 -37,
+                          -22 61.5 40,
+                          -23.5 78.5 -37,
+                          -22 61.5 -37,
+                          -23.5 61.5 -37,
+                          -23.5 130.5 -37,
+                          -22 61.5 -37,
+                          -23.5 78.5 -37,
+                          -23.5 61.5 -37,
+                          -22 61.5 40,
+                          -23.5 61.5 -27,
+                          -23.5 61.5 30,
+                          -23.5 61.5 -27,
+                          -22 61.5 40,
+                          -23.5 61.5 30,
+                          -22 61.5 40,
+                          -23.5 61.5 40,
+                          -23.5 78.5 -37,
+                          -23.5 61.5 -27,
+                          -23.5 78.5 -27,
+                          -29 78.5 -27,
+                          -23.5 78.5 -27,
+                          -23.5 61.5 -27,
+                          -34.8561 78.5 -33.8342,
+                          -23.5 78.5 -37,
+                          -23.5 78.5 -27,
+                          -29 78.5 -27,
+                          -34.8561 78.5 -33.8342,
+                          -23.5 78.5 -27,
+                          -23.5 78.5 -37,
+                          -23.5 61.5 -37,
+                          -23.5 61.5 -27,
+                          -42.5 61.5 -27,
+                          -23.5 61.5 -27,
+                          -23.5 61.5 30,
+                          -29 78.5 -27,
+                          -23.5 61.5 -27,
+                          -42.5 61.5 -27,
+                          -23.5 130.5 -37,
+                          -23.5 78.5 -37,
+                          -27.0355 130.5 -40.5355,
+                          -27.0355 78.5 -40.5355,
+                          -27.0355 130.5 -40.5355,
+                          -23.5 78.5 -37,
+                          -34.8561 78.5 -33.8342,
+                          -27.0355 78.5 -40.5355,
+                          -23.5 78.5 -37,
+                          -23.5 61.5 40,
+                          -23.5 130.5 40,
+                          -23.5 130.5 30,
+                          -23.5 61.5 30,
+                          -23.5 61.5 40,
+                          -23.5 130.5 30,
+                          -42.5 61.5 30,
+                          -23.5 61.5 30,
+                          -23.5 130.5 30,
+                          -42.5 61.5 30,
+                          -23.5 130.5 30,
+                          -42.5 130.5 30,
+                          -42.5 61.5 30,
+                          -42.5 61.5 -27,
+                          -23.5 61.5 30,
+                          -29 130.5 -27,
+                          -42.5 130.5 -27,
+                          -42.5 130.5 30,
+                          -42.5 61.5 -27,
+                          -42.5 130.5 30,
+                          -42.5 130.5 -27,
+                          -42.5 61.5 30,
+                          -42.5 130.5 30,
+                          -42.5 61.5 -27,
+                          -29 78.5 -27,
+                          -42.5 130.5 -27,
+                          -29 130.5 -27,
+                          -29 78.5 -27,
+                          -42.5 61.5 -27,
+                          -42.5 130.5 -27,
+                          -34.8561 78.5 -33.8342,
+                          -29 130.5 -27,
+                          -34.8561 130.5 -33.8342,
+                          -29 78.5 -27,
+                          -29 130.5 -27,
+                          -34.8561 78.5 -33.8342,
+                          -23.5 130.5 -37,
+                          -27.0355 130.5 -40.5355,
+                          -34.8561 130.5 -33.8342,
+                          -27.0355 78.5 -40.5355,
+                          -34.8561 130.5 -33.8342,
+                          -27.0355 130.5 -40.5355,
+                          -34.8561 78.5 -33.8342,
+                          -34.8561 130.5 -33.8342,
+                          -27.0355 78.5 -40.5355 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          -1 0 5.59019e-17,
+                          5.59019e-17 1.30614e-17 1,
+                          5.59019e-17 1.30614e-17 1,
+                          5.59019e-17 1.30614e-17 1,
+                          5.59019e-17 1.30614e-17 1,
+                          5.59019e-17 1.30614e-17 1,
+                          5.59019e-17 1.30614e-17 1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -0.707107 -9.23584e-18 -0.707107,
+                          -0.707107 -9.23584e-18 -0.707107,
+                          -0.707107 -9.23584e-18 -0.707107,
+                          -0.707107 -9.23584e-18 -0.707107,
+                          -0.707107 -9.23584e-18 -0.707107,
+                          -0.707107 -9.23584e-18 -0.707107,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          5.59019e-17 1.30614e-17 1,
+                          5.59019e-17 1.30614e-17 1,
+                          5.59019e-17 1.30614e-17 1,
+                          5.59019e-17 1.30614e-17 1,
+                          5.59019e-17 1.30614e-17 1,
+                          5.59019e-17 1.30614e-17 1,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 1 -1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          1 0 -5.59019e-17,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          -5.59019e-17 -1.30614e-17 -1,
+                          0.759352 8.49882e-18 0.65068,
+                          0.759352 8.49882e-18 0.65068,
+                          0.759352 8.49882e-18 0.65068,
+                          0.759352 8.49882e-18 0.65068,
+                          0.759352 8.49882e-18 0.65068,
+                          0.759352 8.49882e-18 0.65068,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0 -1 1.30614e-17,
+                          0.65068 -9.91824e-18 -0.759352,
+                          0.65068 -9.91824e-18 -0.759352,
+                          0.65068 -9.91824e-18 -0.759352,
+                          0.65068 -9.91824e-18 -0.759352,
+                          0.65068 -9.91824e-18 -0.759352,
+                          0.65068 -9.91824e-18 -0.759352 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 22 130.5 -37,
+                          22 61.5 -37,
+                          22 61.5 40,
+                          23.5 61.5 40,
+                          22 61.5 40,
+                          22 61.5 -37,
+                          22 130.5 40,
+                          22 130.5 -37,
+                          22 61.5 40,
+                          23.5 130.5 40,
+                          22 130.5 40,
+                          22 61.5 40,
+                          23.5 130.5 40,
+                          22 61.5 40,
+                          23.5 61.5 40,
+                          23.5 61.5 -37,
+                          22 61.5 -37,
+                          22 130.5 -37,
+                          23.5 61.5 40,
+                          22 61.5 -37,
+                          23.5 61.5 30,
+                          42.5 61.5 30,
+                          23.5 61.5 30,
+                          22 61.5 -37,
+                          29 61.5 -27,
+                          42.5 61.5 30,
+                          22 61.5 -37,
+                          34.8561 61.5 -33.8342,
+                          29 61.5 -27,
+                          22 61.5 -37,
+                          23.5 61.5 -37,
+                          34.8561 61.5 -33.8342,
+                          22 61.5 -37,
+                          23.5 130.5 -37,
+                          22 130.5 -37,
+                          22 130.5 40,
+                          23.5 113.5 -37,
+                          22 130.5 -37,
+                          23.5 130.5 -37,
+                          23.5 61.5 -37,
+                          22 130.5 -37,
+                          23.5 113.5 -37,
+                          23.5 130.5 -37,
+                          22 130.5 40,
+                          23.5 130.5 -27,
+                          23.5 130.5 30,
+                          23.5 130.5 -27,
+                          22 130.5 40,
+                          23.5 130.5 30,
+                          22 130.5 40,
+                          23.5 130.5 40,
+                          23.5 113.5 -37,
+                          23.5 130.5 -27,
+                          23.5 113.5 -27,
+                          29 113.5 -27,
+                          23.5 113.5 -27,
+                          23.5 130.5 -27,
+                          34.8561 113.5 -33.8342,
+                          23.5 113.5 -37,
+                          23.5 113.5 -27,
+                          29 113.5 -27,
+                          34.8561 113.5 -33.8342,
+                          23.5 113.5 -27,
+                          23.5 113.5 -37,
+                          23.5 130.5 -37,
+                          23.5 130.5 -27,
+                          42.5 130.5 -27,
+                          23.5 130.5 -27,
+                          23.5 130.5 30,
+                          29 113.5 -27,
+                          23.5 130.5 -27,
+                          42.5 130.5 -27,
+                          23.5 61.5 -37,
+                          23.5 113.5 -37,
+                          27.0355 61.5 -40.5355,
+                          27.0355 113.5 -40.5355,
+                          27.0355 61.5 -40.5355,
+                          23.5 113.5 -37,
+                          34.8561 113.5 -33.8342,
+                          27.0355 113.5 -40.5355,
+                          23.5 113.5 -37,
+                          23.5 130.5 40,
+                          23.5 61.5 40,
+                          23.5 61.5 30,
+                          23.5 130.5 30,
+                          23.5 130.5 40,
+                          23.5 61.5 30,
+                          42.5 130.5 30,
+                          23.5 130.5 30,
+                          23.5 61.5 30,
+                          42.5 130.5 30,
+                          23.5 61.5 30,
+                          42.5 61.5 30,
+                          42.5 130.5 30,
+                          42.5 130.5 -27,
+                          23.5 130.5 30,
+                          29 61.5 -27,
+                          42.5 61.5 -27,
+                          42.5 61.5 30,
+                          42.5 130.5 -27,
+                          42.5 61.5 30,
+                          42.5 61.5 -27,
+                          42.5 130.5 30,
+                          42.5 61.5 30,
+                          42.5 130.5 -27,
+                          29 113.5 -27,
+                          42.5 61.5 -27,
+                          29 61.5 -27,
+                          29 113.5 -27,
+                          42.5 130.5 -27,
+                          42.5 61.5 -27,
+                          34.8561 113.5 -33.8342,
+                          29 61.5 -27,
+                          34.8561 61.5 -33.8342,
+                          29 113.5 -27,
+                          29 61.5 -27,
+                          34.8561 113.5 -33.8342,
+                          23.5 61.5 -37,
+                          27.0355 61.5 -40.5355,
+                          34.8561 61.5 -33.8342,
+                          27.0355 113.5 -40.5355,
+                          34.8561 61.5 -33.8342,
+                          27.0355 61.5 -40.5355,
+                          34.8561 113.5 -33.8342,
+                          34.8561 61.5 -33.8342,
+                          27.0355 113.5 -40.5355 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.73 0.949 1
+    }
+    Separator {
+        Normal {
+            vector      [ 1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          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 0 1,
+                          0 0 1,
+                          0 0 1,
+                          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 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,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 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 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 16 24.5 48,
+                          16 21.5 16,
+                          16 24.5 16,
+                          45 21.5 16,
+                          16 24.5 16,
+                          16 21.5 16,
+                          -45 24.5 -16,
+                          16 24.5 48,
+                          16 24.5 16,
+                          45 24.5 16,
+                          -45 24.5 -16,
+                          16 24.5 16,
+                          45 21.5 16,
+                          45 24.5 16,
+                          16 24.5 16,
+                          16 24.5 48,
+                          16 21.5 48,
+                          16 21.5 16,
+                          -16 21.5 48,
+                          16 21.5 16,
+                          16 21.5 48,
+                          45 21.5 -16,
+                          16 21.5 16,
+                          -16 21.5 48,
+                          45 21.5 16,
+                          16 21.5 16,
+                          45 21.5 -16,
+                          -16 24.5 48,
+                          16 21.5 48,
+                          16 24.5 48,
+                          -16 21.5 48,
+                          16 21.5 48,
+                          -16 24.5 48,
+                          -16 24.5 48,
+                          16 24.5 48,
+                          -16 24.5 16,
+                          -45 24.5 -16,
+                          -16 24.5 16,
+                          16 24.5 48,
+                          -16 21.5 48,
+                          -16 24.5 48,
+                          -16 24.5 16,
+                          -16 21.5 16,
+                          -16 21.5 48,
+                          -16 24.5 16,
+                          -45 24.5 16,
+                          -16 21.5 16,
+                          -16 24.5 16,
+                          -45 24.5 -16,
+                          -45 24.5 16,
+                          -16 24.5 16,
+                          45 21.5 -16,
+                          -16 21.5 48,
+                          -16 21.5 16,
+                          -45 21.5 16,
+                          -16 21.5 16,
+                          -45 24.5 16,
+                          -45 21.5 16,
+                          45 21.5 -16,
+                          -16 21.5 16,
+                          -45 21.5 16,
+                          -45 24.5 16,
+                          -45 24.5 -16,
+                          45 24.5 16,
+                          45 24.5 -16,
+                          -45 24.5 -16,
+                          -45 21.5 -16,
+                          -45 24.5 -16,
+                          45 24.5 -16,
+                          -45 21.5 16,
+                          -45 24.5 -16,
+                          -45 21.5 -16,
+                          45 21.5 -16,
+                          45 24.5 -16,
+                          45 24.5 16,
+                          45 21.5 -16,
+                          -45 21.5 -16,
+                          45 24.5 -16,
+                          45 21.5 16,
+                          45 21.5 -16,
+                          45 24.5 16,
+                          -45 21.5 16,
+                          -45 21.5 -16,
+                          45 21.5 -16 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+	#FACE COLOR!
+    Material {
+        diffuseColor    0.7450980392156863 0.7450980392156863 0.7450980392156863
+    }
+    Separator {
+        Normal {
+            vector      [ 1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          0.920358 4.44858e-05 0.391076,
+                          1 1.47115e-09 1.26441e-05,
+                          1 8.87578e-17 -3.44389e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          0.710487 -0.1001 0.696554,
+                          1 6.4881e-16 -1.63647e-16,
+                          1 -1.84543e-12 7.12089e-07,
+                          0.920363 -1.00911e-06 0.391066,
+                          0.710487 -0.1001 0.696554,
+                          1 -1.84543e-12 7.12089e-07,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          0.628317 0.262161 0.732454,
+                          1 8.87578e-17 -3.44389e-16,
+                          1 8.97641e-17 -3.45605e-16,
+                          0.649215 0.1969 0.734677,
+                          1 8.87578e-17 -3.44389e-16,
+                          0.628317 0.262161 0.732454,
+                          0.694129 8.04319e-05 0.719851,
+                          1 8.87578e-17 -3.44389e-16,
+                          0.649215 0.1969 0.734677,
+                          0.920358 4.44858e-05 0.391076,
+                          1 8.87578e-17 -3.44389e-16,
+                          0.694129 8.04319e-05 0.719851,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          0.628315 0.677926 0.381624,
+                          1 8.97641e-17 -3.45605e-16,
+                          1 9.50428e-17 -3.64448e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          0.628315 0.677926 0.381624,
+                          0.628317 0.262161 0.732454,
+                          1 8.97641e-17 -3.45605e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          0.628315 0.677926 0.381624,
+                          1 9.50428e-17 -3.64448e-16,
+                          1 6.47453e-17 -5.773e-16,
+                          0.628317 0.762212 -0.155726,
+                          1 6.47453e-17 -5.773e-16,
+                          1 4.47901e-16 2.91165e-16,
+                          0.628315 0.677926 0.381624,
+                          1 6.47453e-17 -5.773e-16,
+                          0.628317 0.762212 -0.155726,
+                          0.628316 0.490351 -0.603966,
+                          1 4.47901e-16 2.91165e-16,
+                          1 1.44534e-16 -3.03557e-16,
+                          0.628317 0.762212 -0.155726,
+                          1 4.47901e-16 2.91165e-16,
+                          0.628316 0.490351 -0.603966,
+                          0.628316 0.490351 -0.603966,
+                          1 1.44534e-16 -3.03557e-16,
+                          1 9.94565e-11 -4.11985e-06,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          0.668381 -2.53296e-06 -0.743819,
+                          1 -1.63889e-12 -4.71261e-07,
+                          1 3.24212e-16 -4.1861e-16,
+                          0.668379 1.74619e-05 -0.743821,
+                          0.628316 0.490351 -0.603966,
+                          1 9.94565e-11 -4.11985e-06,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          0.668381 -0.41874 -0.614755,
+                          1 3.24212e-16 -4.1861e-16,
+                          1 3.0758e-16 -5.68304e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          0.668381 -0.41874 -0.614755,
+                          0.668381 -2.53296e-06 -0.743819,
+                          1 3.24212e-16 -4.1861e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          0.668381 -0.695538 -0.263617,
+                          1 3.0758e-16 -5.68304e-16,
+                          1 8.79963e-17 -1.20777e-15,
+                          0.668381 -0.695538 -0.263617,
+                          0.668381 -0.41874 -0.614755,
+                          1 3.0758e-16 -5.68304e-16,
+                          0.668381 -0.722671 0.176106,
+                          1 8.79963e-17 -1.20777e-15,
+                          1 1.42817e-15 1.03868e-15,
+                          0.668381 -0.695538 -0.263617,
+                          1 8.79963e-17 -1.20777e-15,
+                          0.668381 -0.722671 0.176106,
+                          0.731002 -0.343491 0.589618,
+                          1 1.42817e-15 1.03868e-15,
+                          1 6.4881e-16 -1.63647e-16,
+                          0.726746 -0.493107 0.478212,
+                          1 1.42817e-15 1.03868e-15,
+                          0.731002 -0.343491 0.589618,
+                          0.711269 -0.600738 0.364981,
+                          1 1.42817e-15 1.03868e-15,
+                          0.726746 -0.493107 0.478212,
+                          0.67776 -0.705674 0.206554,
+                          1 1.42817e-15 1.03868e-15,
+                          0.711269 -0.600738 0.364981,
+                          0.668381 -0.722671 0.176106,
+                          1 1.42817e-15 1.03868e-15,
+                          0.67776 -0.705674 0.206554,
+                          0.723573 -0.212769 0.656637,
+                          1 6.4881e-16 -1.63647e-16,
+                          0.710487 -0.1001 0.696554,
+                          0.731002 -0.343491 0.589618,
+                          1 6.4881e-16 -1.63647e-16,
+                          0.723573 -0.212769 0.656637,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -0.977371 0.00933189 0.211327,
+                          -0.854343 0.000118538 0.51971,
+                          -0.877901 -0.194162 0.437711,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -0.993056 -0.0216827 -0.115629,
+                          -0.845445 0.215074 0.488841,
+                          -0.854346 -1.45971e-05 0.519706,
+                          -0.977372 0.00928282 0.211324,
+                          -0.993056 -0.0216827 -0.115629,
+                          -0.854346 -1.45971e-05 0.519706,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -0.989508 -0.0734211 0.124433,
+                          -0.877901 -0.194162 0.437711,
+                          -0.924799 -0.282131 0.255244,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -0.992574 0.0175279 -0.12037,
+                          -0.877901 -0.194162 0.437711,
+                          -0.992807 0.0471008 -0.110069,
+                          -0.991755 0.0834061 -0.0972947,
+                          -0.992807 0.0471008 -0.110069,
+                          -0.877901 -0.194162 0.437711,
+                          -0.977371 0.00933189 0.211327,
+                          -0.877901 -0.194162 0.437711,
+                          -0.992574 0.0175279 -0.12037,
+                          -0.991755 0.0834061 -0.0972947,
+                          -0.877901 -0.194162 0.437711,
+                          -0.987887 0.149889 -0.0401596,
+                          -0.98953 0.14055 -0.0327925,
+                          -0.987887 0.149889 -0.0401596,
+                          -0.877901 -0.194162 0.437711,
+                          -0.991036 0.131153 -0.0254228,
+                          -0.877901 -0.194162 0.437711,
+                          -0.989508 -0.0734211 0.124433,
+                          -0.98953 0.14055 -0.0327925,
+                          -0.877901 -0.194162 0.437711,
+                          -0.991036 0.131153 -0.0254228,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          0.711301 -0.600695 0.364989,
+                          0.72506 -0.510703 0.462029,
+                          0.704435 -0.629828 0.327244,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          0.725129 -0.510031 0.462663,
+                          0.72506 -0.510703 0.462029,
+                          0.711301 -0.600695 0.364989,
+                          -0.0699932 -0.705483 -0.705262,
+                          -0.0713743 -0.7085 -0.702092,
+                          -0.0687848 -0.705177 -0.705687,
+                          -0.0763981 -0.714813 -0.69513,
+                          -0.0713743 -0.7085 -0.702092,
+                          -0.0699932 -0.705483 -0.705262,
+                          -0.0763981 -0.714813 -0.69513,
+                          -0.076807 -0.715847 -0.69402,
+                          -0.0713743 -0.7085 -0.702092,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          0.677776 -0.705669 0.206521,
+                          0.704435 -0.629828 0.327244,
+                          0.667042 -0.726577 0.164744,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          0.677776 -0.705669 0.206521,
+                          0.711301 -0.600695 0.364989,
+                          0.704435 -0.629828 0.327244,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          0.61811 -0.786091 0.000872262,
+                          0.667042 -0.726577 0.164744,
+                          0.608951 -0.792769 -0.0263698,
+                          0.669909 -0.721372 0.175627,
+                          0.677776 -0.705669 0.206521,
+                          0.667042 -0.726577 0.164744,
+                          0.61811 -0.786091 0.000872262,
+                          0.669909 -0.721372 0.175627,
+                          0.667042 -0.726577 0.164744,
+                          0.52807 -0.815393 -0.237225,
+                          0.608951 -0.792769 -0.0263698,
+                          0.52567 -0.815294 -0.242831,
+                          0.52807 -0.815393 -0.237225,
+                          0.61811 -0.786091 0.000872262,
+                          0.608951 -0.792769 -0.0263698,
+                          0.52807 -0.815393 -0.237225,
+                          0.52567 -0.815294 -0.242831,
+                          0.414742 -0.777777 -0.472284,
+                          0.414287 -0.77751 -0.473122,
+                          0.414742 -0.777777 -0.472284,
+                          0.280174 -0.667451 -0.689936,
+                          0.414287 -0.77751 -0.473122,
+                          0.52807 -0.815393 -0.237225,
+                          0.414742 -0.777777 -0.472284,
+                          0.139418 -0.491531 -0.859628,
+                          0.280174 -0.667451 -0.689936,
+                          0.135591 -0.485893 -0.863437,
+                          0.295429 -0.68291 -0.668098,
+                          0.414287 -0.77751 -0.473122,
+                          0.280174 -0.667451 -0.689936,
+                          0.139418 -0.491531 -0.859628,
+                          0.295429 -0.68291 -0.668098,
+                          0.280174 -0.667451 -0.689936,
+                          0.025306 -0.301118 -0.953251,
+                          0.135591 -0.485893 -0.863437,
+                          0.000892922 -0.253502 -0.967334,
+                          0.025306 -0.301118 -0.953251,
+                          0.139418 -0.491531 -0.859628,
+                          0.135591 -0.485893 -0.863437,
+                          -0.0525547 -0.13805 -0.98903,
+                          0.000892922 -0.253502 -0.967334,
+                          -0.106533 1.79561e-15 -0.994309,
+                          -0.0525547 -0.13805 -0.98903,
+                          0.025306 -0.301118 -0.953251,
+                          0.000892922 -0.253502 -0.967334,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -0.106533 1.91737e-15 -0.994309,
+                          -0.106533 1.91737e-15 -0.994309,
+                          -0.156238 0.160954 -0.974517,
+                          -0.0525547 -0.13805 -0.98903,
+                          -0.106533 1.79561e-15 -0.994309,
+                          -0.106533 2.12577e-15 -0.994309,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -0.153063 0.149074 -0.976908,
+                          -0.156238 0.160954 -0.974517,
+                          -0.189985 0.315571 -0.929689,
+                          -0.153063 0.149074 -0.976908,
+                          -0.106533 1.91737e-15 -0.994309,
+                          -0.156238 0.160954 -0.974517,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -0.190613 0.319272 -0.928295,
+                          -0.189985 0.315571 -0.929689,
+                          -0.207612 0.461039 -0.862752,
+                          -0.190613 0.319272 -0.928295,
+                          -0.153063 0.149074 -0.976908,
+                          -0.189985 0.315571 -0.929689,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -0.209653 0.499638 -0.84048,
+                          -0.207612 0.461039 -0.862752,
+                          -0.209134 0.595136 -0.775936,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -0.209653 0.499638 -0.84048,
+                          -0.190613 0.319272 -0.928295,
+                          -0.207612 0.461039 -0.862752,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -0.947373 0.0357123 0.318135,
+                          -0.999979 0.00394893 -0.00514859,
+                          -0.896406 0.355827 -0.264278,
+                          -0.210148 0.516013 -0.830403,
+                          -0.209653 0.499638 -0.84048,
+                          -0.209134 0.595136 -0.775936,
+                          -0.00742854 -0.998057 0.0618633,
+                          -0.00332779 -0.998557 0.0536045,
+                          -0.0152289 -0.999453 0.0293601,
+                          -0.00742854 -0.998057 0.0618633,
+                          -0.0152289 -0.999453 0.0293601,
+                          -0.0105326 -0.997732 0.0664819,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -0.975367 -0.0703845 0.209057,
+                          -0.896406 0.355827 -0.264278,
+                          -0.78291 0.581403 -0.221412,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -0.858329 0.00237028 0.513094,
+                          -0.896406 0.355827 -0.264278,
+                          -0.975367 -0.0703845 0.209057,
+                          -0.947373 0.0357123 0.318135,
+                          -0.896406 0.355827 -0.264278,
+                          -0.858329 0.00237028 0.513094,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -0.98109 -0.0766641 0.177722,
+                          -0.78291 0.581403 -0.221412,
+                          -0.789416 0.61151 -0.0536421,
+                          -0.975367 -0.0703845 0.209057,
+                          -0.78291 0.581403 -0.221412,
+                          -0.98109 -0.0766641 0.177722,
+                          -0.990621 -0.125691 -0.053586,
+                          -0.789416 0.61151 -0.0536421,
+                          -0.83858 0.515884 0.175064,
+                          -0.98109 -0.0766641 0.177722,
+                          -0.789416 0.61151 -0.0536421,
+                          -0.990621 -0.125691 -0.053586,
+                          -0.990441 -0.11642 -0.0739744,
+                          -0.83858 0.515884 0.175064,
+                          -0.84615 0.392931 0.360048,
+                          -0.988604 -0.129375 -0.0769654,
+                          -0.83858 0.515884 0.175064,
+                          -0.990441 -0.11642 -0.0739744,
+                          -0.990621 -0.125691 -0.053586,
+                          -0.83858 0.515884 0.175064,
+                          -0.988604 -0.129375 -0.0769654,
+                          -0.991759 -0.0897756 -0.0914015,
+                          -0.84615 0.392931 0.360048,
+                          -0.845445 0.215074 0.488841,
+                          -0.990441 -0.11642 -0.0739744,
+                          -0.84615 0.392931 0.360048,
+                          -0.991759 -0.0897756 -0.0914015,
+                          -0.993002 -0.0576843 -0.103053,
+                          -0.845445 0.215074 0.488841,
+                          -0.993056 -0.0216827 -0.115629,
+                          -0.991759 -0.0897756 -0.0914015,
+                          -0.845445 0.215074 0.488841,
+                          -0.993002 -0.0576843 -0.103053,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -0.920363 -1.00911e-06 0.391066,
+                          -1 -1.8456e-12 7.12089e-07,
+                          -1 4.71514e-16 5.25032e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -0.628317 0.262161 0.732454,
+                          -1 -8.85379e-17 3.44289e-16,
+                          -1 1.47115e-09 1.26441e-05,
+                          -0.628317 0.262161 0.732454,
+                          -1 1.47115e-09 1.26441e-05,
+                          -0.649215 0.1969 0.734677,
+                          -0.920358 4.44858e-05 0.391076,
+                          -0.649215 0.1969 0.734677,
+                          -1 1.47115e-09 1.26441e-05,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -0.723573 -0.212769 0.656637,
+                          -1 4.71514e-16 5.25032e-16,
+                          -1 1.25088e-15 1.72735e-15,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -0.710487 -0.1001 0.696554,
+                          -0.694135 -1.85182e-06 0.719845,
+                          -1 4.71514e-16 5.25032e-16,
+                          -0.920363 -1.00911e-06 0.391066,
+                          -1 4.71514e-16 5.25032e-16,
+                          -0.694135 -1.85182e-06 0.719845,
+                          -0.710487 -0.1001 0.696554,
+                          -1 4.71514e-16 5.25032e-16,
+                          -0.723573 -0.212769 0.656637,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -0.726746 -0.493107 0.478212,
+                          -1 1.25088e-15 1.72735e-15,
+                          -1 -8.92994e-17 -5.19094e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -0.731002 -0.343491 0.589618,
+                          -1 1.25088e-15 1.72735e-15,
+                          -0.726746 -0.493107 0.478212,
+                          -0.723573 -0.212769 0.656637,
+                          -1 1.25088e-15 1.72735e-15,
+                          -0.731002 -0.343491 0.589618,
+                          -0.668381 -0.695538 -0.263617,
+                          -1 -8.92994e-17 -5.19094e-16,
+                          -1 1.30284e-16 1.20375e-16,
+                          -0.67776 -0.705674 0.206554,
+                          -1 -8.92994e-17 -5.19094e-16,
+                          -0.668381 -0.722671 0.176106,
+                          -0.668381 -0.695538 -0.263617,
+                          -0.668381 -0.722671 0.176106,
+                          -1 -8.92994e-17 -5.19094e-16,
+                          -0.711269 -0.600738 0.364981,
+                          -1 -8.92994e-17 -5.19094e-16,
+                          -0.67776 -0.705674 0.206554,
+                          -0.726746 -0.493107 0.478212,
+                          -1 -8.92994e-17 -5.19094e-16,
+                          -0.711269 -0.600738 0.364981,
+                          -0.668381 -0.41874 -0.614755,
+                          -1 1.30284e-16 1.20375e-16,
+                          -1 1.46917e-16 2.70068e-16,
+                          -0.668381 -0.41874 -0.614755,
+                          -0.668381 -0.695538 -0.263617,
+                          -1 1.30284e-16 1.20375e-16,
+                          -0.668381 -0.41874 -0.614755,
+                          -1 1.46917e-16 2.70068e-16,
+                          -1 -1.63907e-12 -4.71261e-07,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -0.668379 1.74619e-05 -0.743821,
+                          -1 9.94564e-11 -4.11985e-06,
+                          -1 -3.27616e-17 3.85121e-16,
+                          -0.668381 -0.41874 -0.614755,
+                          -1 -1.63907e-12 -4.71261e-07,
+                          -0.668381 -2.53296e-06 -0.743819,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -0.628316 0.490351 -0.603966,
+                          -1 -3.27616e-17 3.85121e-16,
+                          -1 2.70605e-16 9.79843e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -0.628317 1.82416e-05 -0.777958,
+                          -1 -3.27616e-17 3.85121e-16,
+                          -0.628316 0.490351 -0.603966,
+                          -0.668379 1.74619e-05 -0.743821,
+                          -1 -3.27616e-17 3.85121e-16,
+                          -0.628317 1.82416e-05 -0.777958,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -0.628317 0.762212 -0.155726,
+                          -1 2.70605e-16 9.79843e-16,
+                          -1 -1.1255e-16 1.11378e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -0.628316 0.490351 -0.603966,
+                          -1 2.70605e-16 9.79843e-16,
+                          -0.628317 0.762212 -0.155726,
+                          -0.628317 0.762212 -0.155726,
+                          -1 -1.1255e-16 1.11378e-16,
+                          -1 -8.22529e-17 3.2423e-16,
+                          -0.628315 0.677926 0.381624,
+                          -1 -8.22529e-17 3.2423e-16,
+                          -1 -8.75316e-17 3.43073e-16,
+                          -0.628317 0.762212 -0.155726,
+                          -1 -8.22529e-17 3.2423e-16,
+                          -0.628315 0.677926 0.381624,
+                          -0.628315 0.677926 0.381624,
+                          -1 -8.75316e-17 3.43073e-16,
+                          -1 -8.85379e-17 3.44289e-16,
+                          -0.628315 0.677926 0.381624,
+                          -1 -8.85379e-17 3.44289e-16,
+                          -0.628317 0.262161 0.732454,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          0.977372 0.00928282 0.211324,
+                          0.854346 -1.45971e-05 0.519706,
+                          0.845445 0.215074 0.488841,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          0.991755 0.0834061 -0.0972947,
+                          0.877901 -0.194162 0.437711,
+                          0.854343 0.000118538 0.51971,
+                          0.991755 0.0834061 -0.0972947,
+                          0.854343 0.000118538 0.51971,
+                          0.992807 0.0471008 -0.110069,
+                          0.977371 0.00933189 0.211327,
+                          0.992807 0.0471008 -0.110069,
+                          0.854343 0.000118538 0.51971,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          0.993002 -0.0576843 -0.103053,
+                          0.845445 0.215074 0.488841,
+                          0.84615 0.392931 0.360048,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          0.993056 -0.0216827 -0.115629,
+                          0.845445 0.215074 0.488841,
+                          0.993002 -0.0576843 -0.103053,
+                          0.992574 0.0175536 -0.120371,
+                          0.845445 0.215074 0.488841,
+                          0.993056 -0.0216827 -0.115629,
+                          0.977372 0.00928282 0.211324,
+                          0.845445 0.215074 0.488841,
+                          0.992574 0.0175536 -0.120371,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          0.990441 -0.11642 -0.0739744,
+                          0.84615 0.392931 0.360048,
+                          0.83858 0.515884 0.175064,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          0.993002 -0.0576843 -0.103053,
+                          0.84615 0.392931 0.360048,
+                          0.991759 -0.0897756 -0.0914015,
+                          0.990441 -0.11642 -0.0739744,
+                          0.991759 -0.0897756 -0.0914015,
+                          0.84615 0.392931 0.360048,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          0.988604 -0.129375 -0.0769654,
+                          0.83858 0.515884 0.175064,
+                          0.789416 0.61151 -0.0536421,
+                          0.990441 -0.11642 -0.0739744,
+                          0.83858 0.515884 0.175064,
+                          0.988604 -0.129375 -0.0769654,
+                          0.990621 -0.125691 -0.053586,
+                          0.789416 0.61151 -0.0536421,
+                          0.78291 0.581403 -0.221412,
+                          0.988604 -0.129375 -0.0769654,
+                          0.789416 0.61151 -0.0536421,
+                          0.990621 -0.125691 -0.053586,
+                          0.98109 -0.0766641 0.177722,
+                          0.78291 0.581403 -0.221412,
+                          0.896406 0.355827 -0.264278,
+                          0.990621 -0.125691 -0.053586,
+                          0.78291 0.581403 -0.221412,
+                          0.98109 -0.0766641 0.177722,
+                          0.858329 0.00237028 0.513094,
+                          0.896406 0.355827 -0.264278,
+                          0.999979 0.00394893 -0.00514859,
+                          0.98109 -0.0766641 0.177722,
+                          0.896406 0.355827 -0.264278,
+                          0.975367 -0.0703845 0.209057,
+                          0.858329 0.00237028 0.513094,
+                          0.975367 -0.0703845 0.209057,
+                          0.896406 0.355827 -0.264278,
+                          0.210325 0.559088 -0.801987,
+                          0.209134 0.595136 -0.775936,
+                          0.207612 0.461039 -0.862752,
+                          0.00742854 -0.998057 0.0618633,
+                          0.0152289 -0.999453 0.0293601,
+                          0.00797292 -0.999008 0.0438033,
+                          0.947373 0.0357123 0.318135,
+                          0.858329 0.00237028 0.513094,
+                          0.999979 0.00394893 -0.00514859,
+                          0.0105326 -0.997732 0.0664819,
+                          0.0152289 -0.999453 0.0293601,
+                          0.00742854 -0.998057 0.0618633,
+                          0.190613 0.319272 -0.928295,
+                          0.207612 0.461039 -0.862752,
+                          0.189985 0.315571 -0.929689,
+                          0.210148 0.516013 -0.830403,
+                          0.210325 0.559088 -0.801987,
+                          0.207612 0.461039 -0.862752,
+                          0.209653 0.499638 -0.84048,
+                          0.210148 0.516013 -0.830403,
+                          0.207612 0.461039 -0.862752,
+                          0.190613 0.319272 -0.928295,
+                          0.209653 0.499638 -0.84048,
+                          0.207612 0.461039 -0.862752,
+                          0.190613 0.319272 -0.928295,
+                          0.189985 0.315571 -0.929689,
+                          0.156238 0.160954 -0.974517,
+                          0.153063 0.149074 -0.976908,
+                          0.156238 0.160954 -0.974517,
+                          0.106533 1.93626e-15 -0.994309,
+                          0.153063 0.149074 -0.976908,
+                          0.190613 0.319272 -0.928295,
+                          0.156238 0.160954 -0.974517,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          0.106533 2.14466e-15 -0.994309,
+                          0.106533 1.8145e-15 -0.994309,
+                          -0.000892922 -0.253502 -0.967334,
+                          0.106533 1.93626e-15 -0.994309,
+                          0.153063 0.149074 -0.976908,
+                          0.106533 1.93626e-15 -0.994309,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          -0.025306 -0.301118 -0.953251,
+                          -0.000892922 -0.253502 -0.967334,
+                          -0.135591 -0.485893 -0.863437,
+                          0.0525547 -0.13805 -0.98903,
+                          0.106533 2.14466e-15 -0.994309,
+                          -0.000892922 -0.253502 -0.967334,
+                          -0.025306 -0.301118 -0.953251,
+                          0.0525547 -0.13805 -0.98903,
+                          -0.000892922 -0.253502 -0.967334,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          -0.139418 -0.491531 -0.859628,
+                          -0.135591 -0.485893 -0.863437,
+                          -0.280174 -0.667451 -0.689936,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          -0.139418 -0.491531 -0.859628,
+                          -0.025306 -0.301118 -0.953251,
+                          -0.135591 -0.485893 -0.863437,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          -0.295429 -0.68291 -0.668098,
+                          -0.280174 -0.667451 -0.689936,
+                          -0.414742 -0.777777 -0.472284,
+                          -0.295429 -0.68291 -0.668098,
+                          -0.139418 -0.491531 -0.859628,
+                          -0.280174 -0.667451 -0.689936,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          -0.414287 -0.77751 -0.473122,
+                          -0.414742 -0.777777 -0.472284,
+                          -0.52567 -0.815294 -0.242831,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          -0.414287 -0.77751 -0.473122,
+                          -0.295429 -0.68291 -0.668098,
+                          -0.414742 -0.777777 -0.472284,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          -0.52807 -0.815393 -0.237225,
+                          -0.52567 -0.815294 -0.242831,
+                          -0.608951 -0.792769 -0.0263698,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          -0.52807 -0.815393 -0.237225,
+                          -0.414287 -0.77751 -0.473122,
+                          -0.52567 -0.815294 -0.242831,
+                          -0.61811 -0.786091 0.000872262,
+                          -0.608951 -0.792769 -0.0263698,
+                          -0.667042 -0.726577 0.164744,
+                          -0.61811 -0.786091 0.000872262,
+                          -0.52807 -0.815393 -0.237225,
+                          -0.608951 -0.792769 -0.0263698,
+                          -0.669909 -0.721372 0.175627,
+                          -0.667042 -0.726577 0.164744,
+                          -0.704435 -0.629828 0.327244,
+                          -0.669909 -0.721372 0.175627,
+                          -0.61811 -0.786091 0.000872262,
+                          -0.667042 -0.726577 0.164744,
+                          -0.711301 -0.600695 0.364989,
+                          -0.704435 -0.629828 0.327244,
+                          -0.72506 -0.510703 0.462029,
+                          -0.677776 -0.705669 0.206521,
+                          -0.669909 -0.721372 0.175627,
+                          -0.704435 -0.629828 0.327244,
+                          -0.711301 -0.600695 0.364989,
+                          -0.677776 -0.705669 0.206521,
+                          -0.704435 -0.629828 0.327244,
+                          0.987736 -0.0839875 0.131618,
+                          0.924799 -0.282131 0.255244,
+                          0.877901 -0.194162 0.437711,
+                          -0.711301 -0.600695 0.364989,
+                          -0.72506 -0.510703 0.462029,
+                          -0.725129 -0.510031 0.462663,
+                          0.0699932 -0.705483 -0.705262,
+                          0.0687848 -0.705177 -0.705687,
+                          0.0713743 -0.7085 -0.702092,
+                          0.0758931 -0.713875 -0.696148,
+                          0.0699932 -0.705483 -0.705262,
+                          0.0713743 -0.7085 -0.702092,
+                          0.0765099 -0.715311 -0.694606,
+                          0.0758931 -0.713875 -0.696148,
+                          0.0713743 -0.7085 -0.702092,
+                          0.987887 0.149888 -0.0401598,
+                          0.877901 -0.194162 0.437711,
+                          0.991755 0.0834061 -0.0972947,
+                          0.991137 0.13049 -0.024905,
+                          0.877901 -0.194162 0.437711,
+                          0.987887 0.149888 -0.0401598,
+                          0.987736 -0.0839875 0.131618,
+                          0.877901 -0.194162 0.437711,
+                          0.993773 0.110998 -0.00976122,
+                          0.991137 0.13049 -0.024905,
+                          0.993773 0.110998 -0.00976122,
+                          0.877901 -0.194162 0.437711,
+                          0.231685 0.932786 0.276102,
+                          0.226115 0.936715 0.267278,
+                          0.0849307 0.996061 0.0254687,
+                          0.628317 0.762212 -0.155726,
+                          0.0849313 0.99606 0.0255277,
+                          0.226025 0.936732 0.267293,
+                          0.866656 0.43049 0.252161,
+                          0.231809 0.932681 0.276352,
+                          0.0849265 0.996065 0.0253506,
+                          0.0126202 0.922799 -0.385075,
+                          0.0849313 0.99606 0.0255277,
+                          0.628317 0.762212 -0.155726,
+                          0.642347 0.661916 -0.386339,
+                          0.0849278 0.996065 0.0253519,
+                          0.0148813 0.92285 -0.384871,
+                          0.693419 0.720452 0.0109233,
+                          0.0849278 0.996065 0.0253519,
+                          0.642347 0.661916 -0.386339,
+                          0.866656 0.43049 0.252161,
+                          0.0849265 0.996065 0.0253506,
+                          0.693392 0.720475 0.0110529,
+                          0.231685 0.932786 0.276102,
+                          0.365227 0.802409 0.471962,
+                          0.226115 0.936715 0.267278,
+                          0.628315 0.677926 0.381624,
+                          0.226025 0.936732 0.267293,
+                          0.365265 0.802433 0.471892,
+                          0.628315 0.677926 0.381624,
+                          0.628317 0.762212 -0.155726,
+                          0.226025 0.936732 0.267293,
+                          0.374274 0.790938 0.484082,
+                          0.486347 0.616111 0.619575,
+                          0.365227 0.802409 0.471962,
+                          0.628315 0.677926 0.381624,
+                          0.365265 0.802433 0.471892,
+                          0.486348 0.616091 0.619595,
+                          0.231685 0.932786 0.276102,
+                          0.374274 0.790938 0.484082,
+                          0.365227 0.802409 0.471962,
+                          0.491636 0.606163 0.625189,
+                          0.58119 0.406574 0.704923,
+                          0.486347 0.616111 0.619575,
+                          0.628315 0.677926 0.381624,
+                          0.486348 0.616091 0.619595,
+                          0.581163 0.406535 0.704967,
+                          0.374274 0.790938 0.484082,
+                          0.491636 0.606163 0.625189,
+                          0.486347 0.616111 0.619575,
+                          0.58355 0.40035 0.706533,
+                          0.630571 0.26175 0.730662,
+                          0.58119 0.406574 0.704923,
+                          0.628315 0.677926 0.381624,
+                          0.581163 0.406535 0.704967,
+                          0.628317 0.262161 0.732454,
+                          0.491636 0.606163 0.625189,
+                          0.58355 0.40035 0.706533,
+                          0.58119 0.406574 0.704923,
+                          0.648163 0.200778 0.734556,
+                          0.64923 0.196873 0.734671,
+                          0.630571 0.26175 0.730662,
+                          0.58355 0.40035 0.706533,
+                          0.648163 0.200778 0.734556,
+                          0.630571 0.26175 0.730662,
+                          0.694136 -1.36375e-15 0.719844,
+                          0.694136 -1.2531e-15 0.719844,
+                          0.64923 0.196873 0.734671,
+                          0.648163 0.200778 0.734556,
+                          0.694136 -1.36375e-15 0.719844,
+                          0.64923 0.196873 0.734671,
+                          0.713448 -0.121721 0.690055,
+                          0.694136 -1.33341e-15 0.719844,
+                          0.694136 -1.33341e-15 0.719844,
+                          0.710491 -0.1001 0.696551,
+                          0.694136 -1.33341e-15 0.719844,
+                          0.713448 -0.121721 0.690055,
+                          0.920363 -1.00911e-06 0.391066,
+                          0.694135 -1.85182e-06 0.719845,
+                          0.710487 -0.1001 0.696554,
+                          0.90428 -0.00267052 0.426932,
+                          0.694137 6.75727e-05 0.719843,
+                          0.648167 0.200763 0.734557,
+                          0.997125 -0.0254795 0.0713634,
+                          0.71345 -0.121752 0.690047,
+                          0.694137 -7.26966e-05 0.719843,
+                          0.90428 -0.00273404 0.42693,
+                          0.997125 -0.0254795 0.0713634,
+                          0.694137 -7.26966e-05 0.719843,
+                          0.992512 -0.00479914 0.12205,
+                          0.648167 0.200763 0.734557,
+                          0.583541 0.400405 0.706509,
+                          0.90428 -0.00267052 0.426932,
+                          0.648167 0.200763 0.734557,
+                          0.992512 -0.00479914 0.12205,
+                          0.961352 0.153926 0.228273,
+                          0.583541 0.400405 0.706509,
+                          0.49164 0.606177 0.625171,
+                          0.992512 -0.00479914 0.12205,
+                          0.583541 0.400405 0.706509,
+                          0.961352 0.153926 0.228273,
+                          0.961352 0.153926 0.228273,
+                          0.49164 0.606177 0.625171,
+                          0.374227 0.79103 0.483969,
+                          0.866656 0.43049 0.252161,
+                          0.374227 0.79103 0.483969,
+                          0.231809 0.932681 0.276352,
+                          0.961352 0.153926 0.228273,
+                          0.374227 0.79103 0.483969,
+                          0.866656 0.43049 0.252161,
+                          0.628317 1.82416e-05 -0.777958,
+                          -0.106533 2.31468e-05 -0.994309,
+                          -0.152992 0.149087 -0.976917,
+                          0.668381 -0.41874 -0.614755,
+                          -0.0525486 -0.13805 -0.98903,
+                          -0.106533 -3.35984e-06 -0.994309,
+                          0.668381 -0.41874 -0.614755,
+                          -0.106533 -3.35984e-06 -0.994309,
+                          0.628319 -2.64657e-06 -0.777956,
+                          0.628317 1.82416e-05 -0.777958,
+                          -0.152992 0.149087 -0.976917,
+                          -0.19061 0.319261 -0.9283,
+                          0.628317 1.82416e-05 -0.777958,
+                          -0.19061 0.319261 -0.9283,
+                          -0.209719 0.499612 -0.840479,
+                          -0.208878 0.599921 -0.772312,
+                          -0.201161 0.677497 -0.707483,
+                          -0.209653 0.499638 -0.84048,
+                          0.628316 0.490351 -0.603966,
+                          -0.209719 0.499612 -0.840479,
+                          -0.201156 0.677514 -0.707468,
+                          -0.210148 0.516013 -0.830403,
+                          -0.208878 0.599921 -0.772312,
+                          -0.209653 0.499638 -0.84048,
+                          0.628316 0.490351 -0.603966,
+                          0.628317 1.82416e-05 -0.777958,
+                          -0.209719 0.499612 -0.840479,
+                          0.352459 0.246612 -0.902749,
+                          -0.201221 0.677421 -0.707539,
+                          -0.208747 0.600146 -0.772172,
+                          0.0104396 0.917928 -0.396611,
+                          0.628316 0.490351 -0.603966,
+                          -0.201156 0.677514 -0.707468,
+                          0.455343 0.460692 -0.761857,
+                          0.0104415 0.917948 -0.396564,
+                          -0.201231 0.677436 -0.707521,
+                          0.455281 0.460688 -0.761896,
+                          -0.201221 0.677421 -0.707539,
+                          0.352459 0.246612 -0.902749,
+                          0.352459 0.246612 -0.902749,
+                          -0.208747 0.600146 -0.772172,
+                          -0.210184 0.5158 -0.830526,
+                          0.726715 -0.493138 0.478226,
+                          0.726696 -0.49336 0.478026,
+                          0.725214 -0.509189 0.463455,
+                          -0.068066 -0.703678 -0.707251,
+                          -0.0658709 -0.701907 -0.709216,
+                          0.6129 -0.730795 -0.300486,
+                          0.711301 -0.600695 0.364989,
+                          0.726715 -0.493138 0.478226,
+                          0.725214 -0.509189 0.463455,
+                          0.725129 -0.510031 0.462663,
+                          0.711301 -0.600695 0.364989,
+                          0.725214 -0.509189 0.463455,
+                          -0.0680579 -0.703645 -0.707285,
+                          -0.0687848 -0.705177 -0.705687,
+                          -0.0658629 -0.701902 -0.709222,
+                          0.726715 -0.493138 0.478226,
+                          0.728109 -0.475333 0.493879,
+                          0.726696 -0.49336 0.478026,
+                          0.659017 -0.583002 -0.475189,
+                          0.6129 -0.730795 -0.300486,
+                          0.764118 -0.638666 0.0907168,
+                          -0.068066 -0.703678 -0.707251,
+                          0.6129 -0.730795 -0.300486,
+                          -0.0699883 -0.705475 -0.705271,
+                          0.659017 -0.583002 -0.475189,
+                          -0.0699883 -0.705475 -0.705271,
+                          0.6129 -0.730795 -0.300486,
+                          0.730996 -0.3435 0.589621,
+                          0.729582 -0.451022 0.514091,
+                          0.728109 -0.475333 0.493879,
+                          0.910835 -0.302738 0.280587,
+                          0.764118 -0.638666 0.0907168,
+                          0.72969 -0.451003 0.513954,
+                          0.726715 -0.493138 0.478226,
+                          0.730996 -0.3435 0.589621,
+                          0.728109 -0.475333 0.493879,
+                          0.659017 -0.583002 -0.475189,
+                          0.764118 -0.638666 0.0907168,
+                          0.910835 -0.302738 0.280587,
+                          0.730996 -0.3435 0.589621,
+                          0.731126 -0.350273 0.58546,
+                          0.729582 -0.451022 0.514091,
+                          0.992665 -0.115635 0.0352721,
+                          0.729471 -0.45117 0.514119,
+                          0.731134 -0.350274 0.58545,
+                          0.910857 -0.302704 0.280553,
+                          0.729471 -0.45117 0.514119,
+                          0.992665 -0.115635 0.0352721,
+                          0.730996 -0.3435 0.589621,
+                          0.725833 -0.239816 0.644713,
+                          0.731126 -0.350273 0.58546,
+                          0.996196 -0.0572645 0.0656818,
+                          0.731134 -0.350274 0.58545,
+                          0.725832 -0.239869 0.644694,
+                          0.992665 -0.115635 0.0352721,
+                          0.731134 -0.350274 0.58545,
+                          0.996196 -0.0572645 0.0656818,
+                          0.723576 -0.21277 0.656633,
+                          0.713448 -0.121721 0.690055,
+                          0.725833 -0.239816 0.644713,
+                          0.996196 -0.0572645 0.0656818,
+                          0.725832 -0.239869 0.644694,
+                          0.71345 -0.121752 0.690047,
+                          0.730996 -0.3435 0.589621,
+                          0.723576 -0.21277 0.656633,
+                          0.725833 -0.239816 0.644713,
+                          0.723576 -0.21277 0.656633,
+                          0.710491 -0.1001 0.696551,
+                          0.713448 -0.121721 0.690055,
+                          0.996196 -0.0572645 0.0656818,
+                          0.71345 -0.121752 0.690047,
+                          0.997125 -0.0254795 0.0713634,
+                          0.668381 -0.695538 -0.263617,
+                          0.668381 -0.722671 0.176106,
+                          0.61811 -0.786092 0.000845952,
+                          0.668381 -0.695538 -0.263617,
+                          0.61811 -0.786092 0.000845952,
+                          0.528022 -0.815421 -0.237238,
+                          0.668381 -0.695538 -0.263617,
+                          0.528022 -0.815421 -0.237238,
+                          0.414222 -0.777563 -0.473092,
+                          0.668381 -0.695538 -0.263617,
+                          0.414222 -0.777563 -0.473092,
+                          0.295503 -0.68287 -0.668106,
+                          0.668381 -0.41874 -0.614755,
+                          0.295503 -0.68287 -0.668106,
+                          0.13944 -0.491521 -0.85963,
+                          0.668381 -0.695538 -0.263617,
+                          0.295503 -0.68287 -0.668106,
+                          0.668381 -0.41874 -0.614755,
+                          0.668381 -0.41874 -0.614755,
+                          0.13944 -0.491521 -0.85963,
+                          0.0253145 -0.301116 -0.953251,
+                          0.668381 -0.41874 -0.614755,
+                          0.0253145 -0.301116 -0.953251,
+                          -0.0525486 -0.13805 -0.98903,
+                          -0.0680579 -0.703645 -0.707285,
+                          -0.0699932 -0.705483 -0.705262,
+                          -0.0687848 -0.705177 -0.705687,
+                          -0.226115 0.936715 0.267278,
+                          -0.231685 0.932786 0.276102,
+                          -0.0849307 0.996061 0.0254687,
+                          -0.693392 0.720475 0.0110529,
+                          -0.0849265 0.996065 0.0253506,
+                          -0.231809 0.932681 0.276352,
+                          -0.628315 0.677926 0.381624,
+                          -0.226025 0.936732 0.267293,
+                          -0.0849313 0.99606 0.0255277,
+                          -0.628317 0.762212 -0.155726,
+                          -0.0849313 0.99606 0.0255277,
+                          -0.0126202 0.922799 -0.385075,
+                          -0.693419 0.720452 0.0109233,
+                          -0.0148813 0.92285 -0.384871,
+                          -0.0849278 0.996065 0.0253519,
+                          -0.628317 0.762212 -0.155726,
+                          -0.628315 0.677926 0.381624,
+                          -0.0849313 0.99606 0.0255277,
+                          -0.365227 0.802409 0.471962,
+                          -0.374274 0.790938 0.484082,
+                          -0.231685 0.932786 0.276102,
+                          -0.866656 0.43049 0.252161,
+                          -0.231809 0.932681 0.276352,
+                          -0.374227 0.79103 0.483969,
+                          -0.226115 0.936715 0.267278,
+                          -0.365227 0.802409 0.471962,
+                          -0.231685 0.932786 0.276102,
+                          -0.866656 0.43049 0.252161,
+                          -0.693392 0.720475 0.0110529,
+                          -0.231809 0.932681 0.276352,
+                          -0.486347 0.616111 0.619575,
+                          -0.491636 0.606163 0.625189,
+                          -0.374274 0.790938 0.484082,
+                          -0.866656 0.43049 0.252161,
+                          -0.374227 0.79103 0.483969,
+                          -0.49164 0.606177 0.625171,
+                          -0.365227 0.802409 0.471962,
+                          -0.486347 0.616111 0.619575,
+                          -0.374274 0.790938 0.484082,
+                          -0.58119 0.406574 0.704923,
+                          -0.58355 0.40035 0.706533,
+                          -0.491636 0.606163 0.625189,
+                          -0.961352 0.153926 0.228273,
+                          -0.49164 0.606177 0.625171,
+                          -0.583541 0.400405 0.706509,
+                          -0.486347 0.616111 0.619575,
+                          -0.58119 0.406574 0.704923,
+                          -0.491636 0.606163 0.625189,
+                          -0.866656 0.43049 0.252161,
+                          -0.49164 0.606177 0.625171,
+                          -0.961352 0.153926 0.228273,
+                          -0.630571 0.26175 0.730662,
+                          -0.648163 0.200778 0.734556,
+                          -0.58355 0.40035 0.706533,
+                          -0.961352 0.153926 0.228273,
+                          -0.583541 0.400405 0.706509,
+                          -0.648167 0.200763 0.734557,
+                          -0.58119 0.406574 0.704923,
+                          -0.630571 0.26175 0.730662,
+                          -0.58355 0.40035 0.706533,
+                          -0.694136 -1.37617e-15 0.719844,
+                          -0.694136 -1.48682e-15 0.719844,
+                          -0.648163 0.200778 0.734556,
+                          -0.961352 0.153926 0.228273,
+                          -0.648167 0.200763 0.734557,
+                          -0.694137 6.75727e-05 0.719843,
+                          -0.64923 0.196873 0.734671,
+                          -0.694136 -1.37617e-15 0.719844,
+                          -0.648163 0.200778 0.734556,
+                          -0.630571 0.26175 0.730662,
+                          -0.64923 0.196873 0.734671,
+                          -0.648163 0.200778 0.734556,
+                          -0.710491 -0.1001 0.696551,
+                          -0.694136 -1.45648e-15 0.719844,
+                          -0.694136 -1.45648e-15 0.719844,
+                          -0.710491 -0.1001 0.696551,
+                          -0.713448 -0.12172 0.690055,
+                          -0.694136 -1.45648e-15 0.719844,
+                          -0.90428 -0.00273404 0.42693,
+                          -0.694137 -7.26966e-05 0.719843,
+                          -0.71345 -0.121752 0.690047,
+                          -0.90428 -0.00267052 0.426932,
+                          -0.961352 0.153926 0.228273,
+                          -0.694137 6.75727e-05 0.719843,
+                          -0.920358 4.44858e-05 0.391076,
+                          -0.694129 8.04319e-05 0.719851,
+                          -0.649215 0.1969 0.734677,
+                          -0.628315 0.677926 0.381624,
+                          -0.628317 0.262161 0.732454,
+                          -0.581163 0.406535 0.704967,
+                          -0.628315 0.677926 0.381624,
+                          -0.581163 0.406535 0.704967,
+                          -0.486348 0.616091 0.619595,
+                          -0.628315 0.677926 0.381624,
+                          -0.486348 0.616091 0.619595,
+                          -0.365265 0.802433 0.471892,
+                          -0.628315 0.677926 0.381624,
+                          -0.365265 0.802433 0.471892,
+                          -0.226025 0.936732 0.267293,
+                          0.00742854 -0.998057 0.0618633,
+                          0.00797292 -0.999008 0.0438033,
+                          0.00332779 -0.998557 0.0536045,
+                          0.209653 0.499638 -0.84048,
+                          0.208878 0.599921 -0.772312,
+                          0.210148 0.516013 -0.830403,
+                          -0.352459 0.246612 -0.902749,
+                          0.210184 0.5158 -0.830526,
+                          0.208747 0.600146 -0.772172,
+                          0.209653 0.499638 -0.84048,
+                          0.201161 0.677497 -0.707483,
+                          0.208878 0.599921 -0.772312,
+                          -0.455281 0.460688 -0.761896,
+                          0.208747 0.600146 -0.772172,
+                          0.201221 0.677421 -0.707539,
+                          -0.455281 0.460688 -0.761896,
+                          -0.352459 0.246612 -0.902749,
+                          0.208747 0.600146 -0.772172,
+                          -0.628316 0.490351 -0.603966,
+                          0.201156 0.677514 -0.707468,
+                          0.209719 0.499612 -0.840479,
+                          -0.628317 0.762212 -0.155726,
+                          -0.0104396 0.917928 -0.396611,
+                          0.201156 0.677514 -0.707468,
+                          -0.642347 0.661916 -0.386339,
+                          0.201231 0.677436 -0.707521,
+                          -0.0104415 0.917948 -0.396564,
+                          -0.628316 0.490351 -0.603966,
+                          -0.628317 0.762212 -0.155726,
+                          0.201156 0.677514 -0.707468,
+                          -0.642347 0.661916 -0.386339,
+                          -0.455343 0.460692 -0.761857,
+                          0.201231 0.677436 -0.707521,
+                          -0.628316 0.490351 -0.603966,
+                          0.209719 0.499612 -0.840479,
+                          0.19061 0.319261 -0.9283,
+                          -0.628316 0.490351 -0.603966,
+                          0.19061 0.319261 -0.9283,
+                          0.152992 0.149087 -0.976917,
+                          -0.628316 0.490351 -0.603966,
+                          0.152992 0.149087 -0.976917,
+                          0.106533 2.31468e-05 -0.994309,
+                          -0.628319 -2.64657e-06 -0.777956,
+                          0.106533 -3.35984e-06 -0.994309,
+                          0.0525486 -0.13805 -0.98903,
+                          -0.628317 1.82416e-05 -0.777958,
+                          -0.628316 0.490351 -0.603966,
+                          0.106533 2.31468e-05 -0.994309,
+                          -0.723576 -0.21277 0.656633,
+                          -0.725833 -0.239816 0.644713,
+                          -0.713448 -0.12172 0.690055,
+                          -0.997125 -0.0254795 0.0713634,
+                          -0.71345 -0.121752 0.690047,
+                          -0.725832 -0.239869 0.644694,
+                          -0.710491 -0.1001 0.696551,
+                          -0.723576 -0.21277 0.656633,
+                          -0.713448 -0.12172 0.690055,
+                          -0.996899 -0.00504281 0.0785324,
+                          -0.71345 -0.121752 0.690047,
+                          -0.997125 -0.0254795 0.0713634,
+                          -0.992513 -0.00479334 0.122048,
+                          -0.71345 -0.121752 0.690047,
+                          -0.996899 -0.00504281 0.0785324,
+                          -0.90428 -0.00273404 0.42693,
+                          -0.71345 -0.121752 0.690047,
+                          -0.992513 -0.00479334 0.122048,
+                          -0.730996 -0.3435 0.589621,
+                          -0.731126 -0.350273 0.58546,
+                          -0.725833 -0.239816 0.644713,
+                          -0.996196 -0.0572645 0.0656818,
+                          -0.725832 -0.239869 0.644694,
+                          -0.731134 -0.350274 0.58545,
+                          -0.723576 -0.21277 0.656633,
+                          -0.730996 -0.3435 0.589621,
+                          -0.725833 -0.239816 0.644713,
+                          -0.996196 -0.0572645 0.0656818,
+                          -0.997125 -0.0254795 0.0713634,
+                          -0.725832 -0.239869 0.644694,
+                          -0.726715 -0.493138 0.478226,
+                          -0.729582 -0.451021 0.514091,
+                          -0.731126 -0.350273 0.58546,
+                          -0.996196 -0.0572645 0.0656818,
+                          -0.731134 -0.350274 0.58545,
+                          -0.729469 -0.45117 0.51412,
+                          -0.730996 -0.3435 0.589621,
+                          -0.726715 -0.493138 0.478226,
+                          -0.731126 -0.350273 0.58546,
+                          -0.726715 -0.493138 0.478226,
+                          -0.728108 -0.475344 0.493869,
+                          -0.729582 -0.451021 0.514091,
+                          -0.910817 -0.302761 0.280619,
+                          -0.729691 -0.451002 0.513953,
+                          -0.764098 -0.63872 0.0905027,
+                          -0.91084 -0.302726 0.280585,
+                          -0.996196 -0.0572645 0.0656818,
+                          -0.729469 -0.45117 0.51412,
+                          -0.726715 -0.493138 0.478226,
+                          -0.726698 -0.493341 0.478043,
+                          -0.728108 -0.475344 0.493869,
+                          -0.659025 -0.583003 -0.475178,
+                          -0.764098 -0.63872 0.0905027,
+                          -0.613211 -0.730726 -0.300018,
+                          -0.910817 -0.302761 0.280619,
+                          -0.764098 -0.63872 0.0905027,
+                          -0.992671 -0.115594 0.0352401,
+                          -0.659025 -0.583003 -0.475178,
+                          -0.992671 -0.115594 0.0352401,
+                          -0.764098 -0.63872 0.0905027,
+                          -0.711301 -0.600695 0.364989,
+                          -0.725214 -0.509189 0.463455,
+                          -0.726698 -0.493341 0.478043,
+                          0.0680653 -0.703675 -0.707254,
+                          -0.613211 -0.730726 -0.300018,
+                          0.0658689 -0.701906 -0.709218,
+                          -0.726715 -0.493138 0.478226,
+                          -0.711301 -0.600695 0.364989,
+                          -0.726698 -0.493341 0.478043,
+                          0.0699896 -0.705475 -0.705271,
+                          -0.613211 -0.730726 -0.300018,
+                          0.0680653 -0.703675 -0.707254,
+                          -0.659025 -0.583003 -0.475178,
+                          -0.613211 -0.730726 -0.300018,
+                          0.0699896 -0.705475 -0.705271,
+                          -0.711301 -0.600695 0.364989,
+                          -0.725129 -0.510031 0.462663,
+                          -0.725214 -0.509189 0.463455,
+                          0.068058 -0.703645 -0.707285,
+                          0.0658629 -0.701902 -0.709222,
+                          0.0687848 -0.705177 -0.705687,
+                          0.0699932 -0.705483 -0.705262,
+                          0.068058 -0.703645 -0.707285,
+                          0.0687848 -0.705177 -0.705687,
+                          -0.668381 -2.53296e-06 -0.743819,
+                          0.0525486 -0.13805 -0.98903,
+                          -0.0253145 -0.301116 -0.953251,
+                          -0.668381 -2.53296e-06 -0.743819,
+                          -0.628319 -2.64657e-06 -0.777956,
+                          0.0525486 -0.13805 -0.98903,
+                          -0.668381 -2.53296e-06 -0.743819,
+                          -0.0253145 -0.301116 -0.953251,
+                          -0.13944 -0.491521 -0.85963,
+                          -0.668381 -0.41874 -0.614755,
+                          -0.13944 -0.491521 -0.85963,
+                          -0.295503 -0.68287 -0.668106,
+                          -0.668381 -0.41874 -0.614755,
+                          -0.668381 -2.53296e-06 -0.743819,
+                          -0.13944 -0.491521 -0.85963,
+                          -0.668381 -0.41874 -0.614755,
+                          -0.295503 -0.68287 -0.668106,
+                          -0.414222 -0.777563 -0.473092,
+                          -0.668381 -0.695538 -0.263617,
+                          -0.414222 -0.777563 -0.473092,
+                          -0.528022 -0.815421 -0.237238,
+                          -0.668381 -0.41874 -0.614755,
+                          -0.414222 -0.777563 -0.473092,
+                          -0.668381 -0.695538 -0.263617,
+                          -0.668381 -0.695538 -0.263617,
+                          -0.528022 -0.815421 -0.237238,
+                          -0.61811 -0.786092 0.000845952,
+                          -0.668381 -0.695538 -0.263617,
+                          -0.61811 -0.786092 0.000845952,
+                          -0.668381 -0.722671 0.176106,
+                          0.668379 1.74619e-05 -0.743821,
+                          0.628317 1.82416e-05 -0.777958,
+                          0.628316 0.490351 -0.603966,
+                          0.668381 -0.41874 -0.614755,
+                          0.628319 -2.64657e-06 -0.777956,
+                          0.668381 -2.53296e-06 -0.743819,
+                          0.0126202 0.922799 -0.385075,
+                          0.628317 0.762212 -0.155726,
+                          0.628316 0.490351 -0.603966,
+                          0.0104396 0.917928 -0.396611,
+                          0.0126202 0.922799 -0.385075,
+                          0.628316 0.490351 -0.603966,
+                          0.455343 0.460692 -0.761857,
+                          0.0148813 0.92285 -0.384871,
+                          0.0104415 0.917948 -0.396564,
+                          0.642347 0.661916 -0.386339,
+                          0.0148813 0.92285 -0.384871,
+                          0.455343 0.460692 -0.761857,
+                          -0.628317 0.762212 -0.155726,
+                          -0.0126202 0.922799 -0.385075,
+                          -0.0104396 0.917928 -0.396611,
+                          -0.642347 0.661916 -0.386339,
+                          -0.0104415 0.917948 -0.396564,
+                          -0.0148813 0.92285 -0.384871,
+                          -0.693419 0.720452 0.0109233,
+                          -0.642347 0.661916 -0.386339,
+                          -0.0148813 0.92285 -0.384871,
+                          0.0757064 -0.101912 0.991908,
+                          0.115872 -0.0560996 0.991679,
+                          0.0913467 -0.0141368 0.995719,
+                          1 -3.38128e-17 -3.44339e-16,
+                          1 -3.38128e-17 -3.44339e-16,
+                          0.916576 0.39986 4.10285e-16,
+                          0.0175612 0.065991 0.997666,
+                          0.0757064 -0.101912 0.991908,
+                          0.0913467 -0.0141368 0.995719,
+                          0.0918966 0.0198694 0.99557,
+                          0.0175612 0.065991 0.997666,
+                          0.0913467 -0.0141368 0.995719,
+                          0.946239 -0.323468 -9.13046e-16,
+                          0.939359 -0.342936 -9.46018e-16,
+                          1 -3.38128e-17 -3.44339e-16,
+                          0.946239 -0.323468 -9.13046e-16,
+                          1 -3.38128e-17 -3.44339e-16,
+                          1 -3.38128e-17 -3.44339e-16,
+                          0.0757064 -0.101912 0.991908,
+                          0.167142 -0.0959123 0.981256,
+                          0.115872 -0.0560996 0.991679,
+                          0.701103 0.71306 1.05306e-15,
+                          0.916576 0.39986 4.10285e-16,
+                          0.68804 0.725673 1.08046e-15,
+                          0.921271 0.388922 3.88813e-16,
+                          0.916576 0.39986 4.10285e-16,
+                          0.701103 0.71306 1.05306e-15,
+                          1 -3.38128e-17 -3.44339e-16,
+                          0.916576 0.39986 4.10285e-16,
+                          0.921271 0.388922 3.88813e-16,
+                          0.0757064 -0.101912 0.991908,
+                          0.239228 -0.128347 0.962443,
+                          0.167142 -0.0959123 0.981256,
+                          0.385974 0.92251 1.5418e-15,
+                          0.68804 0.725673 1.08046e-15,
+                          0.36724 0.930126 1.56208e-15,
+                          0.701103 0.71306 1.05306e-15,
+                          0.68804 0.725673 1.08046e-15,
+                          0.385974 0.92251 1.5418e-15,
+                          0.279895 -0.143375 0.949264,
+                          0.334396 -0.147939 0.930749,
+                          0.239228 -0.128347 0.962443,
+                          0.0189844 0.99982 1.80852e-15,
+                          0.36724 0.930126 1.56208e-15,
+                          -0.00427686 0.999991 1.81684e-15,
+                          0.0757064 -0.101912 0.991908,
+                          0.279895 -0.143375 0.949264,
+                          0.239228 -0.128347 0.962443,
+                          0.385974 0.92251 1.5418e-15,
+                          0.36724 0.930126 1.56208e-15,
+                          0.0189844 0.99982 1.80852e-15,
+                          0.624597 -0.145709 0.767234,
+                          0.446433 -0.1465 0.882743,
+                          0.334396 -0.147939 0.930749,
+                          -0.330721 0.943729 1.82711e-15,
+                          -0.00427686 0.999991 1.81684e-15,
+                          -0.373464 0.927645 1.81263e-15,
+                          0.279895 -0.143375 0.949264,
+                          0.624597 -0.145709 0.767234,
+                          0.334396 -0.147939 0.930749,
+                          0.0189844 0.99982 1.80852e-15,
+                          -0.00427686 0.999991 1.81684e-15,
+                          -0.330721 0.943729 1.82711e-15,
+                          0.624597 -0.145709 0.767234,
+                          0.59448 -0.116847 0.795575,
+                          0.446433 -0.1465 0.882743,
+                          -0.615255 0.788328 1.64297e-15,
+                          -0.373464 0.927645 1.81263e-15,
+                          -0.725652 0.688062 1.49897e-15,
+                          -0.330721 0.943729 1.82711e-15,
+                          -0.373464 0.927645 1.81263e-15,
+                          -0.615255 0.788328 1.64297e-15,
+                          0.624597 -0.145709 0.767234,
+                          0.71817 -0.0691792 0.692421,
+                          0.59448 -0.116847 0.795575,
+                          -0.907919 0.419145 1.07354e-15,
+                          -0.725652 0.688062 1.49897e-15,
+                          -0.938614 0.344969 9.49453e-16,
+                          -0.615255 0.788328 1.64297e-15,
+                          -0.725652 0.688062 1.49897e-15,
+                          -0.907919 0.419145 1.07354e-15,
+                          0.95722 -0.0695989 0.280866,
+                          0.762036 -0.0263223 0.647,
+                          0.71817 -0.0691792 0.692421,
+                          -0.907919 0.419145 1.07354e-15,
+                          -0.938614 0.344969 9.49453e-16,
+                          -1 1.56273e-16 3.44339e-16,
+                          0.624597 -0.145709 0.767234,
+                          0.95722 -0.0695989 0.280866,
+                          0.71817 -0.0691792 0.692421,
+                          0.91034 0.0869548 0.404622,
+                          0.744628 0.00411571 0.667467,
+                          0.762036 -0.0263223 0.647,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -0.956458 -0.291871 -2.00512e-16,
+                          0.95722 -0.0695989 0.280866,
+                          0.91034 0.0869548 0.404622,
+                          0.762036 -0.0263223 0.647,
+                          -0.907919 0.419145 1.07354e-15,
+                          -1 1.56273e-16 3.44339e-16,
+                          -1 1.56273e-16 3.44339e-16,
+                          0.91034 0.0869548 0.404622,
+                          0.669396 0.0303265 0.742287,
+                          0.744628 0.00411571 0.667467,
+                          -0.862159 -0.506638 -6.22866e-16,
+                          -0.956458 -0.291871 -2.00512e-16,
+                          -0.820191 -0.57209 -7.56139e-16,
+                          -0.862159 -0.506638 -6.22866e-16,
+                          -1 -8.86479e-17 3.44339e-16,
+                          -0.956458 -0.291871 -2.00512e-16,
+                          0.91034 0.0869548 0.404622,
+                          0.530491 0.0483385 0.846311,
+                          0.669396 0.0303265 0.742287,
+                          -0.691127 -0.722733 -1.07406e-15,
+                          -0.820191 -0.57209 -7.56139e-16,
+                          -0.585815 -0.810444 -1.26955e-15,
+                          -0.862159 -0.506638 -6.22866e-16,
+                          -0.820191 -0.57209 -7.56139e-16,
+                          -0.691127 -0.722733 -1.07406e-15,
+                          0.559773 0.341124 0.755175,
+                          0.530491 0.0483385 0.846311,
+                          0.91034 0.0869548 0.404622,
+                          0.559773 0.341124 0.755175,
+                          0.160063 0.313194 0.936103,
+                          0.530491 0.0483385 0.846311,
+                          0.430505 0.0673644 0.900071,
+                          0.530491 0.0483385 0.846311,
+                          0.160063 0.313194 0.936103,
+                          -0.691127 -0.722733 -1.07406e-15,
+                          -0.585815 -0.810444 -1.26955e-15,
+                          -0.362794 -0.931869 -1.56678e-15,
+                          0.95722 -0.0695989 0.280866,
+                          0.98778 0.0905609 0.126842,
+                          0.91034 0.0869548 0.404622,
+                          0.878802 0.316614 0.357019,
+                          0.91034 0.0869548 0.404622,
+                          0.98778 0.0905609 0.126842,
+                          0.878802 0.316614 0.357019,
+                          0.559773 0.341124 0.755175,
+                          0.91034 0.0869548 0.404622,
+                          0.995575 0.0586257 0.0734385,
+                          0.993602 0.0916832 0.0659415,
+                          0.98778 0.0905609 0.126842,
+                          0.952511 0.271619 0.13764,
+                          0.98778 0.0905609 0.126842,
+                          0.993602 0.0916832 0.0659415,
+                          0.996898 -0.0050512 0.0785375,
+                          0.995575 0.0586257 0.0734385,
+                          0.98778 0.0905609 0.126842,
+                          0.99695 -0.0261594 0.0735236,
+                          0.996898 -0.0050512 0.0785375,
+                          0.98778 0.0905609 0.126842,
+                          0.95722 -0.0695989 0.280866,
+                          0.99695 -0.0261594 0.0735236,
+                          0.98778 0.0905609 0.126842,
+                          0.952511 0.271619 0.13764,
+                          0.878802 0.316614 0.357019,
+                          0.98778 0.0905609 0.126842,
+                          0.961352 0.153926 0.228273,
+                          0.993904 0.0903405 0.0631921,
+                          0.995574 0.0586423 0.0734391,
+                          0.960734 0.263121 0.088073,
+                          0.952511 0.271619 0.13764,
+                          0.993602 0.0916832 0.0659415,
+                          0.991592 0.108527 0.0704728,
+                          0.960734 0.263121 0.088073,
+                          0.993602 0.0916832 0.0659415,
+                          0.866656 0.43049 0.252161,
+                          0.991552 0.108655 0.0708467,
+                          0.993904 0.0903405 0.0631921,
+                          0.961352 0.153926 0.228273,
+                          0.866656 0.43049 0.252161,
+                          0.993904 0.0903405 0.0631921,
+                          0.961352 0.153926 0.228273,
+                          0.995574 0.0586423 0.0734391,
+                          0.996899 -0.00505742 0.078535,
+                          0.992513 -0.00479334 0.122048,
+                          0.996899 -0.00504281 0.0785324,
+                          0.997125 -0.0254795 0.0713634,
+                          0.992512 -0.00479914 0.12205,
+                          0.961352 0.153926 0.228273,
+                          0.996899 -0.00505742 0.078535,
+                          0.983867 -0.160678 0.0786607,
+                          0.99695 -0.0261594 0.0735236,
+                          0.95722 -0.0695989 0.280866,
+                          0.983867 -0.160678 0.0786607,
+                          0.996196 -0.0572404 0.0656986,
+                          0.99695 -0.0261594 0.0735236,
+                          0.90428 -0.00273404 0.42693,
+                          0.992513 -0.00479334 0.122048,
+                          0.997125 -0.0254795 0.0713634,
+                          0.625938 -0.311625 0.714907,
+                          0.95722 -0.0695989 0.280866,
+                          0.624597 -0.145709 0.767234,
+                          0.953529 -0.211032 0.215055,
+                          0.983867 -0.160678 0.0786607,
+                          0.95722 -0.0695989 0.280866,
+                          0.625938 -0.311625 0.714907,
+                          0.953529 -0.211032 0.215055,
+                          0.95722 -0.0695989 0.280866,
+                          0.411238 -0.315332 0.855248,
+                          0.624597 -0.145709 0.767234,
+                          0.279895 -0.143375 0.949264,
+                          0.411238 -0.315332 0.855248,
+                          0.625938 -0.311625 0.714907,
+                          0.624597 -0.145709 0.767234,
+                          0.264781 -0.289391 0.919861,
+                          0.279895 -0.143375 0.949264,
+                          0.0757064 -0.101912 0.991908,
+                          0.264781 -0.289391 0.919861,
+                          0.411238 -0.315332 0.855248,
+                          0.279895 -0.143375 0.949264,
+                          0.0175612 0.065991 0.997666,
+                          0.068466 -0.0897697 0.993606,
+                          0.0757064 -0.101912 0.991908,
+                          0.989949 0.141421 -8.41444e-17,
+                          0.989949 0.141421 -8.41444e-17,
+                          0.989949 0.141421 -8.41444e-17,
+                          0.136275 -0.190295 0.972223,
+                          0.14008 -0.195296 0.970689,
+                          0.0757064 -0.101912 0.991908,
+                          0.264781 -0.289391 0.919861,
+                          0.0757064 -0.101912 0.991908,
+                          0.14008 -0.195296 0.970689,
+                          0.989949 0.141421 -8.41444e-17,
+                          0.989949 0.141421 -8.41444e-17,
+                          0.989949 0.141421 -8.41444e-17,
+                          0.0175612 0.065991 0.997666,
+                          0.0298239 0.0124091 0.999478,
+                          0.068466 -0.0897697 0.993606,
+                          0.989949 0.141421 -8.41444e-17,
+                          0.989949 0.141421 -8.41444e-17,
+                          0.989949 0.141421 -8.41444e-17,
+                          0.989949 0.141421 -8.41444e-17,
+                          0.989949 0.141421 -8.41444e-17,
+                          0.989949 0.141421 -8.41444e-17,
+                          0.0175612 0.065991 0.997666,
+                          0.0237821 0.0364679 0.999052,
+                          0.0298239 0.0124091 0.999478,
+                          8.00716e-09 0.24581 0.969318,
+                          0.989954 0.141386 -0.000253812,
+                          0.74145 0.175543 0.647639,
+                          0.989949 0.141426 1.56733e-05,
+                          0.989954 0.141386 -0.000253812,
+                          8.00716e-09 0.24581 0.969318,
+                          8.00716e-09 0.24581 0.969318,
+                          0.74145 0.175543 0.647639,
+                          0.330594 0.110064 0.937333,
+                          -9.91619e-16 0.0709012 0.997483,
+                          0.00831958 0.0664736 0.997754,
+                          0.0175612 0.065991 0.997666,
+                          -8.86479e-17 1 1.81538e-15,
+                          -8.86479e-17 1 1.81538e-15,
+                          -8.86479e-17 1 1.81538e-15,
+                          0.11249 0.0499885 0.992395,
+                          -9.91619e-16 0.0709012 0.997483,
+                          0.0175612 0.065991 0.997666,
+                          0.0918966 0.0198694 0.99557,
+                          0.11249 0.0499885 0.992395,
+                          0.0175612 0.065991 0.997666,
+                          8.00716e-09 0.24581 0.969318,
+                          0.330594 0.110064 0.937333,
+                          0.169535 0.0899003 0.981415,
+                          -9.91619e-16 0.0709012 0.997483,
+                          -9.91531e-16 0.0666362 0.997777,
+                          0.00831958 0.0664736 0.997754,
+                          -8.86479e-17 1 1.81538e-15,
+                          -8.86479e-17 1 1.81538e-15,
+                          -8.86479e-17 1 1.81538e-15,
+                          -8.86479e-17 1 1.81538e-15,
+                          -8.86479e-17 1 1.81538e-15,
+                          -8.86479e-17 1 1.81538e-15,
+                          -0.13835 0.0577876 0.988696,
+                          -9.9164e-16 0.0666362 0.997777,
+                          -9.91727e-16 0.0709012 0.997483,
+                          -0.00831922 0.0664736 0.997754,
+                          -9.9164e-16 0.0666362 0.997777,
+                          -0.13835 0.0577876 0.988696,
+                          -8.86479e-17 1 1.81538e-15,
+                          -8.86479e-17 1 1.81538e-15,
+                          -8.86479e-17 1 1.81538e-15,
+                          -9.79408e-16 0.245809 0.969318,
+                          -9.9164e-16 0.0666362 0.997777,
+                          -9.9164e-16 0.0666362 0.997777,
+                          -9.79408e-16 0.245809 0.969318,
+                          -9.9164e-16 0.0666362 0.997777,
+                          -9.9164e-16 0.0666362 0.997777,
+                          0.11249 0.0499885 0.992395,
+                          0.13835 0.0577876 0.988696,
+                          -9.91619e-16 0.0709012 0.997483,
+                          -9.71303e-16 0.288825 0.957382,
+                          -9.91619e-16 0.0709012 0.997483,
+                          0.13835 0.0577876 0.988696,
+                          -0.160063 0.313194 0.936103,
+                          -9.91727e-16 0.0709012 0.997483,
+                          -9.71429e-16 0.288825 0.957382,
+                          -0.160063 0.313194 0.936103,
+                          -0.13835 0.0577876 0.988696,
+                          -9.91727e-16 0.0709012 0.997483,
+                          0.758344 -0.651854 -1.44449e-15,
+                          0.628344 -0.777936 -1.62861e-15,
+                          0.760252 -0.649629 -1.44111e-15,
+                          0.160063 0.313194 0.936103,
+                          0.13835 0.0577876 0.988696,
+                          0.213515 0.0793783 0.97371,
+                          0.289189 -0.957272 -1.83739e-15,
+                          0.237185 -0.971465 -1.84525e-15,
+                          0.628344 -0.777936 -1.62861e-15,
+                          -9.67981e-16 0.304038 0.95266,
+                          -9.71303e-16 0.288825 0.957382,
+                          0.13835 0.0577876 0.988696,
+                          0.160063 0.313194 0.936103,
+                          -9.67981e-16 0.304038 0.95266,
+                          0.13835 0.0577876 0.988696,
+                          0.542668 -0.839947 -1.71169e-15,
+                          0.628344 -0.777936 -1.62861e-15,
+                          0.758344 -0.651854 -1.44449e-15,
+                          0.289189 -0.957272 -1.83739e-15,
+                          0.628344 -0.777936 -1.62861e-15,
+                          0.542668 -0.839947 -1.71169e-15,
+                          0.785926 -0.61832 -1.39311e-15,
+                          0.760252 -0.649629 -1.44111e-15,
+                          0.939359 -0.342936 -9.46018e-16,
+                          0.758344 -0.651854 -1.44449e-15,
+                          0.760252 -0.649629 -1.44111e-15,
+                          0.785926 -0.61832 -1.39311e-15,
+                          0.785926 -0.61832 -1.39311e-15,
+                          0.939359 -0.342936 -9.46018e-16,
+                          0.946239 -0.323468 -9.13046e-16,
+                          0.304531 0.0785021 0.949262,
+                          0.160063 0.313194 0.936103,
+                          0.213515 0.0793783 0.97371,
+                          -0.0250147 -0.999687 -1.8062e-15,
+                          -0.057645 -0.998337 -1.79251e-15,
+                          0.237185 -0.971465 -1.84525e-15,
+                          -0.0250147 -0.999687 -1.8062e-15,
+                          0.237185 -0.971465 -1.84525e-15,
+                          0.289189 -0.957272 -1.83739e-15,
+                          -0.160063 0.313194 0.936103,
+                          -9.71429e-16 0.288825 0.957382,
+                          -9.68112e-16 0.304038 0.95266,
+                          -8.45596e-16 0.596404 0.802684,
+                          -9.67981e-16 0.304038 0.95266,
+                          0.160063 0.313194 0.936103,
+                          -0.139499 0.643651 0.752498,
+                          -9.68112e-16 0.304038 0.95266,
+                          -8.45865e-16 0.596404 0.802684,
+                          -0.139499 0.643651 0.752498,
+                          -0.160063 0.313194 0.936103,
+                          -9.68112e-16 0.304038 0.95266,
+                          0.139499 0.643651 0.752498,
+                          0.160063 0.313194 0.936103,
+                          0.559773 0.341124 0.755175,
+                          0.304531 0.0785021 0.949262,
+                          0.430505 0.0673644 0.900071,
+                          0.160063 0.313194 0.936103,
+                          -8.27705e-16 0.623001 0.782221,
+                          -8.45596e-16 0.596404 0.802684,
+                          0.160063 0.313194 0.936103,
+                          0.139499 0.643651 0.752498,
+                          -8.27705e-16 0.623001 0.782221,
+                          0.160063 0.313194 0.936103,
+                          0.42828 0.679601 0.595583,
+                          0.559773 0.341124 0.755175,
+                          0.878802 0.316614 0.357019,
+                          0.42828 0.679601 0.595583,
+                          0.139499 0.643651 0.752498,
+                          0.559773 0.341124 0.755175,
+                          0.68193 0.644307 0.346179,
+                          0.878802 0.316614 0.357019,
+                          0.952511 0.271619 0.13764,
+                          0.68193 0.644307 0.346179,
+                          0.42828 0.679601 0.595583,
+                          0.878802 0.316614 0.357019,
+                          0.796718 0.589085 0.134976,
+                          0.952511 0.271619 0.13764,
+                          0.960734 0.263121 0.088073,
+                          0.796718 0.589085 0.134976,
+                          0.68193 0.644307 0.346179,
+                          0.952511 0.271619 0.13764,
+                          0.990817 0.12005 0.0622115,
+                          0.958937 0.282647 0.0234522,
+                          0.960734 0.263121 0.088073,
+                          0.815091 0.576393 0.0582807,
+                          0.960734 0.263121 0.088073,
+                          0.958937 0.282647 0.0234522,
+                          0.991592 0.108527 0.0704728,
+                          0.990817 0.12005 0.0622115,
+                          0.960734 0.263121 0.088073,
+                          0.815091 0.576393 0.0582807,
+                          0.796718 0.589085 0.134976,
+                          0.960734 0.263121 0.088073,
+                          0.958138 0.0744003 -0.276472,
+                          0.910919 0.343837 -0.228039,
+                          0.958937 0.282647 0.0234522,
+                          0.785138 0.618892 -0.0230438,
+                          0.958937 0.282647 0.0234522,
+                          0.910919 0.343837 -0.228039,
+                          0.971648 0.0937846 -0.217036,
+                          0.958138 0.0744003 -0.276472,
+                          0.958937 0.282647 0.0234522,
+                          0.973255 0.0948206 -0.209245,
+                          0.971648 0.0937846 -0.217036,
+                          0.958937 0.282647 0.0234522,
+                          0.99235 0.123176 -0.0083192,
+                          0.973255 0.0948206 -0.209245,
+                          0.958937 0.282647 0.0234522,
+                          0.990817 0.12005 0.0622115,
+                          0.99235 0.123176 -0.0083192,
+                          0.958937 0.282647 0.0234522,
+                          0.785138 0.618892 -0.0230438,
+                          0.815091 0.576393 0.0582807,
+                          0.958937 0.282647 0.0234522,
+                          0.774218 0.177839 -0.607421,
+                          0.73764 0.371382 -0.563882,
+                          0.910919 0.343837 -0.228039,
+                          0.680072 0.69777 -0.224987,
+                          0.910919 0.343837 -0.228039,
+                          0.73764 0.371382 -0.563882,
+                          0.766331 0.0457247 -0.640817,
+                          0.774218 0.177839 -0.607421,
+                          0.910919 0.343837 -0.228039,
+                          0.958138 0.0744003 -0.276472,
+                          0.766331 0.0457247 -0.640817,
+                          0.910919 0.343837 -0.228039,
+                          0.680072 0.69777 -0.224987,
+                          0.785138 0.618892 -0.0230438,
+                          0.910919 0.343837 -0.228039,
+                          -0.612316 0.0169624 -0.790431,
+                          -0.61279 0.0175559 -0.790051,
+                          -0.617982 0.00514363 -0.786175,
+                          0.57661 0.662925 -0.477548,
+                          0.680072 0.69777 -0.224987,
+                          0.73764 0.371382 -0.563882,
+                          -0.637866 0.0307471 -0.769533,
+                          -0.651047 0.0196781 -0.758782,
+                          -0.61279 0.0175559 -0.790051,
+                          -0.637866 0.0307471 -0.769533,
+                          -0.61279 0.0175559 -0.790051,
+                          -0.612316 0.0169624 -0.790431,
+                          -0.614083 0.00235057 -0.789238,
+                          -0.617982 0.00514363 -0.786175,
+                          -0.641783 0.00685729 -0.766855,
+                          -0.612316 0.0169624 -0.790431,
+                          -0.617982 0.00514363 -0.786175,
+                          -0.614083 0.00235057 -0.789238,
+                          0.750534 -0.00903652 -0.66077,
+                          0.766331 0.0457247 -0.640817,
+                          0.958138 0.0744003 -0.276472,
+                          -0.644191 0.00069228 -0.764864,
+                          -0.641783 0.00685729 -0.766855,
+                          -0.660219 0.0159608 -0.750904,
+                          -0.614083 0.00235057 -0.789238,
+                          -0.641783 0.00685729 -0.766855,
+                          -0.644191 0.00069228 -0.764864,
+                          0.455343 0.460692 -0.761857,
+                          0.956235 0.0780059 -0.282009,
+                          0.971661 0.0938211 -0.216963,
+                          0.892873 0.0224695 -0.449747,
+                          0.750534 -0.00903652 -0.66077,
+                          0.958138 0.0744003 -0.276472,
+                          0.455343 0.460692 -0.761857,
+                          0.892889 0.0224105 -0.449718,
+                          0.956235 0.0780059 -0.282009,
+                          0.455343 0.460692 -0.761857,
+                          0.971661 0.0938211 -0.216963,
+                          0.973169 0.0952893 -0.209433,
+                          0.642347 0.661916 -0.386339,
+                          0.973169 0.0952893 -0.209433,
+                          0.99235 0.123172 -0.0083709,
+                          0.642347 0.661916 -0.386339,
+                          0.455343 0.460692 -0.761857,
+                          0.973169 0.0952893 -0.209433,
+                          0.693392 0.720475 0.0110529,
+                          0.992348 0.123199 -0.00815018,
+                          0.990802 0.120151 0.062253,
+                          0.693419 0.720452 0.0109233,
+                          0.642347 0.661916 -0.386339,
+                          0.99235 0.123172 -0.0083709,
+                          0.866656 0.43049 0.252161,
+                          0.990802 0.120151 0.062253,
+                          0.991552 0.108655 0.0708467,
+                          0.866656 0.43049 0.252161,
+                          0.693392 0.720475 0.0110529,
+                          0.990802 0.120151 0.062253,
+                          -0.356464 -0.934309 -1.57338e-15,
+                          -0.362794 -0.931869 -1.56678e-15,
+                          -0.057645 -0.998337 -1.79251e-15,
+                          -0.356464 -0.934309 -1.57338e-15,
+                          -0.691127 -0.722733 -1.07406e-15,
+                          -0.362794 -0.931869 -1.56678e-15,
+                          -0.0250147 -0.999687 -1.8062e-15,
+                          -0.356464 -0.934309 -1.57338e-15,
+                          -0.057645 -0.998337 -1.79251e-15,
+                          -1.71943e-16 -0.965427 0.260673,
+                          -1.71943e-16 -0.965427 0.260673,
+                          -1.71943e-16 -0.965427 0.260673,
+                          0.136411 -0.193074 0.971655,
+                          0.135908 -0.194103 0.971521,
+                          0.14008 -0.195296 0.970689,
+                          -1.71943e-16 -0.965427 0.260673,
+                          -1.71943e-16 -0.965427 0.260673,
+                          -1.71943e-16 -0.965427 0.260673,
+                          0.136275 -0.190295 0.972223,
+                          0.136411 -0.193074 0.971655,
+                          0.14008 -0.195296 0.970689,
+                          0.148908 -0.253121 0.955906,
+                          0.264781 -0.289391 0.919861,
+                          0.14008 -0.195296 0.970689,
+                          0.0747324 -0.180261 0.980776,
+                          0.148908 -0.253121 0.955906,
+                          0.14008 -0.195296 0.970689,
+                          -8.86479e-17 1 1.81538e-15,
+                          -8.86479e-17 1 1.81538e-15,
+                          -8.86479e-17 1 1.81538e-15,
+                          -1.71943e-16 -0.965427 0.260673,
+                          -1.71943e-16 -0.965427 0.260673,
+                          -1.71943e-16 -0.965427 0.260673,
+                          -1.71943e-16 -0.965427 0.260673,
+                          -1.71943e-16 -0.965427 0.260673,
+                          -1.71943e-16 -0.965427 0.260673,
+                          0.136411 -0.193074 0.971655,
+                          0.131722 -0.192928 0.972331,
+                          0.135908 -0.194103 0.971521,
+                          7.71746e-16 -0.965427 0.260673,
+                          -3.38477e-16 -0.965427 0.260673,
+                          0.750767 -0.62987 0.199029,
+                          -1.71943e-16 -0.965427 0.260673,
+                          -1.71943e-16 -0.965427 0.260673,
+                          -1.71943e-16 -0.965427 0.260673,
+                          -1.71943e-16 -0.965427 0.260673,
+                          -1.71943e-16 -0.965427 0.260673,
+                          -1.71943e-16 -0.965427 0.260673,
+                          0.757062 -0.622818 0.197368,
+                          0.750767 -0.62987 0.199029,
+                          0.989949 0.141421 2.12843e-15,
+                          0.757062 -0.622818 0.197368,
+                          7.71746e-16 -0.965427 0.260673,
+                          0.750767 -0.62987 0.199029,
+                          0.757062 -0.622818 0.197368,
+                          0.989949 0.141421 2.12843e-15,
+                          0.989949 0.141421 -1.12955e-15,
+                          0.983867 -0.160678 0.0786607,
+                          0.99267 -0.115596 0.0352803,
+                          0.996196 -0.0572404 0.0656986,
+                          0.658988 -0.583023 -0.475203,
+                          0.992669 -0.115607 0.0352738,
+                          0.983846 -0.160918 0.0784324,
+                          0.659017 -0.583002 -0.475189,
+                          0.910835 -0.302738 0.280587,
+                          0.992672 -0.115589 0.0352339,
+                          0.603358 -0.771686 -0.201148,
+                          0.983846 -0.160918 0.0784324,
+                          0.953595 -0.210571 0.215213,
+                          0.603358 -0.771686 -0.201148,
+                          0.658988 -0.583023 -0.475203,
+                          0.983846 -0.160918 0.0784324,
+                          0.603358 -0.771686 -0.201148,
+                          0.953595 -0.210571 0.215213,
+                          0.625748 -0.311681 0.715048,
+                          0.309233 -0.894909 0.321735,
+                          0.625748 -0.311681 0.715048,
+                          0.411337 -0.31527 0.855223,
+                          0.309233 -0.894909 0.321735,
+                          0.603358 -0.771686 -0.201148,
+                          0.625748 -0.311681 0.715048,
+                          0.163734 -0.886642 0.432501,
+                          0.411337 -0.31527 0.855223,
+                          0.264706 -0.289361 0.919892,
+                          0.163734 -0.886642 0.432501,
+                          0.309233 -0.894909 0.321735,
+                          0.411337 -0.31527 0.855223,
+                          0.163734 -0.886642 0.432501,
+                          0.264706 -0.289361 0.919892,
+                          0.148909 -0.253127 0.955904,
+                          -9.49378e-16 -0.201987 0.979388,
+                          -9.3959e-16 -0.233496 0.972358,
+                          0.148908 -0.253121 0.955906,
+                          0.163734 -0.886642 0.432501,
+                          0.148909 -0.253127 0.955904,
+                          -8.3756e-06 -0.233496 0.972358,
+                          -9.57454e-16 -0.17301 0.98492,
+                          -9.49378e-16 -0.201987 0.979388,
+                          0.148908 -0.253121 0.955906,
+                          0.0747324 -0.180261 0.980776,
+                          -9.57454e-16 -0.17301 0.98492,
+                          0.148908 -0.253121 0.955906,
+                          -0.0747697 -0.180268 0.980772,
+                          -9.39921e-16 -0.233496 0.972358,
+                          -9.4966e-16 -0.201987 0.979388,
+                          -0.148812 -0.253095 0.955928,
+                          -9.39921e-16 -0.233496 0.972358,
+                          -0.0747697 -0.180268 0.980772,
+                          -0.0178143 -0.854044 0.519896,
+                          8.16986e-06 -0.233496 0.972358,
+                          -0.148813 -0.253102 0.955926,
+                          0.163734 -0.886642 0.432501,
+                          -8.3756e-06 -0.233496 0.972358,
+                          0.0178142 -0.854044 0.519896,
+                          -0.0747697 -0.180268 0.980772,
+                          -9.4966e-16 -0.201987 0.979388,
+                          -9.57694e-16 -0.17301 0.98492,
+                          -8.86479e-17 1 1.81538e-15,
+                          -8.86479e-17 1 1.81538e-15,
+                          -8.86479e-17 1 1.81538e-15,
+                          -8.86479e-17 1 1.81538e-15,
+                          -8.86479e-17 1 1.81538e-15,
+                          -8.86479e-17 1 1.81538e-15,
+                          -0.139499 0.643651 0.752498,
+                          -8.45865e-16 0.596404 0.802684,
+                          -8.28006e-16 0.623001 0.782221,
+                          -4.92309e-16 0.908442 0.418011,
+                          -8.27705e-16 0.623001 0.782221,
+                          0.139499 0.643651 0.752498,
+                          -0.0867596 0.918793 0.385088,
+                          -8.28006e-16 0.623001 0.782221,
+                          -4.93496e-16 0.908442 0.418011,
+                          -0.139499 0.643651 0.752498,
+                          -8.28006e-16 0.623001 0.782221,
+                          -0.0867596 0.918793 0.385088,
+                          0.0867596 0.918793 0.385088,
+                          0.139499 0.643651 0.752498,
+                          0.42828 0.679601 0.595583,
+                          -4.8369e-16 0.912504 0.409068,
+                          -4.92309e-16 0.908442 0.418011,
+                          0.139499 0.643651 0.752498,
+                          0.0867596 0.918793 0.385088,
+                          -4.8369e-16 0.912504 0.409068,
+                          0.139499 0.643651 0.752498,
+                          0.209729 0.927669 0.30894,
+                          0.42828 0.679601 0.595583,
+                          0.68193 0.644307 0.346179,
+                          0.209729 0.927669 0.30894,
+                          0.0867596 0.918793 0.385088,
+                          0.42828 0.679601 0.595583,
+                          0.319812 0.925026 0.205055,
+                          0.68193 0.644307 0.346179,
+                          0.796718 0.589085 0.134976,
+                          0.319812 0.925026 0.205055,
+                          0.209729 0.927669 0.30894,
+                          0.68193 0.644307 0.346179,
+                          0.401586 0.912415 0.0789194,
+                          0.796718 0.589085 0.134976,
+                          0.815091 0.576393 0.0582807,
+                          0.401586 0.912415 0.0789194,
+                          0.319812 0.925026 0.205055,
+                          0.796718 0.589085 0.134976,
+                          0.430803 0.902446 0.000174788,
+                          0.815091 0.576393 0.0582807,
+                          0.785138 0.618892 -0.0230438,
+                          0.430803 0.902446 0.000174788,
+                          0.401586 0.912415 0.0789194,
+                          0.815091 0.576393 0.0582807,
+                          0.407688 0.909914 -0.0764639,
+                          0.785138 0.618892 -0.0230438,
+                          0.680072 0.69777 -0.224987,
+                          0.407688 0.909914 -0.0764639,
+                          0.430803 0.902446 0.000174788,
+                          0.785138 0.618892 -0.0230438,
+                          0.57661 0.662925 -0.477548,
+                          0.506509 0.739626 -0.443173,
+                          0.680072 0.69777 -0.224987,
+                          0.347016 0.920656 -0.178809,
+                          0.680072 0.69777 -0.224987,
+                          0.506509 0.739626 -0.443173,
+                          0.347016 0.920656 -0.178809,
+                          0.407688 0.909914 -0.0764639,
+                          0.680072 0.69777 -0.224987,
+                          -0.66939 0.0161451 -0.742736,
+                          -0.667388 0.0108757 -0.744631,
+                          -0.651047 0.0196781 -0.758782,
+                          0.402591 0.831909 -0.3819,
+                          0.347016 0.920656 -0.178809,
+                          0.506509 0.739626 -0.443173,
+                          -0.689668 -0.00119937 -0.724124,
+                          -0.686211 -0.00184441 -0.7274,
+                          -0.667388 0.0108757 -0.744631,
+                          -0.689668 -0.00119937 -0.724124,
+                          -0.667388 0.0108757 -0.744631,
+                          -0.66939 0.0161451 -0.742736,
+                          -0.6658 0.0187576 -0.745895,
+                          -0.66939 0.0161451 -0.742736,
+                          -0.651047 0.0196781 -0.758782,
+                          -0.6658 0.0187576 -0.745895,
+                          -0.651047 0.0196781 -0.758782,
+                          -0.637866 0.0307471 -0.769533,
+                          -0.0867596 0.918793 0.385088,
+                          -4.93496e-16 0.908442 0.418011,
+                          -4.85021e-16 0.912504 0.409068,
+                          -3.41883e-17 0.999947 -0.0102817,
+                          -4.8369e-16 0.912504 0.409068,
+                          0.0867596 0.918793 0.385088,
+                          0.0103227 0.999929 -0.00595768,
+                          -4.85021e-16 0.912504 0.409068,
+                          -7.84856e-17 0.999947 -0.0102817,
+                          -0.0867596 0.918793 0.385088,
+                          -4.85021e-16 0.912504 0.409068,
+                          0.0103227 0.999929 -0.00595768,
+                          -0.015298 0.999866 0.00588474,
+                          0.0867596 0.918793 0.385088,
+                          0.209729 0.927669 0.30894,
+                          -0.0103227 0.999929 -0.00595768,
+                          -3.41883e-17 0.999947 -0.0102817,
+                          0.0867596 0.918793 0.385088,
+                          -0.015298 0.999866 0.00588474,
+                          -0.0103227 0.999929 -0.00595768,
+                          0.0867596 0.918793 0.385088,
+                          -0.015298 0.999866 0.00588474,
+                          0.209729 0.927669 0.30894,
+                          0.319812 0.925026 0.205055,
+                          -0.00914791 0.999814 0.0170045,
+                          0.319812 0.925026 0.205055,
+                          0.401586 0.912415 0.0789194,
+                          -0.00914791 0.999814 0.0170045,
+                          -0.015298 0.999866 0.00588474,
+                          0.319812 0.925026 0.205055,
+                          -0.00323441 0.999796 0.0199279,
+                          0.401586 0.912415 0.0789194,
+                          0.430803 0.902446 0.000174788,
+                          -0.00323441 0.999796 0.0199279,
+                          -0.00914791 0.999814 0.0170045,
+                          0.401586 0.912415 0.0789194,
+                          0.00834895 0.999752 0.020629,
+                          0.430803 0.902446 0.000174788,
+                          0.407688 0.909914 -0.0764639,
+                          0.00834895 0.999752 0.020629,
+                          -0.00323441 0.999796 0.0199279,
+                          0.430803 0.902446 0.000174788,
+                          0.0176641 0.999678 0.0181929,
+                          0.407688 0.909914 -0.0764639,
+                          0.347016 0.920656 -0.178809,
+                          0.0176641 0.999678 0.0181929,
+                          0.00834895 0.999752 0.020629,
+                          0.407688 0.909914 -0.0764639,
+                          0.296584 0.908125 -0.295545,
+                          0.273619 0.922456 -0.272409,
+                          0.347016 0.920656 -0.178809,
+                          0.0200022 0.999696 0.014442,
+                          0.347016 0.920656 -0.178809,
+                          0.273619 0.922456 -0.272409,
+                          0.402591 0.831909 -0.3819,
+                          0.296584 0.908125 -0.295545,
+                          0.347016 0.920656 -0.178809,
+                          0.0200022 0.999696 0.014442,
+                          0.0176641 0.999678 0.0181929,
+                          0.347016 0.920656 -0.178809,
+                          -0.700413 -0.0031382 -0.713731,
+                          -0.701091 -0.0025957 -0.713067,
+                          -0.698888 -0.00451073 -0.715217,
+                          0.152808 0.980405 -0.12432,
+                          0.0200022 0.999696 0.014442,
+                          0.273619 0.922456 -0.272409,
+                          -0.701709 -0.00124151 -0.712462,
+                          -0.713834 0.0224996 -0.699953,
+                          -0.701091 -0.0025957 -0.713067,
+                          -0.701709 -0.00124151 -0.712462,
+                          -0.701091 -0.0025957 -0.713067,
+                          -0.700413 -0.0031382 -0.713731,
+                          -0.689668 -0.00119937 -0.724124,
+                          -0.698888 -0.00451073 -0.715217,
+                          -0.686211 -0.00184441 -0.7274,
+                          -0.689668 -0.00119937 -0.724124,
+                          -0.700413 -0.0031382 -0.713731,
+                          -0.698888 -0.00451073 -0.715217,
+                          9.88788e-16 -0.0102817 -0.999947,
+                          9.88788e-16 -0.0102817 -0.999947,
+                          -0.370121 -0.00939158 -0.928936,
+                          0.352895 -0.0095462 -0.935614,
+                          0.370121 -0.00939158 -0.928936,
+                          9.88702e-16 -0.0102817 -0.999947,
+                          0.352895 -0.0095462 -0.935614,
+                          9.88702e-16 -0.0102817 -0.999947,
+                          9.88699e-16 -0.0102817 -0.999947,
+                          -0.709431 -0.00780339 -0.704732,
+                          -0.370121 -0.00939158 -0.928936,
+                          -0.733258 -0.00721441 -0.679912,
+                          -0.352895 -0.0095462 -0.935614,
+                          9.88788e-16 -0.0102817 -0.999947,
+                          -0.370121 -0.00939158 -0.928936,
+                          -0.352895 -0.0095462 -0.935614,
+                          -0.370121 -0.00939158 -0.928936,
+                          -0.709431 -0.00780339 -0.704732,
+                          -0.929658 -0.00372945 -0.368406,
+                          -0.733258 -0.00721441 -0.679912,
+                          -0.942213 -0.00292335 -0.335001,
+                          -0.709431 -0.00780339 -0.704732,
+                          -0.733258 -0.00721441 -0.679912,
+                          -0.929658 -0.00372945 -0.368406,
+                          -0.981341 -0.002028 -0.192263,
+                          -0.942213 -0.00292335 -0.335001,
+                          -0.988439 -0.000176103 -0.151618,
+                          -0.929658 -0.00372945 -0.368406,
+                          -0.942213 -0.00292335 -0.335001,
+                          -0.981341 -0.002028 -0.192263,
+                          -0.999763 0.00410321 -0.0213863,
+                          -0.988439 -0.000176103 -0.151618,
+                          -0.999958 0.00826249 0.00388075,
+                          -0.981341 -0.002028 -0.192263,
+                          -0.988439 -0.000176103 -0.151618,
+                          -0.999763 0.00410321 -0.0213863,
+                          -0.991482 0.0130197 0.129593,
+                          -0.999958 0.00826249 0.00388075,
+                          -0.988208 0.0146816 0.152415,
+                          -0.999763 0.00410321 -0.0213863,
+                          -0.999958 0.00826249 0.00388075,
+                          -0.991482 0.0130197 0.129593,
+                          -0.957645 0.0149494 0.287563,
+                          -0.988208 0.0146816 0.152415,
+                          -0.948781 0.0144392 0.315604,
+                          -0.991482 0.0130197 0.129593,
+                          -0.988208 0.0146816 0.152415,
+                          -0.957645 0.0149494 0.287563,
+                          0.152808 0.980405 -0.12432,
+                          0.015383 0.999806 0.012333,
+                          0.0200022 0.999696 0.014442,
+                          -0.957645 0.0149494 0.287563,
+                          -0.948781 0.0144392 0.315604,
+                          -0.865637 0.00714335 0.500622,
+                          -0.752091 0.0196978 -0.658765,
+                          -0.73411 0.0196676 -0.678746,
+                          -0.713834 0.0224996 -0.699953,
+                          -0.957645 0.0149494 0.287563,
+                          -0.865637 0.00714335 0.500622,
+                          -0.876464 0.00754696 0.481408,
+                          -0.713503 0.0251546 -0.7002,
+                          -0.713834 0.0224996 -0.699953,
+                          -0.701709 -0.00124151 -0.712462,
+                          -0.752091 0.0196978 -0.658765,
+                          -0.713834 0.0224996 -0.699953,
+                          -0.713503 0.0251546 -0.7002,
+                          0.892873 0.0224695 -0.449747,
+                          0.738212 -0.0636969 -0.671555,
+                          0.750534 -0.00903652 -0.66077,
+                          -0.661107 0.0118524 -0.750198,
+                          -0.660219 0.0159608 -0.750904,
+                          -0.673114 -0.00690018 -0.739506,
+                          -0.661107 0.0118524 -0.750198,
+                          -0.644191 0.00069228 -0.764864,
+                          -0.660219 0.0159608 -0.750904,
+                          0.892873 0.0224695 -0.449747,
+                          0.760331 -0.0608806 -0.646676,
+                          0.738212 -0.0636969 -0.671555,
+                          0.000147322 -0.995502 0.0947359,
+                          0.000603417 -0.995455 0.0952329,
+                          -0.00130028 -0.995724 0.0923736,
+                          -0.661107 0.0118524 -0.750198,
+                          -0.673114 -0.00690018 -0.739506,
+                          -0.673247 -0.0101041 -0.739348,
+                          0.835578 -0.0117927 -0.549245,
+                          0.781399 -0.0579529 -0.621335,
+                          0.760331 -0.0608806 -0.646676,
+                          -0.00236468 -0.995855 0.0909223,
+                          -0.00130028 -0.995724 0.0923736,
+                          -0.0027881 -0.995976 0.0895816,
+                          0.892873 0.0224695 -0.449747,
+                          0.835578 -0.0117927 -0.549245,
+                          0.760331 -0.0608806 -0.646676,
+                          0.000147322 -0.995502 0.0947359,
+                          -0.00130028 -0.995724 0.0923736,
+                          -0.00236468 -0.995855 0.0909223,
+                          0.455281 0.460688 -0.761896,
+                          0.781437 -0.0578411 -0.621298,
+                          0.835535 -0.0119643 -0.549307,
+                          -0.00236468 -0.995855 0.0909223,
+                          -0.0027881 -0.995976 0.0895816,
+                          -0.00441922 -0.996209 0.0868808,
+                          -0.00742854 -0.998057 0.0618633,
+                          -0.00441922 -0.996209 0.0868808,
+                          -0.0027881 -0.995976 0.0895816,
+                          0.455281 0.460688 -0.761896,
+                          0.352459 0.246612 -0.902749,
+                          0.781437 -0.0578411 -0.621298,
+                          0.455281 0.460688 -0.761896,
+                          0.835535 -0.0119643 -0.549307,
+                          0.892864 0.0224274 -0.449767,
+                          -0.0756556 -0.101903 0.991913,
+                          -0.0918966 0.0198694 0.99557,
+                          -0.0913467 -0.0141368 0.995719,
+                          -1 -2.11109e-16 3.44339e-16,
+                          -1 -2.11109e-16 3.44339e-16,
+                          -0.939359 -0.342936 -2.99102e-16,
+                          -0.115872 -0.0560996 0.991679,
+                          -0.0756556 -0.101903 0.991913,
+                          -0.0913467 -0.0141368 0.995719,
+                          -0.921271 0.388922 1.02327e-15,
+                          -0.916576 0.39986 1.04151e-15,
+                          -1 -2.11109e-16 3.44339e-16,
+                          -0.921271 0.388922 1.02327e-15,
+                          -1 -2.11109e-16 3.44339e-16,
+                          -1 -2.11109e-16 3.44339e-16,
+                          -0.0298251 0.0124044 0.999478,
+                          -0.11249 0.0499885 0.992395,
+                          -0.0918966 0.0198694 0.99557,
+                          -0.785926 -0.61832 -8.51863e-16,
+                          -0.939359 -0.342936 -2.99102e-16,
+                          -0.760252 -0.649629 -9.17541e-16,
+                          -0.0691022 -0.0909454 0.993456,
+                          -0.0298251 0.0124044 0.999478,
+                          -0.0918966 0.0198694 0.99557,
+                          -0.0756556 -0.101903 0.991913,
+                          -0.0691022 -0.0909454 0.993456,
+                          -0.0918966 0.0198694 0.99557,
+                          -0.946239 -0.323468 -2.61392e-16,
+                          -0.939359 -0.342936 -2.99102e-16,
+                          -0.785926 -0.61832 -8.51863e-16,
+                          -1 -2.11109e-16 3.44339e-16,
+                          -0.939359 -0.342936 -2.99102e-16,
+                          -0.946239 -0.323468 -2.61392e-16,
+                          -0.0237569 0.0366483 0.999046,
+                          -0.13835 0.0577876 0.988696,
+                          -0.11249 0.0499885 0.992395,
+                          -0.758344 -0.651854 -9.22238e-16,
+                          -0.760252 -0.649629 -9.17541e-16,
+                          -0.628344 -0.777936 -1.19589e-15,
+                          -0.0298251 0.0124044 0.999478,
+                          -0.0237569 0.0366483 0.999046,
+                          -0.11249 0.0499885 0.992395,
+                          -0.785926 -0.61832 -8.51863e-16,
+                          -0.760252 -0.649629 -9.17541e-16,
+                          -0.758344 -0.651854 -9.22238e-16,
+                          -0.0175612 0.0659909 0.997666,
+                          -0.00831922 0.0664736 0.997754,
+                          -0.13835 0.0577876 0.988696,
+                          -0.0237569 0.0366483 0.999046,
+                          -0.0175612 0.0659909 0.997666,
+                          -0.13835 0.0577876 0.988696,
+                          -0.160063 0.313194 0.936103,
+                          -0.213515 0.0793783 0.97371,
+                          -0.13835 0.0577876 0.988696,
+                          -0.542668 -0.839947 -1.33796e-15,
+                          -0.628344 -0.777936 -1.19589e-15,
+                          -0.237185 -0.971465 -1.68191e-15,
+                          -0.542668 -0.839947 -1.33796e-15,
+                          -0.758344 -0.651854 -9.22238e-16,
+                          -0.628344 -0.777936 -1.19589e-15,
+                          -8.86479e-17 1 1.81538e-15,
+                          -8.86479e-17 1 1.81538e-15,
+                          -8.86479e-17 1 1.81538e-15,
+                          -0.169531 0.0899004 0.981416,
+                          -0.330596 0.110065 0.937332,
+                          -0.742549 0.175406 0.646416,
+                          -8.86479e-17 1 1.81538e-15,
+                          -8.86479e-17 1 1.81538e-15,
+                          -8.86479e-17 1 1.81538e-15,
+                          1.51936e-06 0.0666471 0.997777,
+                          -0.742549 0.175406 0.646416,
+                          -0.989954 0.141386 -0.000254189,
+                          -0.169531 0.0899004 0.981416,
+                          -0.742549 0.175406 0.646416,
+                          1.51936e-06 0.0666471 0.997777,
+                          -0.989949 0.141421 5.97612e-16,
+                          -0.989949 0.141421 5.97612e-16,
+                          -0.989949 0.141421 5.97612e-16,
+                          -7.56276e-09 0.245809 0.969318,
+                          1.51936e-06 0.0666471 0.997777,
+                          -0.989954 0.141386 -0.000254189,
+                          -0.989949 0.141426 1.5699e-05,
+                          -7.56276e-09 0.245809 0.969318,
+                          -0.989954 0.141386 -0.000254189,
+                          -0.989949 0.141421 5.97612e-16,
+                          -0.989949 0.141421 5.97612e-16,
+                          -0.989949 0.141421 5.97612e-16,
+                          -0.239228 -0.128347 0.962443,
+                          -0.279837 -0.143367 0.949282,
+                          -0.0756556 -0.101903 0.991913,
+                          -0.136275 -0.190295 0.972223,
+                          -0.0756556 -0.101903 0.991913,
+                          -0.279837 -0.143367 0.949282,
+                          -0.167142 -0.0959123 0.981256,
+                          -0.239228 -0.128347 0.962443,
+                          -0.0756556 -0.101903 0.991913,
+                          -0.115872 -0.0560996 0.991679,
+                          -0.167142 -0.0959123 0.981256,
+                          -0.0756556 -0.101903 0.991913,
+                          -0.989949 0.141421 5.97612e-16,
+                          -0.989949 0.141421 5.97612e-16,
+                          -0.989949 0.141421 5.97612e-16,
+                          -0.989949 0.141421 5.97612e-16,
+                          -0.989949 0.141421 5.97612e-16,
+                          -0.989949 0.141421 5.97612e-16,
+                          -0.334396 -0.147939 0.930749,
+                          -0.624526 -0.145715 0.76729,
+                          -0.279837 -0.143367 0.949282,
+                          -0.412583 -0.315413 0.85457,
+                          -0.279837 -0.143367 0.949282,
+                          -0.624526 -0.145715 0.76729,
+                          -0.239228 -0.128347 0.962443,
+                          -0.334396 -0.147939 0.930749,
+                          -0.279837 -0.143367 0.949282,
+                          -0.14008 -0.195296 0.970689,
+                          -0.136275 -0.190295 0.972223,
+                          -0.279837 -0.143367 0.949282,
+                          -0.264976 -0.28945 0.919786,
+                          -0.14008 -0.195296 0.970689,
+                          -0.279837 -0.143367 0.949282,
+                          -0.412583 -0.315413 0.85457,
+                          -0.264976 -0.28945 0.919786,
+                          -0.279837 -0.143367 0.949282,
+                          -0.91034 0.0869548 0.404622,
+                          -0.95721 -0.0696041 0.280898,
+                          -0.624526 -0.145715 0.76729,
+                          -0.626979 -0.311535 0.714033,
+                          -0.624526 -0.145715 0.76729,
+                          -0.95721 -0.0696041 0.280898,
+                          -0.762036 -0.0263223 0.647,
+                          -0.91034 0.0869548 0.404622,
+                          -0.624526 -0.145715 0.76729,
+                          -0.71817 -0.0691792 0.692421,
+                          -0.762036 -0.0263223 0.647,
+                          -0.624526 -0.145715 0.76729,
+                          -0.59448 -0.116847 0.795575,
+                          -0.71817 -0.0691792 0.692421,
+                          -0.624526 -0.145715 0.76729,
+                          -0.446433 -0.1465 0.882743,
+                          -0.59448 -0.116847 0.795575,
+                          -0.624526 -0.145715 0.76729,
+                          -0.334396 -0.147939 0.930749,
+                          -0.446433 -0.1465 0.882743,
+                          -0.624526 -0.145715 0.76729,
+                          -0.626979 -0.311535 0.714033,
+                          -0.412583 -0.315413 0.85457,
+                          -0.624526 -0.145715 0.76729,
+                          -0.996898 -0.0050512 0.0785375,
+                          -0.99695 -0.0261594 0.0735236,
+                          -0.95721 -0.0696041 0.280898,
+                          -0.953753 -0.210813 0.214274,
+                          -0.95721 -0.0696041 0.280898,
+                          -0.99695 -0.0261594 0.0735236,
+                          -0.98778 0.0905609 0.126842,
+                          -0.996898 -0.0050512 0.0785375,
+                          -0.95721 -0.0696041 0.280898,
+                          -0.91034 0.0869548 0.404622,
+                          -0.98778 0.0905609 0.126842,
+                          -0.95721 -0.0696041 0.280898,
+                          -0.953753 -0.210813 0.214274,
+                          -0.626979 -0.311535 0.714033,
+                          -0.95721 -0.0696041 0.280898,
+                          -0.983893 -0.160592 0.07851,
+                          -0.953753 -0.210813 0.214274,
+                          -0.99695 -0.0261594 0.0735236,
+                          -0.996196 -0.0572404 0.0656986,
+                          -0.983893 -0.160592 0.07851,
+                          -0.99695 -0.0261594 0.0735236,
+                          -0.98778 0.0905609 0.126842,
+                          -0.995575 0.0586257 0.0734385,
+                          -0.996898 -0.0050512 0.0785375,
+                          -0.992512 -0.00479914 0.12205,
+                          -0.996899 -0.00505742 0.078535,
+                          -0.995574 0.0586423 0.0734391,
+                          -0.98778 0.0905609 0.126842,
+                          -0.993602 0.0916832 0.0659415,
+                          -0.995575 0.0586257 0.0734385,
+                          -0.961352 0.153926 0.228273,
+                          -0.995574 0.0586423 0.0734391,
+                          -0.993904 0.0903405 0.0631921,
+                          -0.961352 0.153926 0.228273,
+                          -0.992512 -0.00479914 0.12205,
+                          -0.995574 0.0586423 0.0734391,
+                          -0.952511 0.271619 0.13764,
+                          -0.993602 0.0916832 0.0659415,
+                          -0.98778 0.0905609 0.126842,
+                          -0.960734 0.263121 0.088073,
+                          -0.991592 0.108527 0.0704728,
+                          -0.993602 0.0916832 0.0659415,
+                          -0.961352 0.153926 0.228273,
+                          -0.993904 0.0903405 0.0631921,
+                          -0.991552 0.108655 0.0708467,
+                          -0.952511 0.271619 0.13764,
+                          -0.960734 0.263121 0.088073,
+                          -0.993602 0.0916832 0.0659415,
+                          -0.878802 0.316614 0.357019,
+                          -0.98778 0.0905609 0.126842,
+                          -0.91034 0.0869548 0.404622,
+                          -0.878802 0.316614 0.357019,
+                          -0.952511 0.271619 0.13764,
+                          -0.98778 0.0905609 0.126842,
+                          -0.669396 0.0303265 0.742287,
+                          -0.530491 0.0483385 0.846311,
+                          -0.91034 0.0869548 0.404622,
+                          -0.559773 0.341124 0.755175,
+                          -0.91034 0.0869548 0.404622,
+                          -0.530491 0.0483385 0.846311,
+                          -0.744628 0.00411571 0.667467,
+                          -0.669396 0.0303265 0.742287,
+                          -0.91034 0.0869548 0.404622,
+                          -0.762036 -0.0263223 0.647,
+                          -0.744628 0.00411571 0.667467,
+                          -0.91034 0.0869548 0.404622,
+                          -0.559773 0.341124 0.755175,
+                          -0.878802 0.316614 0.357019,
+                          -0.91034 0.0869548 0.404622,
+                          0.691127 -0.722733 -1.55002e-15,
+                          0.585815 -0.810444 -1.67299e-15,
+                          0.820191 -0.57209 -1.32099e-15,
+                          -0.559773 0.341124 0.755175,
+                          -0.530491 0.0483385 0.846311,
+                          -0.430505 0.0673644 0.900071,
+                          0.356464 -0.934309 -1.81887e-15,
+                          0.362794 -0.931869 -1.81662e-15,
+                          0.585815 -0.810444 -1.67299e-15,
+                          0.356464 -0.934309 -1.81887e-15,
+                          0.585815 -0.810444 -1.67299e-15,
+                          0.691127 -0.722733 -1.55002e-15,
+                          0.862159 -0.506638 -1.21662e-15,
+                          0.820191 -0.57209 -1.32099e-15,
+                          0.956458 -0.291871 -8.59204e-16,
+                          0.691127 -0.722733 -1.55002e-15,
+                          0.820191 -0.57209 -1.32099e-15,
+                          0.862159 -0.506638 -1.21662e-15,
+                          0.862159 -0.506638 -1.21662e-15,
+                          0.956458 -0.291871 -8.59204e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 3.33569e-16 -3.44339e-16,
+                          1 3.33569e-16 -3.44339e-16,
+                          0.938614 0.344969 3.0305e-16,
+                          0.862159 -0.506638 -1.21662e-15,
+                          1 8.86479e-17 -3.44339e-16,
+                          1 8.86479e-17 -3.44339e-16,
+                          0.907919 0.419145 4.48276e-16,
+                          0.938614 0.344969 3.0305e-16,
+                          0.725652 0.688062 9.99225e-16,
+                          0.907919 0.419145 4.48276e-16,
+                          1 3.33569e-16 -3.44339e-16,
+                          0.938614 0.344969 3.0305e-16,
+                          0.615255 0.788328 1.21926e-15,
+                          0.725652 0.688062 9.99225e-16,
+                          0.373464 0.927645 1.55543e-15,
+                          0.907919 0.419145 4.48276e-16,
+                          0.725652 0.688062 9.99225e-16,
+                          0.615255 0.788328 1.21926e-15,
+                          0.330721 0.943729 1.59935e-15,
+                          0.373464 0.927645 1.55543e-15,
+                          0.00427686 0.999991 1.81389e-15,
+                          0.615255 0.788328 1.21926e-15,
+                          0.373464 0.927645 1.55543e-15,
+                          0.330721 0.943729 1.59935e-15,
+                          -0.0189844 0.99982 1.82159e-15,
+                          0.00427686 0.999991 1.81389e-15,
+                          -0.36724 0.930126 1.81499e-15,
+                          0.330721 0.943729 1.59935e-15,
+                          0.00427686 0.999991 1.81389e-15,
+                          -0.0189844 0.99982 1.82159e-15,
+                          -0.385974 0.92251 1.80761e-15,
+                          -0.36724 0.930126 1.81499e-15,
+                          -0.68804 0.725673 1.55429e-15,
+                          -0.0189844 0.99982 1.82159e-15,
+                          -0.36724 0.930126 1.81499e-15,
+                          -0.385974 0.92251 1.80761e-15,
+                          -0.701103 0.71306 1.53589e-15,
+                          -0.68804 0.725673 1.55429e-15,
+                          -0.916576 0.39986 1.04151e-15,
+                          -0.385974 0.92251 1.80761e-15,
+                          -0.68804 0.725673 1.55429e-15,
+                          -0.701103 0.71306 1.53589e-15,
+                          -0.701103 0.71306 1.53589e-15,
+                          -0.916576 0.39986 1.04151e-15,
+                          -0.921271 0.388922 1.02327e-15,
+                          -0.559773 0.341124 0.755175,
+                          -0.304531 0.0785021 0.949262,
+                          -0.213515 0.0793783 0.97371,
+                          0.0250147 -0.999687 -1.82343e-15,
+                          -0.237185 -0.971465 -1.68191e-15,
+                          0.057645 -0.998337 -1.83221e-15,
+                          -0.160063 0.313194 0.936103,
+                          -0.559773 0.341124 0.755175,
+                          -0.213515 0.0793783 0.97371,
+                          -0.289189 -0.957272 -1.63824e-15,
+                          -0.237185 -0.971465 -1.68191e-15,
+                          0.0250147 -0.999687 -1.82343e-15,
+                          -0.542668 -0.839947 -1.33796e-15,
+                          -0.237185 -0.971465 -1.68191e-15,
+                          -0.289189 -0.957272 -1.63824e-15,
+                          -0.559773 0.341124 0.755175,
+                          -0.430505 0.0673644 0.900071,
+                          -0.304531 0.0785021 0.949262,
+                          0.356464 -0.934309 -1.81887e-15,
+                          0.057645 -0.998337 -1.83221e-15,
+                          0.362794 -0.931869 -1.81662e-15,
+                          0.0250147 -0.999687 -1.82343e-15,
+                          0.057645 -0.998337 -1.83221e-15,
+                          0.356464 -0.934309 -1.81887e-15,
+                          -0.958937 0.282647 0.0234522,
+                          -0.990817 0.12005 0.0622115,
+                          -0.991592 0.108527 0.0704728,
+                          -0.866656 0.43049 0.252161,
+                          -0.991552 0.108655 0.0708467,
+                          -0.990802 0.120151 0.062253,
+                          -0.960734 0.263121 0.088073,
+                          -0.958937 0.282647 0.0234522,
+                          -0.991592 0.108527 0.0704728,
+                          -0.866656 0.43049 0.252161,
+                          -0.961352 0.153926 0.228273,
+                          -0.991552 0.108655 0.0708467,
+                          -0.958937 0.282647 0.0234522,
+                          -0.99235 0.123176 -0.0083192,
+                          -0.990817 0.12005 0.0622115,
+                          -0.866656 0.43049 0.252161,
+                          -0.990802 0.120151 0.062253,
+                          -0.992348 0.123199 -0.00815018,
+                          -0.910919 0.343837 -0.228039,
+                          -0.973255 0.0948206 -0.209245,
+                          -0.99235 0.123176 -0.0083192,
+                          -0.642347 0.661916 -0.386339,
+                          -0.99235 0.123172 -0.0083709,
+                          -0.973169 0.0952893 -0.209433,
+                          -0.958937 0.282647 0.0234522,
+                          -0.910919 0.343837 -0.228039,
+                          -0.99235 0.123176 -0.0083192,
+                          -0.693419 0.720452 0.0109233,
+                          -0.99235 0.123172 -0.0083709,
+                          -0.642347 0.661916 -0.386339,
+                          -0.866656 0.43049 0.252161,
+                          -0.992348 0.123199 -0.00815018,
+                          -0.693392 0.720475 0.0110529,
+                          -0.910919 0.343837 -0.228039,
+                          -0.971648 0.0937846 -0.217036,
+                          -0.973255 0.0948206 -0.209245,
+                          -0.455343 0.460692 -0.761857,
+                          -0.973169 0.0952893 -0.209433,
+                          -0.971661 0.0938211 -0.216963,
+                          -0.642347 0.661916 -0.386339,
+                          -0.973169 0.0952893 -0.209433,
+                          -0.455343 0.460692 -0.761857,
+                          -0.910919 0.343837 -0.228039,
+                          -0.958138 0.0744003 -0.276472,
+                          -0.971648 0.0937846 -0.217036,
+                          -0.455343 0.460692 -0.761857,
+                          -0.971661 0.0938211 -0.216963,
+                          -0.956235 0.0780059 -0.282009,
+                          -0.774218 0.177839 -0.607421,
+                          -0.766331 0.0457247 -0.640817,
+                          -0.958138 0.0744003 -0.276472,
+                          -0.892873 0.0224695 -0.449747,
+                          -0.958138 0.0744003 -0.276472,
+                          -0.766331 0.0457247 -0.640817,
+                          -0.73764 0.371382 -0.563882,
+                          -0.774218 0.177839 -0.607421,
+                          -0.958138 0.0744003 -0.276472,
+                          -0.910919 0.343837 -0.228039,
+                          -0.73764 0.371382 -0.563882,
+                          -0.958138 0.0744003 -0.276472,
+                          -0.455343 0.460692 -0.761857,
+                          -0.956235 0.0780059 -0.282009,
+                          -0.892889 0.0224105 -0.449718,
+                          0.644191 0.00069228 -0.764864,
+                          0.641783 0.00685729 -0.766855,
+                          0.617982 0.00514363 -0.786175,
+                          -0.835578 -0.0117927 -0.549245,
+                          -0.892873 0.0224695 -0.449747,
+                          -0.766331 0.0457247 -0.640817,
+                          -0.781399 -0.0579529 -0.621335,
+                          -0.835578 -0.0117927 -0.549245,
+                          -0.766331 0.0457247 -0.640817,
+                          -0.760331 -0.0608806 -0.646676,
+                          -0.781399 -0.0579529 -0.621335,
+                          -0.766331 0.0457247 -0.640817,
+                          -0.750534 -0.00903652 -0.66077,
+                          -0.760331 -0.0608806 -0.646676,
+                          -0.766331 0.0457247 -0.640817,
+                          0.644191 0.00069228 -0.764864,
+                          0.660219 0.0159608 -0.750904,
+                          0.641783 0.00685729 -0.766855,
+                          0.614083 0.00235057 -0.789238,
+                          0.617982 0.00514363 -0.786175,
+                          0.61279 0.0175559 -0.790051,
+                          0.644191 0.00069228 -0.764864,
+                          0.617982 0.00514363 -0.786175,
+                          0.614083 0.00235057 -0.789238,
+                          -0.57661 0.662925 -0.477548,
+                          -0.73764 0.371382 -0.563882,
+                          -0.910919 0.343837 -0.228039,
+                          0.637866 0.0307471 -0.769533,
+                          0.61279 0.0175559 -0.790051,
+                          0.651047 0.0196781 -0.758782,
+                          0.614083 0.00235057 -0.789238,
+                          0.61279 0.0175559 -0.790051,
+                          0.612316 0.0169624 -0.790431,
+                          0.637866 0.0307471 -0.769533,
+                          0.612316 0.0169624 -0.790431,
+                          0.61279 0.0175559 -0.790051,
+                          -0.680072 0.69777 -0.224987,
+                          -0.910919 0.343837 -0.228039,
+                          -0.958937 0.282647 0.0234522,
+                          -0.506509 0.739626 -0.443173,
+                          -0.910919 0.343837 -0.228039,
+                          -0.680072 0.69777 -0.224987,
+                          -0.57661 0.662925 -0.477548,
+                          -0.910919 0.343837 -0.228039,
+                          -0.506509 0.739626 -0.443173,
+                          -0.785138 0.618892 -0.0230438,
+                          -0.958937 0.282647 0.0234522,
+                          -0.960734 0.263121 0.088073,
+                          -0.680072 0.69777 -0.224987,
+                          -0.958937 0.282647 0.0234522,
+                          -0.785138 0.618892 -0.0230438,
+                          -0.815091 0.576393 0.0582807,
+                          -0.960734 0.263121 0.088073,
+                          -0.952511 0.271619 0.13764,
+                          -0.785138 0.618892 -0.0230438,
+                          -0.960734 0.263121 0.088073,
+                          -0.815091 0.576393 0.0582807,
+                          -0.796718 0.589085 0.134976,
+                          -0.952511 0.271619 0.13764,
+                          -0.878802 0.316614 0.357019,
+                          -0.815091 0.576393 0.0582807,
+                          -0.952511 0.271619 0.13764,
+                          -0.796718 0.589085 0.134976,
+                          -0.68193 0.644307 0.346179,
+                          -0.878802 0.316614 0.357019,
+                          -0.559773 0.341124 0.755175,
+                          -0.796718 0.589085 0.134976,
+                          -0.878802 0.316614 0.357019,
+                          -0.68193 0.644307 0.346179,
+                          -0.42828 0.679601 0.595583,
+                          -0.559773 0.341124 0.755175,
+                          -0.160063 0.313194 0.936103,
+                          -0.68193 0.644307 0.346179,
+                          -0.559773 0.341124 0.755175,
+                          -0.42828 0.679601 0.595583,
+                          -0.42828 0.679601 0.595583,
+                          -0.160063 0.313194 0.936103,
+                          -0.139499 0.643651 0.752498,
+                          -0.14008 -0.195296 0.970689,
+                          -0.136411 -0.193074 0.971655,
+                          -0.136275 -0.190295 0.972223,
+                          -0.989949 0.141421 -1.2616e-16,
+                          -0.989949 0.141421 9.2942e-15,
+                          -0.750767 -0.62987 0.199029,
+                          -0.135908 -0.194103 0.971521,
+                          -0.131722 -0.192928 0.972331,
+                          -0.136411 -0.193074 0.971655,
+                          -0.753312 -0.627035 0.198362,
+                          -0.750767 -0.62987 0.199029,
+                          -2.27454e-16 -0.965427 0.260673,
+                          -0.14008 -0.195296 0.970689,
+                          -0.135908 -0.194103 0.971521,
+                          -0.136411 -0.193074 0.971655,
+                          -0.753312 -0.627035 0.198362,
+                          -0.989949 0.141421 -1.2616e-16,
+                          -0.750767 -0.62987 0.199029,
+                          -0.753312 -0.627035 0.198362,
+                          -2.27454e-16 -0.965427 0.260673,
+                          -1.14339e-15 -0.965427 0.260673,
+                          -0.148812 -0.253095 0.955928,
+                          -0.0747697 -0.180268 0.980772,
+                          -0.14008 -0.195296 0.970689,
+                          -0.264976 -0.28945 0.919786,
+                          -0.148812 -0.253095 0.955928,
+                          -0.14008 -0.195296 0.970689,
+                          -0.0178143 -0.854044 0.519896,
+                          -0.148813 -0.253102 0.955926,
+                          -0.264917 -0.289417 0.919813,
+                          -0.163731 -0.886641 0.432505,
+                          -0.264917 -0.289417 0.919813,
+                          -0.412658 -0.315345 0.854559,
+                          -0.163731 -0.886641 0.432505,
+                          -0.0178143 -0.854044 0.519896,
+                          -0.264917 -0.289417 0.919813,
+                          -0.309153 -0.894931 0.321749,
+                          -0.412658 -0.315345 0.854559,
+                          -0.626754 -0.31167 0.714172,
+                          -0.309153 -0.894931 0.321749,
+                          -0.163731 -0.886641 0.432505,
+                          -0.412658 -0.315345 0.854559,
+                          -0.309153 -0.894931 0.321749,
+                          -0.626754 -0.31167 0.714172,
+                          -0.953822 -0.210373 0.214401,
+                          -0.603358 -0.771687 -0.201144,
+                          -0.953822 -0.210373 0.214401,
+                          -0.983872 -0.160831 0.0782875,
+                          -0.603358 -0.771687 -0.201144,
+                          -0.309153 -0.894931 0.321749,
+                          -0.953822 -0.210373 0.214401,
+                          -0.996196 -0.0572404 0.0656986,
+                          -0.99267 -0.115596 0.0352804,
+                          -0.983893 -0.160592 0.07851,
+                          -0.603358 -0.771687 -0.201144,
+                          -0.983872 -0.160831 0.0782875,
+                          -0.992669 -0.115608 0.0352692,
+                          -0.91084 -0.302726 0.280585,
+                          -0.992666 -0.115632 0.0352688,
+                          -0.996196 -0.0572645 0.0656818,
+                          -0.603358 -0.771687 -0.201144,
+                          -0.992669 -0.115608 0.0352692,
+                          -0.658993 -0.583025 -0.475194,
+                          -0.781437 -0.0578411 -0.621298,
+                          -0.892864 0.0224274 -0.449767,
+                          -0.835535 -0.0119643 -0.549307,
+                          -0.455281 0.460688 -0.761896,
+                          -0.892864 0.0224274 -0.449767,
+                          -0.781437 -0.0578411 -0.621298,
+                          0.00236468 -0.995855 0.0909223,
+                          0.0027881 -0.995976 0.0895816,
+                          0.00130028 -0.995724 0.0923736,
+                          0.00441922 -0.996209 0.0868808,
+                          0.0027881 -0.995976 0.0895816,
+                          0.00236468 -0.995855 0.0909223,
+                          0.0105326 -0.997732 0.0664819,
+                          0.0027881 -0.995976 0.0895816,
+                          0.00441922 -0.996209 0.0868808,
+                          0.0105326 -0.997732 0.0664819,
+                          0.00742854 -0.998057 0.0618633,
+                          0.0027881 -0.995976 0.0895816,
+                          -0.455281 0.460688 -0.761896,
+                          -0.781437 -0.0578411 -0.621298,
+                          -0.352459 0.246612 -0.902749,
+                          -0.750534 -0.00903652 -0.66077,
+                          -0.738212 -0.0636969 -0.671555,
+                          -0.760331 -0.0608806 -0.646676,
+                          0.00236468 -0.995855 0.0909223,
+                          0.00130028 -0.995724 0.0923736,
+                          -0.000603417 -0.995455 0.0952329,
+                          0.673247 -0.0101041 -0.739348,
+                          0.673114 -0.00690018 -0.739506,
+                          0.660219 0.0159608 -0.750904,
+                          0.00236468 -0.995855 0.0909223,
+                          -0.000603417 -0.995455 0.0952329,
+                          -0.000147322 -0.995502 0.0947359,
+                          0.661107 0.0118524 -0.750198,
+                          0.660219 0.0159608 -0.750904,
+                          0.644191 0.00069228 -0.764864,
+                          0.673247 -0.0101041 -0.739348,
+                          0.660219 0.0159608 -0.750904,
+                          0.661107 0.0118524 -0.750198,
+                          -0.347016 0.920656 -0.178809,
+                          -0.0200022 0.999696 0.014442,
+                          -0.015383 0.999806 0.012333,
+                          0.876464 0.00754696 0.481408,
+                          0.865637 0.00714335 0.500622,
+                          0.948781 0.0144392 0.315604,
+                          -0.152808 0.980405 -0.12432,
+                          -0.347016 0.920656 -0.178809,
+                          -0.015383 0.999806 0.012333,
+                          0.713503 0.0251546 -0.7002,
+                          0.713834 0.0224996 -0.699953,
+                          0.73411 0.0196676 -0.678746,
+                          0.713503 0.0251546 -0.7002,
+                          0.73411 0.0196676 -0.678746,
+                          0.752091 0.0196978 -0.658765,
+                          -0.347016 0.920656 -0.178809,
+                          -0.0176641 0.999678 0.0181929,
+                          -0.0200022 0.999696 0.014442,
+                          0.957645 0.0149494 0.287563,
+                          0.948781 0.0144392 0.315604,
+                          0.988208 0.0146816 0.152415,
+                          0.876464 0.00754696 0.481408,
+                          0.948781 0.0144392 0.315604,
+                          0.957645 0.0149494 0.287563,
+                          -0.407688 0.909914 -0.0764639,
+                          -0.00834895 0.999752 0.020629,
+                          -0.0176641 0.999678 0.0181929,
+                          0.991482 0.0130197 0.129593,
+                          0.988208 0.0146816 0.152415,
+                          0.999958 0.00826249 0.00388075,
+                          -0.347016 0.920656 -0.178809,
+                          -0.407688 0.909914 -0.0764639,
+                          -0.0176641 0.999678 0.0181929,
+                          0.957645 0.0149494 0.287563,
+                          0.988208 0.0146816 0.152415,
+                          0.991482 0.0130197 0.129593,
+                          -0.430803 0.902446 0.000174788,
+                          0.00323441 0.999796 0.0199279,
+                          -0.00834895 0.999752 0.020629,
+                          0.999763 0.00410321 -0.0213863,
+                          0.999958 0.00826249 0.00388075,
+                          0.988439 -0.000176103 -0.151618,
+                          -0.407688 0.909914 -0.0764639,
+                          -0.430803 0.902446 0.000174788,
+                          -0.00834895 0.999752 0.020629,
+                          0.991482 0.0130197 0.129593,
+                          0.999958 0.00826249 0.00388075,
+                          0.999763 0.00410321 -0.0213863,
+                          -0.401586 0.912415 0.0789194,
+                          0.00914791 0.999814 0.0170045,
+                          0.00323441 0.999796 0.0199279,
+                          0.981341 -0.002028 -0.192263,
+                          0.988439 -0.000176103 -0.151618,
+                          0.942213 -0.00292335 -0.335001,
+                          -0.430803 0.902446 0.000174788,
+                          -0.401586 0.912415 0.0789194,
+                          0.00323441 0.999796 0.0199279,
+                          0.999763 0.00410321 -0.0213863,
+                          0.988439 -0.000176103 -0.151618,
+                          0.981341 -0.002028 -0.192263,
+                          -0.209729 0.927669 0.30894,
+                          0.015298 0.999866 0.00588474,
+                          0.00914791 0.999814 0.0170045,
+                          0.929658 -0.00372945 -0.368406,
+                          0.942213 -0.00292335 -0.335001,
+                          0.733258 -0.00721441 -0.679912,
+                          -0.319812 0.925026 0.205055,
+                          -0.209729 0.927669 0.30894,
+                          0.00914791 0.999814 0.0170045,
+                          -0.401586 0.912415 0.0789194,
+                          -0.319812 0.925026 0.205055,
+                          0.00914791 0.999814 0.0170045,
+                          0.981341 -0.002028 -0.192263,
+                          0.942213 -0.00292335 -0.335001,
+                          0.929658 -0.00372945 -0.368406,
+                          -0.0867596 0.918793 0.385088,
+                          0.0103227 0.999929 -0.00595768,
+                          0.015298 0.999866 0.00588474,
+                          0.709431 -0.00780339 -0.704732,
+                          0.733258 -0.00721441 -0.679912,
+                          0.370121 -0.00939158 -0.928936,
+                          -0.209729 0.927669 0.30894,
+                          -0.0867596 0.918793 0.385088,
+                          0.015298 0.999866 0.00588474,
+                          0.929658 -0.00372945 -0.368406,
+                          0.733258 -0.00721441 -0.679912,
+                          0.709431 -0.00780339 -0.704732,
+                          0.709431 -0.00780339 -0.704732,
+                          0.370121 -0.00939158 -0.928936,
+                          0.352895 -0.0095462 -0.935614,
+                          -0.139499 0.643651 0.752498,
+                          -0.0867596 0.918793 0.385088,
+                          -0.209729 0.927669 0.30894,
+                          -0.42828 0.679601 0.595583,
+                          -0.209729 0.927669 0.30894,
+                          -0.319812 0.925026 0.205055,
+                          -0.42828 0.679601 0.595583,
+                          -0.139499 0.643651 0.752498,
+                          -0.209729 0.927669 0.30894,
+                          -0.68193 0.644307 0.346179,
+                          -0.319812 0.925026 0.205055,
+                          -0.401586 0.912415 0.0789194,
+                          -0.68193 0.644307 0.346179,
+                          -0.42828 0.679601 0.595583,
+                          -0.319812 0.925026 0.205055,
+                          -0.796718 0.589085 0.134976,
+                          -0.401586 0.912415 0.0789194,
+                          -0.430803 0.902446 0.000174788,
+                          -0.796718 0.589085 0.134976,
+                          -0.68193 0.644307 0.346179,
+                          -0.401586 0.912415 0.0789194,
+                          -0.815091 0.576393 0.0582807,
+                          -0.430803 0.902446 0.000174788,
+                          -0.407688 0.909914 -0.0764639,
+                          -0.815091 0.576393 0.0582807,
+                          -0.796718 0.589085 0.134976,
+                          -0.430803 0.902446 0.000174788,
+                          -0.785138 0.618892 -0.0230438,
+                          -0.407688 0.909914 -0.0764639,
+                          -0.347016 0.920656 -0.178809,
+                          -0.785138 0.618892 -0.0230438,
+                          -0.815091 0.576393 0.0582807,
+                          -0.407688 0.909914 -0.0764639,
+                          -0.152808 0.980405 -0.12432,
+                          -0.273619 0.922456 -0.272409,
+                          -0.347016 0.920656 -0.178809,
+                          -0.680072 0.69777 -0.224987,
+                          -0.347016 0.920656 -0.178809,
+                          -0.273619 0.922456 -0.272409,
+                          -0.680072 0.69777 -0.224987,
+                          -0.785138 0.618892 -0.0230438,
+                          -0.347016 0.920656 -0.178809,
+                          0.701709 -0.00124151 -0.712462,
+                          0.701091 -0.0025957 -0.713067,
+                          0.713834 0.0224996 -0.699953,
+                          -0.680072 0.69777 -0.224987,
+                          -0.273619 0.922456 -0.272409,
+                          -0.296584 0.908125 -0.295545,
+                          0.700413 -0.0031382 -0.713731,
+                          0.698888 -0.00451073 -0.715217,
+                          0.701091 -0.0025957 -0.713067,
+                          0.700413 -0.0031382 -0.713731,
+                          0.701091 -0.0025957 -0.713067,
+                          0.701709 -0.00124151 -0.712462,
+                          0.701709 -0.00124151 -0.712462,
+                          0.713834 0.0224996 -0.699953,
+                          0.713503 0.0251546 -0.7002,
+                          -0.402591 0.831909 -0.3819,
+                          -0.680072 0.69777 -0.224987,
+                          -0.296584 0.908125 -0.295545,
+                          0.689668 -0.00119937 -0.724124,
+                          0.686211 -0.00184441 -0.7274,
+                          0.698888 -0.00451073 -0.715217,
+                          0.689668 -0.00119937 -0.724124,
+                          0.698888 -0.00451073 -0.715217,
+                          0.700413 -0.0031382 -0.713731,
+                          -0.402591 0.831909 -0.3819,
+                          -0.506509 0.739626 -0.443173,
+                          -0.680072 0.69777 -0.224987,
+                          0.66939 0.0161451 -0.742736,
+                          0.667388 0.0108757 -0.744631,
+                          0.686211 -0.00184441 -0.7274,
+                          0.6658 0.0187576 -0.745895,
+                          0.651047 0.0196781 -0.758782,
+                          0.667388 0.0108757 -0.744631,
+                          0.6658 0.0187576 -0.745895,
+                          0.667388 0.0108757 -0.744631,
+                          0.66939 0.0161451 -0.742736,
+                          0.66939 0.0161451 -0.742736,
+                          0.686211 -0.00184441 -0.7274,
+                          0.689668 -0.00119937 -0.724124,
+                          0.637866 0.0307471 -0.769533,
+                          0.651047 0.0196781 -0.758782,
+                          0.6658 0.0187576 -0.745895,
+                          -0.864067 0.115667 -0.489908,
+                          -0.750341 0.0730699 -0.657001,
+                          -0.818066 0.0176487 -0.574854,
+                          -0.958852 -0.0829948 -0.271504,
+                          -0.864067 0.115667 -0.489908,
+                          -0.818066 0.0176487 -0.574854,
+                          -0.748133 -0.0305746 -0.662845,
+                          -0.958852 -0.0829948 -0.271504,
+                          -0.818066 0.0176487 -0.574854,
+                          -0.440393 0.166262 -0.882276,
+                          -0.572795 0.12991 -0.809339,
+                          -0.750341 0.0730699 -0.657001,
+                          -0.864067 0.115667 -0.489908,
+                          -0.440393 0.166262 -0.882276,
+                          -0.750341 0.0730699 -0.657001,
+                          -0.440393 0.166262 -0.882276,
+                          -0.450239 0.149743 -0.880262,
+                          -0.572795 0.12991 -0.809339,
+                          -0.440393 0.166262 -0.882276,
+                          -0.339283 0.150022 -0.928645,
+                          -0.450239 0.149743 -0.880262,
+                          -0.176015 0.134326 -0.97518,
+                          -0.241659 0.129433 -0.96169,
+                          -0.339283 0.150022 -0.928645,
+                          -0.440393 0.166262 -0.882276,
+                          -0.176015 0.134326 -0.97518,
+                          -0.339283 0.150022 -0.928645,
+                          -0.176015 0.134326 -0.97518,
+                          -0.168236 0.0960181 -0.981059,
+                          -0.241659 0.129433 -0.96169,
+                          1.01355e-15 0.102623 -0.99472,
+                          -0.117106 0.0559442 -0.991543,
+                          -0.168236 0.0960181 -0.981059,
+                          -0.176015 0.134326 -0.97518,
+                          1.01355e-15 0.102623 -0.99472,
+                          -0.168236 0.0960181 -0.981059,
+                          1.01355e-15 0.102623 -0.99472,
+                          -0.0929343 0.0145889 -0.995565,
+                          -0.117106 0.0559442 -0.991543,
+                          1.01355e-15 0.102623 -0.99472,
+                          -0.0928112 -0.0179205 -0.995522,
+                          -0.0929343 0.0145889 -0.995565,
+                          1.01355e-15 0.102623 -0.99472,
+                          -0.110943 -0.0473058 -0.9927,
+                          -0.0928112 -0.0179205 -0.995522,
+                          9.88176e-16 -0.0607044 -0.998156,
+                          -0.116625 -0.049312 -0.991951,
+                          -0.110943 -0.0473058 -0.9927,
+                          9.63413e-16 0.0670753 -0.997748,
+                          9.88176e-16 -0.0607044 -0.998156,
+                          -0.110943 -0.0473058 -0.9927,
+                          1.01355e-15 0.102623 -0.99472,
+                          9.63413e-16 0.0670753 -0.997748,
+                          -0.110943 -0.0473058 -0.9927,
+                          -0.202231 -0.304022 -0.930953,
+                          -0.116625 -0.049312 -0.991951,
+                          9.88176e-16 -0.0607044 -0.998156,
+                          -0.150207 -0.0689534 -0.986247,
+                          -0.116625 -0.049312 -0.991951,
+                          -0.202231 -0.304022 -0.930953,
+                          0.176015 0.134326 -0.97518,
+                          9.94801e-16 -0.0607044 -0.998156,
+                          9.96105e-16 0.0670753 -0.997748,
+                          9.93982e-16 -0.151557 -0.988449,
+                          -0.202231 -0.304022 -0.930953,
+                          9.88176e-16 -0.0607044 -0.998156,
+                          0.116625 -0.049312 -0.991951,
+                          9.85923e-16 -0.151557 -0.988449,
+                          9.94801e-16 -0.0607044 -0.998156,
+                          0.117106 0.0559442 -0.991543,
+                          9.94801e-16 -0.0607044 -0.998156,
+                          0.176015 0.134326 -0.97518,
+                          0.110943 -0.0473058 -0.9927,
+                          0.116625 -0.049312 -0.991951,
+                          9.94801e-16 -0.0607044 -0.998156,
+                          0.0928112 -0.0179205 -0.995522,
+                          0.110943 -0.0473058 -0.9927,
+                          9.94801e-16 -0.0607044 -0.998156,
+                          0.0929343 0.0145889 -0.995565,
+                          0.0928112 -0.0179205 -0.995522,
+                          9.94801e-16 -0.0607044 -0.998156,
+                          0.117106 0.0559442 -0.991543,
+                          0.0929343 0.0145889 -0.995565,
+                          9.94801e-16 -0.0607044 -0.998156,
+                          0.176015 0.134326 -0.97518,
+                          9.96105e-16 0.0670753 -0.997748,
+                          9.43442e-16 0.102623 -0.99472,
+                          9.28079e-16 0.245738 -0.969336,
+                          1.01355e-15 0.102623 -0.99472,
+                          -0.176015 0.134326 -0.97518,
+                          0.212796 0.283837 -0.934962,
+                          9.43442e-16 0.102623 -0.99472,
+                          9.87421e-16 0.245738 -0.969336,
+                          0.212796 0.283837 -0.934962,
+                          0.176015 0.134326 -0.97518,
+                          9.43442e-16 0.102623 -0.99472,
+                          -0.349431 0.322536 -0.879698,
+                          -0.176015 0.134326 -0.97518,
+                          -0.440393 0.166262 -0.882276,
+                          -0.181341 0.273513 -0.94462,
+                          9.28079e-16 0.245738 -0.969336,
+                          -0.176015 0.134326 -0.97518,
+                          -0.349431 0.322536 -0.879698,
+                          -0.181341 0.273513 -0.94462,
+                          -0.176015 0.134326 -0.97518,
+                          -0.635738 0.325839 -0.699761,
+                          -0.440393 0.166262 -0.882276,
+                          -0.864067 0.115667 -0.489908,
+                          -0.635738 0.325839 -0.699761,
+                          -0.349431 0.322536 -0.879698,
+                          -0.440393 0.166262 -0.882276,
+                          -0.992574 0.017545 -0.120372,
+                          -0.992799 0.0480058 -0.109753,
+                          -0.864067 0.115667 -0.489908,
+                          -0.962233 0.213364 -0.169068,
+                          -0.864067 0.115667 -0.489908,
+                          -0.992799 0.0480058 -0.109753,
+                          -0.958852 -0.0829948 -0.271504,
+                          -0.992574 0.017545 -0.120372,
+                          -0.864067 0.115667 -0.489908,
+                          -0.962233 0.213364 -0.169068,
+                          -0.635738 0.325839 -0.699761,
+                          -0.864067 0.115667 -0.489908,
+                          -0.991755 0.0834071 -0.0972942,
+                          -0.962233 0.213364 -0.169068,
+                          -0.992799 0.0480058 -0.109753,
+                          -0.958852 -0.0829948 -0.271504,
+                          -0.993056 -0.0216832 -0.115628,
+                          -0.992574 0.017545 -0.120372,
+                          -0.977372 0.00928282 0.211324,
+                          -0.992574 0.0175536 -0.120371,
+                          -0.993056 -0.0216827 -0.115629,
+                          -0.958852 -0.0829948 -0.271504,
+                          -0.993002 -0.0576867 -0.103051,
+                          -0.993056 -0.0216832 -0.115628,
+                          -0.958852 -0.0829948 -0.271504,
+                          -0.992874 -0.0837301 -0.0847989,
+                          -0.993002 -0.0576867 -0.103051,
+                          -0.92898 -0.283405 -0.238072,
+                          -0.992874 -0.0837301 -0.0847989,
+                          -0.958852 -0.0829948 -0.271504,
+                          -0.962469 -0.255503 -0.0914939,
+                          -0.990442 -0.116416 -0.0739759,
+                          -0.992874 -0.0837301 -0.0847989,
+                          -0.92898 -0.283405 -0.238072,
+                          -0.962469 -0.255503 -0.0914939,
+                          -0.992874 -0.0837301 -0.0847989,
+                          -0.748133 -0.0305746 -0.662845,
+                          -0.62574 -0.04208 -0.778896,
+                          -0.958852 -0.0829948 -0.271504,
+                          -0.691371 -0.329417 -0.643032,
+                          -0.958852 -0.0829948 -0.271504,
+                          -0.62574 -0.04208 -0.778896,
+                          -0.691371 -0.329417 -0.643032,
+                          -0.92898 -0.283405 -0.238072,
+                          -0.958852 -0.0829948 -0.271504,
+                          -0.691371 -0.329417 -0.643032,
+                          -0.62574 -0.04208 -0.778896,
+                          -0.452437 -0.0691492 -0.889111,
+                          -0.30543 -0.0799153 -0.948855,
+                          -0.691371 -0.329417 -0.643032,
+                          -0.452437 -0.0691492 -0.889111,
+                          -0.963418 -0.260834 -0.0615675,
+                          -0.988606 -0.129375 -0.0769489,
+                          -0.990442 -0.116416 -0.0739759,
+                          -0.962469 -0.255503 -0.0914939,
+                          -0.963418 -0.260834 -0.0615675,
+                          -0.990442 -0.116416 -0.0739759,
+                          -0.963418 -0.260834 -0.0615675,
+                          -0.990621 -0.125694 -0.0535853,
+                          -0.988606 -0.129375 -0.0769489,
+                          -0.963418 -0.260834 -0.0615675,
+                          -0.981089 -0.0766635 0.177728,
+                          -0.990621 -0.125694 -0.0535853,
+                          -0.929345 -0.320732 0.182892,
+                          -0.975858 -0.0685551 0.207366,
+                          -0.981089 -0.0766635 0.177728,
+                          -0.963418 -0.260834 -0.0615675,
+                          -0.929345 -0.320732 0.182892,
+                          -0.981089 -0.0766635 0.177728,
+                          -0.929345 -0.320732 0.182892,
+                          -0.900115 -0.0573838 0.431857,
+                          -0.975858 -0.0685551 0.207366,
+                          -0.858324 0.00237511 0.513102,
+                          -0.975858 -0.0685551 0.207366,
+                          -0.900115 -0.0573838 0.431857,
+                          -0.771306 -0.213764 0.599493,
+                          -0.764442 -0.0366005 0.643653,
+                          -0.900115 -0.0573838 0.431857,
+                          -0.858324 0.00237511 0.513102,
+                          -0.900115 -0.0573838 0.431857,
+                          -0.764442 -0.0366005 0.643653,
+                          -0.743158 -0.353504 0.568111,
+                          -0.771306 -0.213764 0.599493,
+                          -0.900115 -0.0573838 0.431857,
+                          -0.929345 -0.320732 0.182892,
+                          -0.743158 -0.353504 0.568111,
+                          -0.900115 -0.0573838 0.431857,
+                          -0.791807 0.0563138 0.608169,
+                          -0.858324 0.00237511 0.513102,
+                          -0.764442 -0.0366005 0.643653,
+                          -0.76532 0.0600937 0.640839,
+                          -0.791807 0.0563138 0.608169,
+                          -0.764442 -0.0366005 0.643653,
+                          -0.74984 0.0110465 0.661527,
+                          -0.76532 0.0600937 0.640839,
+                          -0.764442 -0.0366005 0.643653,
+                          -0.641209 -0.574682 0.508519,
+                          -0.743158 -0.353504 0.568111,
+                          -0.929345 -0.320732 0.182892,
+                          -0.708718 -0.678933 0.191751,
+                          -0.929345 -0.320732 0.182892,
+                          -0.963418 -0.260834 -0.0615675,
+                          -0.513235 -0.732874 0.446638,
+                          -0.929345 -0.320732 0.182892,
+                          -0.708718 -0.678933 0.191751,
+                          -0.529878 -0.715683 0.455003,
+                          -0.929345 -0.320732 0.182892,
+                          -0.513235 -0.732874 0.446638,
+                          -0.529878 -0.715683 0.455003,
+                          -0.641209 -0.574682 0.508519,
+                          -0.929345 -0.320732 0.182892,
+                          -0.807036 -0.590217 -0.0183314,
+                          -0.963418 -0.260834 -0.0615675,
+                          -0.962469 -0.255503 -0.0914939,
+                          -0.708718 -0.678933 0.191751,
+                          -0.963418 -0.260834 -0.0615675,
+                          -0.807036 -0.590217 -0.0183314,
+                          -0.820972 -0.566248 -0.0732703,
+                          -0.962469 -0.255503 -0.0914939,
+                          -0.92898 -0.283405 -0.238072,
+                          -0.807036 -0.590217 -0.0183314,
+                          -0.962469 -0.255503 -0.0914939,
+                          -0.820972 -0.566248 -0.0732703,
+                          -0.753039 -0.607934 -0.251693,
+                          -0.92898 -0.283405 -0.238072,
+                          -0.691371 -0.329417 -0.643032,
+                          -0.820972 -0.566248 -0.0732703,
+                          -0.92898 -0.283405 -0.238072,
+                          -0.753039 -0.607934 -0.251693,
+                          -0.30543 -0.0799153 -0.948855,
+                          -0.202231 -0.304022 -0.930953,
+                          -0.691371 -0.329417 -0.643032,
+                          -0.523776 -0.668864 -0.527523,
+                          -0.691371 -0.329417 -0.643032,
+                          -0.202231 -0.304022 -0.930953,
+                          -0.753039 -0.607934 -0.251693,
+                          -0.691371 -0.329417 -0.643032,
+                          -0.523776 -0.668864 -0.527523,
+                          9.93982e-16 -0.151557 -0.988449,
+                          9.70801e-16 -0.292797 -0.956175,
+                          -0.202231 -0.304022 -0.930953,
+                          -0.173819 -0.640759 -0.747806,
+                          -0.202231 -0.304022 -0.930953,
+                          9.70801e-16 -0.292797 -0.956175,
+                          -0.206336 -0.0791813 -0.975272,
+                          -0.150207 -0.0689534 -0.986247,
+                          -0.202231 -0.304022 -0.930953,
+                          -0.30543 -0.0799153 -0.948855,
+                          -0.206336 -0.0791813 -0.975272,
+                          -0.202231 -0.304022 -0.930953,
+                          -0.523776 -0.668864 -0.527523,
+                          -0.202231 -0.304022 -0.930953,
+                          -0.173819 -0.640759 -0.747806,
+                          0.116625 -0.049312 -0.991951,
+                          9.70377e-16 -0.292797 -0.956175,
+                          9.85923e-16 -0.151557 -0.988449,
+                          9.20915e-16 -0.461265 -0.887262,
+                          -0.173819 -0.640759 -0.747806,
+                          9.70801e-16 -0.292797 -0.956175,
+                          0.202231 -0.304022 -0.930953,
+                          9.1397e-16 -0.461265 -0.887262,
+                          9.70377e-16 -0.292797 -0.956175,
+                          0.150207 -0.0689534 -0.986247,
+                          9.70377e-16 -0.292797 -0.956175,
+                          0.116625 -0.049312 -0.991951,
+                          0.150207 -0.0689534 -0.986247,
+                          0.206336 -0.0791813 -0.975272,
+                          9.70377e-16 -0.292797 -0.956175,
+                          0.202231 -0.304022 -0.930953,
+                          9.70377e-16 -0.292797 -0.956175,
+                          0.206336 -0.0791813 -0.975272,
+                          0.00971634 -0.999932 0.00649957,
+                          4.94806e-16 -0.909804 -0.415038,
+                          7.84829e-17 -0.999947 0.0102817,
+                          0.104235 -0.917922 -0.382824,
+                          7.84856e-17 -0.999947 0.0102817,
+                          4.86558e-16 -0.909804 -0.415038,
+                          0.104235 -0.917922 -0.382824,
+                          -0.00971634 -0.999932 0.00649957,
+                          7.84856e-17 -0.999947 0.0102817,
+                          0.00971634 -0.999932 0.00649957,
+                          -0.104235 -0.917922 -0.382824,
+                          4.94806e-16 -0.909804 -0.415038,
+                          5.82272e-16 -0.856817 -0.515621,
+                          4.94806e-16 -0.909804 -0.415038,
+                          -0.104235 -0.917922 -0.382824,
+                          0.173819 -0.640759 -0.747806,
+                          4.86558e-16 -0.909804 -0.415038,
+                          5.88433e-16 -0.856817 -0.515621,
+                          0.173819 -0.640759 -0.747806,
+                          0.104235 -0.917922 -0.382824,
+                          4.86558e-16 -0.909804 -0.415038,
+                          0.0152861 -0.999874 -0.00429686,
+                          -0.247614 -0.925932 -0.285196,
+                          -0.104235 -0.917922 -0.382824,
+                          -0.173819 -0.640759 -0.747806,
+                          -0.104235 -0.917922 -0.382824,
+                          -0.247614 -0.925932 -0.285196,
+                          0.00971634 -0.999932 0.00649957,
+                          0.0152861 -0.999874 -0.00429686,
+                          -0.104235 -0.917922 -0.382824,
+                          8.25619e-16 -0.613849 -0.789423,
+                          5.82272e-16 -0.856817 -0.515621,
+                          -0.104235 -0.917922 -0.382824,
+                          -0.173819 -0.640759 -0.747806,
+                          8.25619e-16 -0.613849 -0.789423,
+                          -0.104235 -0.917922 -0.382824,
+                          0.0103172 -0.99982 -0.0159159,
+                          -0.364709 -0.918174 -0.154741,
+                          -0.247614 -0.925932 -0.285196,
+                          -0.523776 -0.668864 -0.527523,
+                          -0.247614 -0.925932 -0.285196,
+                          -0.364709 -0.918174 -0.154741,
+                          0.0152861 -0.999874 -0.00429686,
+                          0.0103172 -0.99982 -0.0159159,
+                          -0.247614 -0.925932 -0.285196,
+                          -0.523776 -0.668864 -0.527523,
+                          -0.173819 -0.640759 -0.747806,
+                          -0.247614 -0.925932 -0.285196,
+                          0.0058105 -0.9998 -0.0191128,
+                          -0.43155 -0.901704 -0.0263597,
+                          -0.364709 -0.918174 -0.154741,
+                          -0.753039 -0.607934 -0.251693,
+                          -0.364709 -0.918174 -0.154741,
+                          -0.43155 -0.901704 -0.0263597,
+                          0.0103172 -0.99982 -0.0159159,
+                          0.0058105 -0.9998 -0.0191128,
+                          -0.364709 -0.918174 -0.154741,
+                          -0.753039 -0.607934 -0.251693,
+                          -0.523776 -0.668864 -0.527523,
+                          -0.364709 -0.918174 -0.154741,
+                          -0.00365815 -0.999778 -0.0207521,
+                          -0.425213 -0.903746 0.0493736,
+                          -0.43155 -0.901704 -0.0263597,
+                          -0.820972 -0.566248 -0.0732703,
+                          -0.43155 -0.901704 -0.0263597,
+                          -0.425213 -0.903746 0.0493736,
+                          0.0058105 -0.9998 -0.0191128,
+                          -0.00365815 -0.999778 -0.0207521,
+                          -0.43155 -0.901704 -0.0263597,
+                          -0.820972 -0.566248 -0.0732703,
+                          -0.753039 -0.607934 -0.251693,
+                          -0.43155 -0.901704 -0.0263597,
+                          -0.0156314 -0.999694 -0.0191565,
+                          -0.361894 -0.917435 0.165364,
+                          -0.425213 -0.903746 0.0493736,
+                          -0.807036 -0.590217 -0.0183314,
+                          -0.425213 -0.903746 0.0493736,
+                          -0.361894 -0.917435 0.165364,
+                          -0.00365815 -0.999778 -0.0207521,
+                          -0.0156314 -0.999694 -0.0191565,
+                          -0.425213 -0.903746 0.0493736,
+                          -0.807036 -0.590217 -0.0183314,
+                          -0.820972 -0.566248 -0.0732703,
+                          -0.425213 -0.903746 0.0493736,
+                          -0.258904 -0.931181 0.256653,
+                          -0.276585 -0.920653 0.275498,
+                          -0.361894 -0.917435 0.165364,
+                          -0.708718 -0.678933 0.191751,
+                          -0.361894 -0.917435 0.165364,
+                          -0.276585 -0.920653 0.275498,
+                          -0.139933 -0.984339 0.107221,
+                          -0.258904 -0.931181 0.256653,
+                          -0.361894 -0.917435 0.165364,
+                          -0.015383 -0.999806 -0.012333,
+                          -0.139933 -0.984339 0.107221,
+                          -0.361894 -0.917435 0.165364,
+                          -0.0201178 -0.999684 -0.0150999,
+                          -0.015383 -0.999806 -0.012333,
+                          -0.361894 -0.917435 0.165364,
+                          -0.0156314 -0.999694 -0.0191565,
+                          -0.0201178 -0.999684 -0.0150999,
+                          -0.361894 -0.917435 0.165364,
+                          -0.708718 -0.678933 0.191751,
+                          -0.807036 -0.590217 -0.0183314,
+                          -0.361894 -0.917435 0.165364,
+                          -0.391263 -0.840836 0.374042,
+                          -0.708718 -0.678933 0.191751,
+                          -0.276585 -0.920653 0.275498,
+                          0.173819 -0.640759 -0.747806,
+                          5.88433e-16 -0.856817 -0.515621,
+                          8.43002e-16 -0.613849 -0.789423,
+                          9.20915e-16 -0.461265 -0.887262,
+                          8.25619e-16 -0.613849 -0.789423,
+                          -0.173819 -0.640759 -0.747806,
+                          0.202231 -0.304022 -0.930953,
+                          8.43002e-16 -0.613849 -0.789423,
+                          9.1397e-16 -0.461265 -0.887262,
+                          0.173819 -0.640759 -0.747806,
+                          8.43002e-16 -0.613849 -0.789423,
+                          0.202231 -0.304022 -0.930953,
+                          -0.391263 -0.840836 0.374042,
+                          -0.513235 -0.732874 0.446638,
+                          -0.708718 -0.678933 0.191751,
+                          0.0178142 -0.854044 0.519896,
+                          0.0261185 -0.970552 -0.23947,
+                          -0.0235929 -0.96341 -0.266992,
+                          -0.0178143 -0.854044 0.519896,
+                          0.0334612 -0.960477 -0.276341,
+                          -0.0261184 -0.970552 -0.23947,
+                          0.163734 -0.886642 0.432501,
+                          -0.0235929 -0.96341 -0.266992,
+                          -0.0682971 -0.947789 -0.3115,
+                          0.163734 -0.886642 0.432501,
+                          0.0178142 -0.854044 0.519896,
+                          -0.0235929 -0.96341 -0.266992,
+                          0.309233 -0.894909 0.321735,
+                          -0.0682971 -0.947789 -0.3115,
+                          -0.188717 -0.947466 -0.258253,
+                          0.163734 -0.886642 0.432501,
+                          -0.0682971 -0.947789 -0.3115,
+                          0.309233 -0.894909 0.321735,
+                          0.309233 -0.894909 0.321735,
+                          -0.188717 -0.947466 -0.258253,
+                          -0.11691 -0.899044 -0.421963,
+                          -0.991755 0.0834071 -0.0972942,
+                          -0.987887 0.149892 -0.0401565,
+                          -0.962233 0.213364 -0.169068,
+                          0.603358 -0.771686 -0.201148,
+                          -0.11691 -0.899044 -0.421963,
+                          -0.0759179 -0.733123 -0.675846,
+                          0.309233 -0.894909 0.321735,
+                          -0.11691 -0.899044 -0.421963,
+                          0.603358 -0.771686 -0.201148,
+                          0.603358 -0.771686 -0.201148,
+                          -0.0759179 -0.733123 -0.675846,
+                          -0.0761203 -0.732159 -0.676866,
+                          -0.947373 0.0357123 0.318135,
+                          -0.858329 0.00237028 0.513094,
+                          -0.791807 0.0563241 0.608169,
+                          -0.00742854 -0.998057 0.0618633,
+                          -0.0105326 -0.997732 0.0664819,
+                          -0.00441922 -0.996209 0.0868808,
+                          -0.74984 0.0110465 0.661527,
+                          -0.73823 0.0635339 0.671551,
+                          -0.76532 0.0600937 0.640839,
+                          0.603358 -0.771686 -0.201148,
+                          -0.0765965 -0.714763 -0.695159,
+                          -0.0700486 -0.705442 -0.705298,
+                          0.603358 -0.771686 -0.201148,
+                          -0.0700486 -0.705442 -0.705298,
+                          0.658988 -0.583023 -0.475203,
+                          -0.0763981 -0.714813 -0.69513,
+                          -0.083264 -0.73002 -0.678335,
+                          -0.076807 -0.715847 -0.69402,
+                          0.603358 -0.771686 -0.201148,
+                          -0.0802678 -0.730629 -0.67804,
+                          -0.0765965 -0.714763 -0.695159,
+                          0.603358 -0.771686 -0.201148,
+                          -0.0761203 -0.732159 -0.676866,
+                          -0.0802678 -0.730629 -0.67804,
+                          0.958852 -0.0829948 -0.271504,
+                          0.748133 -0.0305746 -0.662845,
+                          0.818066 0.0176487 -0.574854,
+                          0.864067 0.115667 -0.489908,
+                          0.958852 -0.0829948 -0.271504,
+                          0.818066 0.0176487 -0.574854,
+                          0.750341 0.0730699 -0.657001,
+                          0.864067 0.115667 -0.489908,
+                          0.818066 0.0176487 -0.574854,
+                          0.958852 -0.0829948 -0.271504,
+                          0.62574 -0.04208 -0.778896,
+                          0.748133 -0.0305746 -0.662845,
+                          0.691371 -0.329417 -0.643032,
+                          0.62574 -0.04208 -0.778896,
+                          0.958852 -0.0829948 -0.271504,
+                          0.202231 -0.304022 -0.930953,
+                          0.452437 -0.0691492 -0.889111,
+                          0.62574 -0.04208 -0.778896,
+                          0.691371 -0.329417 -0.643032,
+                          0.202231 -0.304022 -0.930953,
+                          0.62574 -0.04208 -0.778896,
+                          0.993002 -0.0576867 -0.103051,
+                          0.992874 -0.0837301 -0.0847989,
+                          0.958852 -0.0829948 -0.271504,
+                          0.92898 -0.283405 -0.238072,
+                          0.958852 -0.0829948 -0.271504,
+                          0.992874 -0.0837301 -0.0847989,
+                          0.993056 -0.0216832 -0.115628,
+                          0.993002 -0.0576867 -0.103051,
+                          0.958852 -0.0829948 -0.271504,
+                          0.992574 0.017545 -0.120372,
+                          0.993056 -0.0216832 -0.115628,
+                          0.958852 -0.0829948 -0.271504,
+                          0.992799 0.0480058 -0.109753,
+                          0.992574 0.017545 -0.120372,
+                          0.958852 -0.0829948 -0.271504,
+                          0.864067 0.115667 -0.489908,
+                          0.992799 0.0480058 -0.109753,
+                          0.958852 -0.0829948 -0.271504,
+                          0.92898 -0.283405 -0.238072,
+                          0.691371 -0.329417 -0.643032,
+                          0.958852 -0.0829948 -0.271504,
+                          0.962469 -0.255503 -0.0914939,
+                          0.92898 -0.283405 -0.238072,
+                          0.992874 -0.0837301 -0.0847989,
+                          0.990442 -0.116416 -0.0739759,
+                          0.962469 -0.255503 -0.0914939,
+                          0.992874 -0.0837301 -0.0847989,
+                          0.977371 0.00933189 0.211327,
+                          0.992574 0.0175279 -0.12037,
+                          0.992807 0.0471008 -0.110069,
+                          0.967583 0.205964 -0.146158,
+                          0.992799 0.0480058 -0.109753,
+                          0.864067 0.115667 -0.489908,
+                          0.967583 0.205964 -0.146158,
+                          0.991755 0.0834071 -0.0972942,
+                          0.992799 0.0480058 -0.109753,
+                          0.450239 0.149743 -0.880262,
+                          0.440393 0.166262 -0.882276,
+                          0.864067 0.115667 -0.489908,
+                          0.678494 0.321194 -0.660667,
+                          0.864067 0.115667 -0.489908,
+                          0.440393 0.166262 -0.882276,
+                          0.572795 0.12991 -0.809339,
+                          0.450239 0.149743 -0.880262,
+                          0.864067 0.115667 -0.489908,
+                          0.750341 0.0730699 -0.657001,
+                          0.572795 0.12991 -0.809339,
+                          0.864067 0.115667 -0.489908,
+                          0.678494 0.321194 -0.660667,
+                          0.967583 0.205964 -0.146158,
+                          0.864067 0.115667 -0.489908,
+                          0.241659 0.129433 -0.96169,
+                          0.176015 0.134326 -0.97518,
+                          0.440393 0.166262 -0.882276,
+                          0.384548 0.327451 -0.863075,
+                          0.440393 0.166262 -0.882276,
+                          0.176015 0.134326 -0.97518,
+                          0.339283 0.150022 -0.928645,
+                          0.241659 0.129433 -0.96169,
+                          0.440393 0.166262 -0.882276,
+                          0.450239 0.149743 -0.880262,
+                          0.339283 0.150022 -0.928645,
+                          0.440393 0.166262 -0.882276,
+                          0.384548 0.327451 -0.863075,
+                          0.678494 0.321194 -0.660667,
+                          0.440393 0.166262 -0.882276,
+                          0.168236 0.0960181 -0.981059,
+                          0.117106 0.0559442 -0.991543,
+                          0.176015 0.134326 -0.97518,
+                          0.241659 0.129433 -0.96169,
+                          0.168236 0.0960181 -0.981059,
+                          0.176015 0.134326 -0.97518,
+                          0.212796 0.283837 -0.934962,
+                          0.384548 0.327451 -0.863075,
+                          0.176015 0.134326 -0.97518,
+                          0.202231 -0.304022 -0.930953,
+                          0.30543 -0.0799153 -0.948855,
+                          0.452437 -0.0691492 -0.889111,
+                          0.202231 -0.304022 -0.930953,
+                          0.206336 -0.0791813 -0.975272,
+                          0.30543 -0.0799153 -0.948855,
+                          0.173819 -0.640759 -0.747806,
+                          0.202231 -0.304022 -0.930953,
+                          0.691371 -0.329417 -0.643032,
+                          0.523776 -0.668864 -0.527523,
+                          0.691371 -0.329417 -0.643032,
+                          0.92898 -0.283405 -0.238072,
+                          0.173819 -0.640759 -0.747806,
+                          0.691371 -0.329417 -0.643032,
+                          0.523776 -0.668864 -0.527523,
+                          0.753039 -0.607934 -0.251693,
+                          0.92898 -0.283405 -0.238072,
+                          0.962469 -0.255503 -0.0914939,
+                          0.523776 -0.668864 -0.527523,
+                          0.92898 -0.283405 -0.238072,
+                          0.753039 -0.607934 -0.251693,
+                          0.990621 -0.125694 -0.0535853,
+                          0.963418 -0.260834 -0.0615675,
+                          0.962469 -0.255503 -0.0914939,
+                          0.820972 -0.566248 -0.0732703,
+                          0.962469 -0.255503 -0.0914939,
+                          0.963418 -0.260834 -0.0615675,
+                          0.988606 -0.129375 -0.0769489,
+                          0.990621 -0.125694 -0.0535853,
+                          0.962469 -0.255503 -0.0914939,
+                          0.990442 -0.116416 -0.0739759,
+                          0.988606 -0.129375 -0.0769489,
+                          0.962469 -0.255503 -0.0914939,
+                          0.753039 -0.607934 -0.251693,
+                          0.962469 -0.255503 -0.0914939,
+                          0.820972 -0.566248 -0.0732703,
+                          0.975858 -0.0685551 0.207366,
+                          0.929345 -0.320732 0.182892,
+                          0.963418 -0.260834 -0.0615675,
+                          0.807036 -0.590217 -0.0183314,
+                          0.963418 -0.260834 -0.0615675,
+                          0.929345 -0.320732 0.182892,
+                          0.981089 -0.0766635 0.177728,
+                          0.975858 -0.0685551 0.207366,
+                          0.963418 -0.260834 -0.0615675,
+                          0.990621 -0.125694 -0.0535853,
+                          0.981089 -0.0766635 0.177728,
+                          0.963418 -0.260834 -0.0615675,
+                          0.820972 -0.566248 -0.0732703,
+                          0.963418 -0.260834 -0.0615675,
+                          0.807036 -0.590217 -0.0183314,
+                          0.771306 -0.213764 0.599493,
+                          0.743158 -0.353504 0.568111,
+                          0.929345 -0.320732 0.182892,
+                          0.708718 -0.678933 0.191751,
+                          0.929345 -0.320732 0.182892,
+                          0.743158 -0.353504 0.568111,
+                          0.764442 -0.0366005 0.643653,
+                          0.771306 -0.213764 0.599493,
+                          0.929345 -0.320732 0.182892,
+                          0.900115 -0.0573838 0.431857,
+                          0.764442 -0.0366005 0.643653,
+                          0.929345 -0.320732 0.182892,
+                          0.975858 -0.0685551 0.207366,
+                          0.900115 -0.0573838 0.431857,
+                          0.929345 -0.320732 0.182892,
+                          0.807036 -0.590217 -0.0183314,
+                          0.929345 -0.320732 0.182892,
+                          0.708718 -0.678933 0.191751,
+                          0.641209 -0.574682 0.508519,
+                          0.708718 -0.678933 0.191751,
+                          0.743158 -0.353504 0.568111,
+                          0.74984 0.0110465 0.661527,
+                          0.764442 -0.0366005 0.643653,
+                          0.900115 -0.0573838 0.431857,
+                          0.858324 0.00237511 0.513102,
+                          0.900115 -0.0573838 0.431857,
+                          0.975858 -0.0685551 0.207366,
+                          0.73823 0.0635339 0.671551,
+                          0.74984 0.0110465 0.661527,
+                          0.900115 -0.0573838 0.431857,
+                          0.76532 0.0600937 0.640839,
+                          0.73823 0.0635339 0.671551,
+                          0.900115 -0.0573838 0.431857,
+                          0.791807 0.0563138 0.608169,
+                          0.76532 0.0600937 0.640839,
+                          0.900115 -0.0573838 0.431857,
+                          0.858324 0.00237511 0.513102,
+                          0.791807 0.0563138 0.608169,
+                          0.900115 -0.0573838 0.431857,
+                          0.104235 -0.917922 -0.382824,
+                          -0.0152861 -0.999874 -0.00429686,
+                          -0.00971634 -0.999932 0.00649957,
+                          0.247614 -0.925932 -0.285196,
+                          -0.0103172 -0.99982 -0.0159159,
+                          -0.0152861 -0.999874 -0.00429686,
+                          0.104235 -0.917922 -0.382824,
+                          0.247614 -0.925932 -0.285196,
+                          -0.0152861 -0.999874 -0.00429686,
+                          0.364709 -0.918174 -0.154741,
+                          -0.0058105 -0.9998 -0.0191128,
+                          -0.0103172 -0.99982 -0.0159159,
+                          0.247614 -0.925932 -0.285196,
+                          0.364709 -0.918174 -0.154741,
+                          -0.0103172 -0.99982 -0.0159159,
+                          0.43155 -0.901704 -0.0263597,
+                          0.00365815 -0.999778 -0.0207521,
+                          -0.0058105 -0.9998 -0.0191128,
+                          0.364709 -0.918174 -0.154741,
+                          0.43155 -0.901704 -0.0263597,
+                          -0.0058105 -0.9998 -0.0191128,
+                          0.425213 -0.903746 0.0493736,
+                          0.0156314 -0.999694 -0.0191565,
+                          0.00365815 -0.999778 -0.0207521,
+                          0.43155 -0.901704 -0.0263597,
+                          0.425213 -0.903746 0.0493736,
+                          0.00365815 -0.999778 -0.0207521,
+                          0.361894 -0.917435 0.165364,
+                          0.0201178 -0.999684 -0.0150999,
+                          0.0156314 -0.999694 -0.0191565,
+                          0.425213 -0.903746 0.0493736,
+                          0.361894 -0.917435 0.165364,
+                          0.0156314 -0.999694 -0.0191565,
+                          0.139933 -0.984339 0.107221,
+                          0.015383 -0.999806 -0.012333,
+                          0.0201178 -0.999684 -0.0150999,
+                          0.258904 -0.931181 0.256653,
+                          0.139933 -0.984339 0.107221,
+                          0.0201178 -0.999684 -0.0150999,
+                          0.276585 -0.920653 0.275498,
+                          0.258904 -0.931181 0.256653,
+                          0.0201178 -0.999684 -0.0150999,
+                          0.361894 -0.917435 0.165364,
+                          0.276585 -0.920653 0.275498,
+                          0.0201178 -0.999684 -0.0150999,
+                          0.391263 -0.840836 0.374042,
+                          0.276585 -0.920653 0.275498,
+                          0.361894 -0.917435 0.165364,
+                          0.708718 -0.678933 0.191751,
+                          0.361894 -0.917435 0.165364,
+                          0.425213 -0.903746 0.0493736,
+                          0.513235 -0.732874 0.446638,
+                          0.391263 -0.840836 0.374042,
+                          0.361894 -0.917435 0.165364,
+                          0.708718 -0.678933 0.191751,
+                          0.513235 -0.732874 0.446638,
+                          0.361894 -0.917435 0.165364,
+                          0.807036 -0.590217 -0.0183314,
+                          0.425213 -0.903746 0.0493736,
+                          0.43155 -0.901704 -0.0263597,
+                          0.807036 -0.590217 -0.0183314,
+                          0.708718 -0.678933 0.191751,
+                          0.425213 -0.903746 0.0493736,
+                          0.820972 -0.566248 -0.0732703,
+                          0.43155 -0.901704 -0.0263597,
+                          0.364709 -0.918174 -0.154741,
+                          0.820972 -0.566248 -0.0732703,
+                          0.807036 -0.590217 -0.0183314,
+                          0.43155 -0.901704 -0.0263597,
+                          0.753039 -0.607934 -0.251693,
+                          0.364709 -0.918174 -0.154741,
+                          0.247614 -0.925932 -0.285196,
+                          0.753039 -0.607934 -0.251693,
+                          0.820972 -0.566248 -0.0732703,
+                          0.364709 -0.918174 -0.154741,
+                          0.523776 -0.668864 -0.527523,
+                          0.247614 -0.925932 -0.285196,
+                          0.104235 -0.917922 -0.382824,
+                          0.523776 -0.668864 -0.527523,
+                          0.753039 -0.607934 -0.251693,
+                          0.247614 -0.925932 -0.285196,
+                          0.173819 -0.640759 -0.747806,
+                          0.523776 -0.668864 -0.527523,
+                          0.104235 -0.917922 -0.382824,
+                          0.529878 -0.715683 0.455003,
+                          0.513235 -0.732874 0.446638,
+                          0.708718 -0.678933 0.191751,
+                          0.641209 -0.574682 0.508519,
+                          0.529878 -0.715683 0.455003,
+                          0.708718 -0.678933 0.191751,
+                          0.967583 0.205964 -0.146158,
+                          0.987887 0.149892 -0.0401567,
+                          0.991755 0.0834071 -0.0972942,
+                          -0.658993 -0.583025 -0.475194,
+                          0.0759142 -0.733097 -0.675874,
+                          0.111417 -0.884527 -0.452988,
+                          -0.658993 -0.583025 -0.475194,
+                          0.0773422 -0.730987 -0.677995,
+                          0.0759142 -0.733097 -0.675874,
+                          -0.603358 -0.771687 -0.201144,
+                          0.111417 -0.884527 -0.452988,
+                          0.193914 -0.948678 -0.249813,
+                          -0.603358 -0.771687 -0.201144,
+                          -0.658993 -0.583025 -0.475194,
+                          0.111417 -0.884527 -0.452988,
+                          -0.309153 -0.894931 0.321749,
+                          0.193914 -0.948678 -0.249813,
+                          0.0716909 -0.945391 -0.317955,
+                          -0.603358 -0.771687 -0.201144,
+                          0.193914 -0.948678 -0.249813,
+                          -0.309153 -0.894931 0.321749,
+                          -0.163731 -0.886641 0.432505,
+                          0.0716909 -0.945391 -0.317955,
+                          0.0334612 -0.960477 -0.276341,
+                          -0.309153 -0.894931 0.321749,
+                          0.0716909 -0.945391 -0.317955,
+                          -0.163731 -0.886641 0.432505,
+                          -0.163731 -0.886641 0.432505,
+                          0.0334612 -0.960477 -0.276341,
+                          -0.0178143 -0.854044 0.519896,
+                          0.947373 0.0357123 0.318135,
+                          0.791807 0.0563241 0.608169,
+                          0.858329 0.00237028 0.513094,
+                          -0.658993 -0.583025 -0.475194,
+                          0.0700511 -0.705451 -0.705289,
+                          0.0759013 -0.713861 -0.696162,
+                          0.0765099 -0.715311 -0.694606,
+                          0.0826397 -0.728375 -0.680176,
+                          0.0758931 -0.713875 -0.696148,
+                          -0.658993 -0.583025 -0.475194,
+                          0.0759013 -0.713861 -0.696162,
+                          0.0826034 -0.728383 -0.680173,
+                          -0.658993 -0.583025 -0.475194,
+                          0.0826034 -0.728383 -0.680173,
+                          0.0773422 -0.730987 -0.677995,
+                          -0.90428 -0.00267052 0.426932,
+                          -0.992512 -0.00479914 0.12205,
+                          -0.961352 0.153926 0.228273,
+                          8.00716e-09 0.24581 0.969318,
+                          0.169535 0.0899003 0.981415,
+                          -1.4303e-06 0.0666464 0.997777,
+                          -9.79407e-16 0.24581 0.969318,
+                          -9.9164e-16 0.0666362 0.997777,
+                          -9.79408e-16 0.245809 0.969318,
+                          -8.59697e-16 -0.41934 0.907829,
+                          -1.71943e-16 -0.965427 0.260673,
+                          -1.71943e-16 -0.965427 0.260673,
+                          0.757062 -0.622818 0.197368,
+                          -8.04186e-16 -0.41934 0.907829,
+                          2.0485e-15 -0.965427 0.260673,
+                          -8.59697e-16 -0.41934 0.907829,
+                          -8.53427e-16 -0.430687 0.902501,
+                          -1.71943e-16 -0.965427 0.260673,
+                          -0.753312 -0.627035 0.198362,
+                          -2.55892e-15 -0.965427 0.260673,
+                          -7.97916e-16 -0.430687 0.902501,
+                          -9.79407e-16 0.24581 0.969318,
+                          -9.79408e-16 0.245809 0.969318,
+                          -9.35e-16 0.416726 0.909032,
+                          -0.680259 0.383509 0.624635,
+                          -3.16548e-06 0.416705 0.909042,
+                          -7.56276e-09 0.245809 0.969318,
+                          -9.35e-16 0.416726 0.909032,
+                          -9.79407e-16 0.24581 0.969318,
+                          -9.35e-16 0.416726 0.909032,
+                          -8.53427e-16 -0.430687 0.902501,
+                          -9.35e-16 0.416726 0.909032,
+                          -9.35e-16 0.416726 0.909032,
+                          -0.753312 -0.627035 0.198362,
+                          -7.97916e-16 -0.430687 0.902501,
+                          -3.10754e-10 0.416726 0.909032,
+                          -0.753312 -0.627035 0.198362,
+                          -3.10754e-10 0.416726 0.909032,
+                          -0.683689 0.381918 0.621859,
+                          -0.680259 0.383509 0.624635,
+                          -7.56276e-09 0.245809 0.969318,
+                          -0.989949 0.141426 1.5699e-05,
+                          0.989949 0.141426 1.56733e-05,
+                          8.00716e-09 0.24581 0.969318,
+                          3.16396e-06 0.416705 0.909042,
+                          0.680132 0.384271 0.624305,
+                          -6.9261e-09 0.416726 0.909032,
+                          0.98995 0.141421 1.55271e-08,
+                          -8.04186e-16 -0.41934 0.907829,
+                          0.98995 0.141421 1.55271e-08,
+                          -6.9261e-09 0.416726 0.909032,
+                          0.680259 0.383509 0.624635,
+                          0.989949 0.141426 1.56733e-05,
+                          3.16396e-06 0.416705 0.909042,
+                          -8.59697e-16 -0.41934 0.907829,
+                          -9.35e-16 0.416726 0.909032,
+                          -8.53427e-16 -0.430687 0.902501,
+                          0.680259 0.383509 0.624635,
+                          0.989949 0.141422 -8.83439e-08,
+                          0.989949 0.141426 1.56733e-05,
+                          0.757062 -0.622818 0.197368,
+                          0.98995 0.141421 1.55271e-08,
+                          -8.04186e-16 -0.41934 0.907829,
+                          -0.680259 0.383509 0.624635,
+                          -0.989949 0.141426 1.5699e-05,
+                          -0.989949 0.141422 -8.84706e-08,
+                          -0.753312 -0.627035 0.198362,
+                          -0.683689 0.381918 0.621859,
+                          -0.98995 0.141421 8.74392e-09,
+                          0.230125 -0.612952 0.755865,
+                          0.714941 -0.231108 0.659885,
+                          0.392625 -0.548438 0.738283,
+                          0.0749294 -0.795332 0.601525,
+                          0.230125 -0.612952 0.755865,
+                          0.392625 -0.548438 0.738283,
+                          0.230125 -0.612952 0.755865,
+                          0.71668 -0.223973 0.660459,
+                          0.714941 -0.231108 0.659885,
+                          0.137384 -0.669253 0.730224,
+                          -0.21154 -0.652623 0.727554,
+                          0.71668 -0.223973 0.660459,
+                          0.230125 -0.612952 0.755865,
+                          0.137384 -0.669253 0.730224,
+                          0.71668 -0.223973 0.660459,
+                          -0.553842 -0.790291 -0.262104,
+                          -0.91257 -0.402877 0.070044,
+                          -0.21154 -0.652623 0.727554,
+                          -0.200111 -0.891262 0.40695,
+                          -0.553842 -0.790291 -0.262104,
+                          -0.21154 -0.652623 0.727554,
+                          0.137384 -0.669253 0.730224,
+                          -0.200111 -0.891262 0.40695,
+                          -0.21154 -0.652623 0.727554,
+                          -0.53856 -0.797748 -0.271204,
+                          -0.553842 -0.790291 -0.262104,
+                          -0.200111 -0.891262 0.40695,
+                          0.240249 -0.891117 0.384956,
+                          -0.200111 -0.891262 0.40695,
+                          0.137384 -0.669253 0.730224,
+                          0.050449 -0.865066 -0.499115,
+                          -0.53856 -0.797748 -0.271204,
+                          -0.200111 -0.891262 0.40695,
+                          0.240249 -0.891117 0.384956,
+                          0.050449 -0.865066 -0.499115,
+                          -0.200111 -0.891262 0.40695,
+                          0.256931 -0.691971 0.674657,
+                          0.137384 -0.669253 0.730224,
+                          0.230125 -0.612952 0.755865,
+                          0.256931 -0.691971 0.674657,
+                          0.240249 -0.891117 0.384956,
+                          0.137384 -0.669253 0.730224,
+                          0.0749294 -0.795332 0.601525,
+                          0.0839532 -0.804226 0.588365,
+                          0.230125 -0.612952 0.755865,
+                          0.253591 -0.666482 0.701066,
+                          0.230125 -0.612952 0.755865,
+                          0.0839532 -0.804226 0.588365,
+                          0.253591 -0.666482 0.701066,
+                          0.256931 -0.691971 0.674657,
+                          0.230125 -0.612952 0.755865,
+                          0.238072 -0.809802 0.536229,
+                          0.253591 -0.666482 0.701066,
+                          0.0839532 -0.804226 0.588365,
+                          0.0613162 -0.862998 -0.501472,
+                          0.050449 -0.865066 -0.499115,
+                          0.240249 -0.891117 0.384956,
+                          0.430808 -0.772261 0.466923,
+                          0.240249 -0.891117 0.384956,
+                          0.256931 -0.691971 0.674657,
+                          0.379375 -0.750329 -0.54137,
+                          0.0613162 -0.862998 -0.501472,
+                          0.240249 -0.891117 0.384956,
+                          0.430808 -0.772261 0.466923,
+                          0.379375 -0.750329 -0.54137,
+                          0.240249 -0.891117 0.384956,
+                          0.217436 -0.472786 0.853929,
+                          0.256931 -0.691971 0.674657,
+                          0.253591 -0.666482 0.701066,
+                          0.217436 -0.472786 0.853929,
+                          0.430808 -0.772261 0.466923,
+                          0.256931 -0.691971 0.674657,
+                          0.238072 -0.809802 0.536229,
+                          0.254194 -0.805333 0.53556,
+                          0.253591 -0.666482 0.701066,
+                          0.172299 -0.47553 0.862661,
+                          0.253591 -0.666482 0.701066,
+                          0.254194 -0.805333 0.53556,
+                          0.172299 -0.47553 0.862661,
+                          0.217436 -0.472786 0.853929,
+                          0.253591 -0.666482 0.701066,
+                          0.318418 -0.720226 0.616348,
+                          0.172299 -0.47553 0.862661,
+                          0.254194 -0.805333 0.53556,
+                          -0.714941 -0.231108 0.659885,
+                          -0.0749294 -0.795332 0.601525,
+                          -0.392625 -0.548438 0.738283,
+                          -0.714941 -0.231108 0.659885,
+                          -0.0839532 -0.804226 0.588365,
+                          -0.0749294 -0.795332 0.601525,
+                          -0.714941 -0.231108 0.659885,
+                          -0.230125 -0.612952 0.755865,
+                          -0.0839532 -0.804226 0.588365,
+                          -0.238072 -0.809802 0.536229,
+                          -0.0839532 -0.804226 0.588365,
+                          -0.230125 -0.612952 0.755865,
+                          -0.71668 -0.223973 0.660459,
+                          -0.137384 -0.669253 0.730224,
+                          -0.230125 -0.612952 0.755865,
+                          -0.253591 -0.666482 0.701066,
+                          -0.230125 -0.612952 0.755865,
+                          -0.137384 -0.669253 0.730224,
+                          -0.714941 -0.231108 0.659885,
+                          -0.71668 -0.223973 0.660459,
+                          -0.230125 -0.612952 0.755865,
+                          -0.254194 -0.805333 0.53556,
+                          -0.230125 -0.612952 0.755865,
+                          -0.253591 -0.666482 0.701066,
+                          -0.238072 -0.809802 0.536229,
+                          -0.230125 -0.612952 0.755865,
+                          -0.254194 -0.805333 0.53556,
+                          0.21154 -0.652623 0.727554,
+                          0.200111 -0.891262 0.40695,
+                          -0.137384 -0.669253 0.730224,
+                          -0.256931 -0.691971 0.674657,
+                          -0.137384 -0.669253 0.730224,
+                          0.200111 -0.891262 0.40695,
+                          -0.71668 -0.223973 0.660459,
+                          0.21154 -0.652623 0.727554,
+                          -0.137384 -0.669253 0.730224,
+                          -0.253591 -0.666482 0.701066,
+                          -0.137384 -0.669253 0.730224,
+                          -0.256931 -0.691971 0.674657,
+                          0.91257 -0.402877 0.070044,
+                          0.553842 -0.790291 -0.262104,
+                          0.200111 -0.891262 0.40695,
+                          -0.240249 -0.891117 0.384956,
+                          0.200111 -0.891262 0.40695,
+                          0.553842 -0.790291 -0.262104,
+                          0.21154 -0.652623 0.727554,
+                          0.91257 -0.402877 0.070044,
+                          0.200111 -0.891262 0.40695,
+                          -0.256931 -0.691971 0.674657,
+                          0.200111 -0.891262 0.40695,
+                          -0.240249 -0.891117 0.384956,
+                          0.53856 -0.797748 -0.271204,
+                          -0.240249 -0.891117 0.384956,
+                          0.553842 -0.790291 -0.262104,
+                          -0.253591 -0.666482 0.701066,
+                          -0.172299 -0.47553 0.862661,
+                          -0.318418 -0.720226 0.616348,
+                          -0.254194 -0.805333 0.53556,
+                          -0.253591 -0.666482 0.701066,
+                          -0.318418 -0.720226 0.616348,
+                          -0.253591 -0.666482 0.701066,
+                          -0.217436 -0.472786 0.853929,
+                          -0.172299 -0.47553 0.862661,
+                          -0.256931 -0.691971 0.674657,
+                          -0.430808 -0.772261 0.466923,
+                          -0.217436 -0.472786 0.853929,
+                          -0.253591 -0.666482 0.701066,
+                          -0.256931 -0.691971 0.674657,
+                          -0.217436 -0.472786 0.853929,
+                          -0.0613162 -0.862998 -0.501472,
+                          -0.379375 -0.750329 -0.54137,
+                          -0.430808 -0.772261 0.466923,
+                          -0.050449 -0.865066 -0.499115,
+                          -0.0613162 -0.862998 -0.501472,
+                          -0.430808 -0.772261 0.466923,
+                          -0.240249 -0.891117 0.384956,
+                          -0.050449 -0.865066 -0.499115,
+                          -0.430808 -0.772261 0.466923,
+                          -0.256931 -0.691971 0.674657,
+                          -0.240249 -0.891117 0.384956,
+                          -0.430808 -0.772261 0.466923,
+                          0.53856 -0.797748 -0.271204,
+                          -0.050449 -0.865066 -0.499115,
+                          -0.240249 -0.891117 0.384956 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 109.999 65.6149 -28.2639,
+                          109.999 61.3667 15.547,
+                          109.999 50.6687 17.8527,
+                          109.76 50.6687 19.0259,
+                          109.999 50.6687 17.8527,
+                          109.999 61.3667 15.547,
+                          109.999 49.8108 -33.534,
+                          109.999 65.6149 -28.2639,
+                          109.999 50.6687 17.8527,
+                          109.999 42.5981 16.576,
+                          109.999 49.8108 -33.534,
+                          109.999 50.6687 17.8527,
+                          109.13 46.6503 19.6764,
+                          109.999 42.5981 16.576,
+                          109.999 50.6687 17.8527,
+                          109.76 50.6687 19.0259,
+                          109.13 46.6503 19.6764,
+                          109.999 50.6687 17.8527,
+                          109.999 65.6149 -28.2639,
+                          109.999 69.9395 9.2146,
+                          109.999 61.3667 15.547,
+                          108.891 60.2064 18.5269,
+                          109.999 61.3667 15.547,
+                          109.999 69.9395 9.2146,
+                          108.947 57.9848 19.1726,
+                          109.999 61.3667 15.547,
+                          108.891 60.2064 18.5269,
+                          109.081 50.6687 20.0122,
+                          109.999 61.3667 15.547,
+                          108.947 57.9848 19.1726,
+                          109.76 50.6687 19.0259,
+                          109.999 61.3667 15.547,
+                          109.081 50.6687 20.0122,
+                          109.999 72.8235 -20.1051,
+                          109.999 75.0244 0.237638,
+                          109.999 69.9395 9.2146,
+                          108.884 75.0168 6.07596,
+                          109.999 69.9395 9.2146,
+                          109.999 75.0244 0.237638,
+                          109.999 65.6149 -28.2639,
+                          109.999 72.8235 -20.1051,
+                          109.999 69.9395 9.2146,
+                          108.884 75.0168 6.07596,
+                          108.891 60.2064 18.5269,
+                          109.999 69.9395 9.2146,
+                          109.999 72.8235 -20.1051,
+                          109.999 76.0677 -9.99524,
+                          109.999 75.0244 0.237638,
+                          108.884 75.0168 6.07596,
+                          109.999 75.0244 0.237638,
+                          109.999 76.0677 -9.99524,
+                          108.884 77.9717 -12.957,
+                          109.999 76.0677 -9.99524,
+                          109.999 72.8235 -20.1051,
+                          108.884 75.0168 6.07596,
+                          109.999 76.0677 -9.99524,
+                          108.884 77.9717 -12.957,
+                          108.884 67.9516 -29.408,
+                          109.999 72.8235 -20.1051,
+                          109.999 65.6149 -28.2639,
+                          108.884 77.9717 -12.957,
+                          109.999 72.8235 -20.1051,
+                          108.884 67.9516 -29.408,
+                          108.884 67.9516 -29.408,
+                          109.999 65.6149 -28.2639,
+                          109.999 49.8108 -33.534,
+                          109.999 42.5981 16.576,
+                          109.999 42.0443 -32.3406,
+                          109.999 49.8108 -33.534,
+                          109.004 49.8108 -35.7655,
+                          109.999 49.8108 -33.534,
+                          109.999 42.0443 -32.3406,
+                          109.004 49.8108 -35.7655,
+                          108.884 67.9516 -29.408,
+                          109.999 49.8108 -33.534,
+                          109.999 31.8272 9.87052,
+                          109.999 31.625 -25.9515,
+                          109.999 42.0443 -32.3406,
+                          109.004 34.1724 -30.9769,
+                          109.999 42.0443 -32.3406,
+                          109.999 31.625 -25.9515,
+                          109.999 42.5981 16.576,
+                          109.999 31.8272 9.87052,
+                          109.999 42.0443 -32.3406,
+                          109.004 34.1724 -30.9769,
+                          109.004 49.8108 -35.7655,
+                          109.999 42.0443 -32.3406,
+                          109.999 31.8272 9.87052,
+                          109.999 24.4545 -8.22826,
+                          109.999 31.625 -25.9515,
+                          109.004 24.0184 -18.0865,
+                          109.999 31.625 -25.9515,
+                          109.999 24.4545 -8.22826,
+                          109.004 24.0184 -18.0865,
+                          109.004 34.1724 -30.9769,
+                          109.999 31.625 -25.9515,
+                          109.009 23.0314 -1.59438,
+                          109.999 24.4545 -8.22826,
+                          109.999 31.8272 9.87052,
+                          109.004 24.0184 -18.0865,
+                          109.999 24.4545 -8.22826,
+                          109.009 23.0314 -1.59438,
+                          109.192 36.4393 16.0523,
+                          109.999 31.8272 9.87052,
+                          109.999 42.5981 16.576,
+                          109.179 30.3508 11.3039,
+                          109.999 31.8272 9.87052,
+                          109.192 36.4393 16.0523,
+                          109.133 26.4407 6.32377,
+                          109.999 31.8272 9.87052,
+                          109.179 30.3508 11.3039,
+                          109.032 23.3807 -0.373823,
+                          109.999 31.8272 9.87052,
+                          109.133 26.4407 6.32377,
+                          109.009 23.0314 -1.59438,
+                          109.999 31.8272 9.87052,
+                          109.032 23.3807 -0.373823,
+                          109.17 41.9596 18.5463,
+                          109.999 42.5981 16.576,
+                          109.13 46.6503 19.6764,
+                          109.192 36.4393 16.0523,
+                          109.999 42.5981 16.576,
+                          109.17 41.9596 18.5463,
+                          81.999 30.8575 -32.5654,
+                          81.999 24.7769 42.6906,
+                          81.999 40.9964 46.1274,
+                          84.4595 40.8107 52.295,
+                          81.999 40.9964 46.1274,
+                          81.999 24.7769 42.6906,
+                          81.999 40.9964 -33.8726,
+                          81.999 30.8575 -32.5654,
+                          81.999 40.9964 46.1274,
+                          81.999 57.1023 42.7408,
+                          81.999 40.9964 -33.8726,
+                          81.999 40.9964 46.1274,
+                          84.9127 54.2367 57.4132,
+                          81.999 57.1023 42.7408,
+                          81.999 40.9964 46.1274,
+                          84.4595 40.8107 52.295,
+                          84.9127 54.2367 57.4132,
+                          81.999 40.9964 46.1274,
+                          81.999 13.1869 -22.6229,
+                          81.999 11.3339 32.9628,
+                          81.999 24.7769 42.6906,
+                          83.358 7.76134 36.4586,
+                          81.999 24.7769 42.6906,
+                          81.999 11.3339 32.9628,
+                          81.999 21.3771 -28.7305,
+                          81.999 13.1869 -22.6229,
+                          81.999 24.7769 42.6906,
+                          81.999 30.8575 -32.5654,
+                          81.999 21.3771 -28.7305,
+                          81.999 24.7769 42.6906,
+                          84.7636 40.6455 58.9289,
+                          81.999 24.7769 42.6906,
+                          84.5831 30.4841 57.6103,
+                          84.2947 19.7488 53.6572,
+                          84.5831 30.4841 57.6103,
+                          81.999 24.7769 42.6906,
+                          84.4595 40.8107 52.295,
+                          81.999 24.7769 42.6906,
+                          84.7636 40.6455 58.9289,
+                          84.2947 19.7488 53.6572,
+                          81.999 24.7769 42.6906,
+                          83.3841 3.87717 40.5514,
+                          83.4146 4.03983 40.3717,
+                          83.3841 3.87717 40.5514,
+                          81.999 24.7769 42.6906,
+                          83.4369 4.23247 40.1613,
+                          81.999 24.7769 42.6906,
+                          83.358 7.76134 36.4586,
+                          83.4146 4.03983 40.3717,
+                          81.999 24.7769 42.6906,
+                          83.4369 4.23247 40.1613,
+                          81.999 6.80462 -14.6305,
+                          81.999 5.50284 24.5702,
+                          81.999 11.3339 32.9628,
+                          109.133 26.4407 6.32377,
+                          81.999 11.3339 32.9628,
+                          81.999 5.50284 24.5702,
+                          81.999 13.1869 -22.6229,
+                          81.999 6.80462 -14.6305,
+                          81.999 11.3339 32.9628,
+                          83.6206 12.4637 31.6668,
+                          81.999 11.3339 32.9628,
+                          109.133 26.4407 6.32377,
+                          84.7154 11.599 32.4235,
+                          81.999 11.3339 32.9628,
+                          83.6206 12.4637 31.6668,
+                          84.0977 7.85853 36.2769,
+                          81.999 11.3339 32.9628,
+                          84.7154 11.599 32.4235,
+                          84.0977 7.85853 36.2769,
+                          83.358 7.76134 36.4586,
+                          81.999 11.3339 32.9628,
+                          81.999 2.6621 -5.29399,
+                          81.999 1.98608 14.9697,
+                          81.999 5.50284 24.5702,
+                          109.032 23.3807 -0.373823,
+                          81.999 5.50284 24.5702,
+                          81.999 1.98608 14.9697,
+                          81.999 6.80462 -14.6305,
+                          81.999 2.6621 -5.29399,
+                          81.999 5.50284 24.5702,
+                          109.032 23.3807 -0.373823,
+                          109.133 26.4407 6.32377,
+                          81.999 5.50284 24.5702,
+                          81.999 2.6621 -5.29399,
+                          81.999 1.01913 4.80039,
+                          81.999 1.98608 14.9697,
+                          108.853 22.0962 -8.22725,
+                          81.999 1.98608 14.9697,
+                          81.999 1.01913 4.80039,
+                          109.009 23.0314 -1.59438,
+                          109.032 23.3807 -0.373823,
+                          81.999 1.98608 14.9697,
+                          108.853 22.0962 -8.22725,
+                          109.009 23.0314 -1.59438,
+                          81.999 1.98608 14.9697,
+                          108.583 23.0226 -16.1054,
+                          81.999 1.01913 4.80039,
+                          81.999 2.6621 -5.29399,
+                          108.583 23.0226 -16.1054,
+                          108.853 22.0962 -8.22725,
+                          81.999 1.01913 4.80039,
+                          108.583 23.0226 -16.1054,
+                          81.999 2.6621 -5.29399,
+                          81.999 6.80462 -14.6305,
+                          108.242 25.8058 -22.8779,
+                          81.999 6.80462 -14.6305,
+                          81.999 13.1869 -22.6229,
+                          108.242 25.8058 -22.8779,
+                          108.583 23.0226 -16.1054,
+                          81.999 6.80462 -14.6305,
+                          107.417 35.6265 -32.757,
+                          81.999 13.1869 -22.6229,
+                          81.999 21.3771 -28.7305,
+                          107.886 29.5793 -27.9546,
+                          108.242 25.8058 -22.8779,
+                          81.999 13.1869 -22.6229,
+                          107.417 35.6265 -32.757,
+                          107.886 29.5793 -27.9546,
+                          81.999 13.1869 -22.6229,
+                          107.075 41.1406 -35.2007,
+                          81.999 21.3771 -28.7305,
+                          81.999 30.8575 -32.5654,
+                          107.075 41.1406 -35.2007,
+                          107.417 35.6265 -32.757,
+                          81.999 21.3771 -28.7305,
+                          106.841 45.8108 -36.2525,
+                          81.999 30.8575 -32.5654,
+                          81.999 40.9964 -33.8726,
+                          106.841 45.8108 -36.2525,
+                          107.075 41.1406 -35.2007,
+                          81.999 30.8575 -32.5654,
+                          81.999 57.1023 42.7408,
+                          81.999 47.5146 -33.3379,
+                          81.999 40.9964 -33.8726,
+                          106.679 49.8108 -36.5169,
+                          81.999 40.9964 -33.8726,
+                          81.999 47.5146 -33.3379,
+                          106.841 45.8108 -36.2525,
+                          81.999 40.9964 -33.8726,
+                          106.679 49.8108 -36.5169,
+                          81.999 57.1023 42.7408,
+                          81.999 53.8534 -31.75,
+                          81.999 47.5146 -33.3379,
+                          106.54 54.2085 -36.1646,
+                          81.999 47.5146 -33.3379,
+                          81.999 53.8534 -31.75,
+                          106.54 54.2085 -36.1646,
+                          106.679 49.8108 -36.5169,
+                          81.999 47.5146 -33.3379,
+                          81.999 57.1023 42.7408,
+                          81.999 59.8487 -29.1514,
+                          81.999 53.8534 -31.75,
+                          106.427 59.3252 -34.8844,
+                          81.999 53.8534 -31.75,
+                          81.999 59.8487 -29.1514,
+                          106.427 59.3252 -34.8844,
+                          106.54 54.2085 -36.1646,
+                          81.999 53.8534 -31.75,
+                          81.999 70.489 33.1483,
+                          81.999 65.3401 -25.6119,
+                          81.999 59.8487 -29.1514,
+                          106.37 64.8029 -32.3337,
+                          81.999 59.8487 -29.1514,
+                          81.999 65.3401 -25.6119,
+                          81.999 57.1023 42.7408,
+                          81.999 70.489 33.1483,
+                          81.999 59.8487 -29.1514,
+                          106.37 64.8029 -32.3337,
+                          106.427 59.3252 -34.8844,
+                          81.999 59.8487 -29.1514,
+                          81.999 70.489 33.1483,
+                          81.999 73.0753 -17.7654,
+                          81.999 65.3401 -25.6119,
+                          80.9495 65.0305 -32.1047,
+                          81.999 65.3401 -25.6119,
+                          81.999 73.0753 -17.7654,
+                          103.365 64.9061 -31.516,
+                          106.37 64.8029 -32.3337,
+                          81.999 65.3401 -25.6119,
+                          90.2955 64.9173 -32.5566,
+                          103.365 64.9061 -31.516,
+                          81.999 65.3401 -25.6119,
+                          90.2955 64.9173 -32.5566,
+                          81.999 65.3401 -25.6119,
+                          80.9495 65.0305 -32.1047,
+                          81.999 78.8744 18.9825,
+                          81.999 78.3755 -8.11303,
+                          81.999 73.0753 -17.7654,
+                          85.3657 88.7782 -21.1588,
+                          81.999 73.0753 -17.7654,
+                          81.999 78.3755 -8.11303,
+                          81.999 70.489 33.1483,
+                          81.999 78.8744 18.9825,
+                          81.999 73.0753 -17.7654,
+                          80.5996 77.4356 -34.4485,
+                          81.999 73.0753 -17.7654,
+                          85.3657 88.7782 -21.1588,
+                          80.9495 65.0305 -32.1047,
+                          81.999 73.0753 -17.7654,
+                          80.5996 77.4356 -34.4485,
+                          81.999 78.8744 18.9825,
+                          81.999 80.8428 2.63387,
+                          81.999 78.3755 -8.11303,
+                          85.6589 89.7553 -19.3134,
+                          81.999 78.3755 -8.11303,
+                          81.999 80.8428 2.63387,
+                          85.3657 88.7782 -21.1588,
+                          81.999 78.3755 -8.11303,
+                          85.6589 89.7553 -19.3134,
+                          85.9406 95.5969 4.24845,
+                          81.999 80.8428 2.63387,
+                          81.999 78.8744 18.9825,
+                          85.6589 89.7553 -19.3134,
+                          81.999 80.8428 2.63387,
+                          85.9406 95.5969 4.24845,
+                          84.9056 87.7317 32.054,
+                          81.999 78.8744 18.9825,
+                          81.999 70.489 33.1483,
+                          85.2037 93.7307 18.016,
+                          81.999 78.8744 18.9825,
+                          84.9056 87.7317 32.054,
+                          85.9406 95.5969 4.24845,
+                          81.999 78.8744 18.9825,
+                          85.2037 93.7307 18.016,
+                          84.9286 77.3031 44.9498,
+                          81.999 70.489 33.1483,
+                          81.999 57.1023 42.7408,
+                          84.9056 87.7317 32.054,
+                          81.999 70.489 33.1483,
+                          84.9286 77.3031 44.9498,
+                          84.9577 67.098 52.3178,
+                          81.999 57.1023 42.7408,
+                          84.9127 54.2367 57.4132,
+                          84.9286 77.3031 44.9498,
+                          81.999 57.1023 42.7408,
+                          84.9577 67.098 52.3178,
+                          -110.001 49.8108 -33.534,
+                          -110.001 42.5981 16.576,
+                          -110.001 50.6687 17.8527,
+                          -109.762 50.6687 19.0259,
+                          -110.001 50.6687 17.8527,
+                          -110.001 42.5981 16.576,
+                          -110.001 61.3667 15.547,
+                          -110.001 49.8108 -33.534,
+                          -110.001 50.6687 17.8527,
+                          -108.893 60.2064 18.5269,
+                          -110.001 61.3667 15.547,
+                          -110.001 50.6687 17.8527,
+                          -108.893 60.2064 18.5269,
+                          -110.001 50.6687 17.8527,
+                          -108.949 57.9848 19.1726,
+                          -109.762 50.6687 19.0259,
+                          -108.949 57.9848 19.1726,
+                          -110.001 50.6687 17.8527,
+                          -110.001 42.0443 -32.3406,
+                          -110.001 31.8272 9.87052,
+                          -110.001 42.5981 16.576,
+                          -109.172 41.9596 18.5463,
+                          -110.001 42.5981 16.576,
+                          -110.001 31.8272 9.87052,
+                          -110.001 49.8108 -33.534,
+                          -110.001 42.0443 -32.3406,
+                          -110.001 42.5981 16.576,
+                          -109.132 46.6503 19.6764,
+                          -109.083 50.6687 20.0122,
+                          -110.001 42.5981 16.576,
+                          -109.762 50.6687 19.0259,
+                          -110.001 42.5981 16.576,
+                          -109.083 50.6687 20.0122,
+                          -109.132 46.6503 19.6764,
+                          -110.001 42.5981 16.576,
+                          -109.172 41.9596 18.5463,
+                          -110.001 31.625 -25.9515,
+                          -110.001 24.4545 -8.22826,
+                          -110.001 31.8272 9.87052,
+                          -109.181 30.3508 11.3039,
+                          -110.001 31.8272 9.87052,
+                          -110.001 24.4545 -8.22826,
+                          -110.001 42.0443 -32.3406,
+                          -110.001 31.625 -25.9515,
+                          -110.001 31.8272 9.87052,
+                          -109.194 36.4393 16.0523,
+                          -110.001 31.8272 9.87052,
+                          -109.181 30.3508 11.3039,
+                          -109.172 41.9596 18.5463,
+                          -110.001 31.8272 9.87052,
+                          -109.194 36.4393 16.0523,
+                          -109.006 24.0184 -18.0865,
+                          -110.001 24.4545 -8.22826,
+                          -110.001 31.625 -25.9515,
+                          -109.034 23.3807 -0.373823,
+                          -110.001 24.4545 -8.22826,
+                          -109.011 23.0314 -1.59438,
+                          -109.006 24.0184 -18.0865,
+                          -109.011 23.0314 -1.59438,
+                          -110.001 24.4545 -8.22826,
+                          -109.135 26.4407 6.32377,
+                          -110.001 24.4545 -8.22826,
+                          -109.034 23.3807 -0.373823,
+                          -109.181 30.3508 11.3039,
+                          -110.001 24.4545 -8.22826,
+                          -109.135 26.4407 6.32377,
+                          -109.006 34.1724 -30.9769,
+                          -110.001 31.625 -25.9515,
+                          -110.001 42.0443 -32.3406,
+                          -109.006 34.1724 -30.9769,
+                          -109.006 24.0184 -18.0865,
+                          -110.001 31.625 -25.9515,
+                          -109.006 34.1724 -30.9769,
+                          -110.001 42.0443 -32.3406,
+                          -110.001 49.8108 -33.534,
+                          -110.001 61.3667 15.547,
+                          -110.001 65.6149 -28.2639,
+                          -110.001 49.8108 -33.534,
+                          -109.006 49.8108 -35.7655,
+                          -110.001 49.8108 -33.534,
+                          -110.001 65.6149 -28.2639,
+                          -109.006 34.1724 -30.9769,
+                          -110.001 49.8108 -33.534,
+                          -109.006 49.8108 -35.7655,
+                          -110.001 69.9395 9.2146,
+                          -110.001 72.8235 -20.1051,
+                          -110.001 65.6149 -28.2639,
+                          -108.886 67.9516 -29.408,
+                          -110.001 65.6149 -28.2639,
+                          -110.001 72.8235 -20.1051,
+                          -110.001 61.3667 15.547,
+                          -110.001 69.9395 9.2146,
+                          -110.001 65.6149 -28.2639,
+                          -108.886 49.8108 -35.8679,
+                          -110.001 65.6149 -28.2639,
+                          -108.886 67.9516 -29.408,
+                          -109.006 49.8108 -35.7655,
+                          -110.001 65.6149 -28.2639,
+                          -108.886 49.8108 -35.8679,
+                          -110.001 75.0244 0.237638,
+                          -110.001 76.0677 -9.99524,
+                          -110.001 72.8235 -20.1051,
+                          -108.886 77.9717 -12.957,
+                          -110.001 72.8235 -20.1051,
+                          -110.001 76.0677 -9.99524,
+                          -110.001 69.9395 9.2146,
+                          -110.001 75.0244 0.237638,
+                          -110.001 72.8235 -20.1051,
+                          -108.886 67.9516 -29.408,
+                          -110.001 72.8235 -20.1051,
+                          -108.886 77.9717 -12.957,
+                          -108.886 77.9717 -12.957,
+                          -110.001 76.0677 -9.99524,
+                          -110.001 75.0244 0.237638,
+                          -108.886 75.0168 6.07596,
+                          -110.001 75.0244 0.237638,
+                          -110.001 69.9395 9.2146,
+                          -108.886 77.9717 -12.957,
+                          -110.001 75.0244 0.237638,
+                          -108.886 75.0168 6.07596,
+                          -108.886 75.0168 6.07596,
+                          -110.001 69.9395 9.2146,
+                          -110.001 61.3667 15.547,
+                          -108.886 75.0168 6.07596,
+                          -110.001 61.3667 15.547,
+                          -108.893 60.2064 18.5269,
+                          -82.001 53.8534 -31.75,
+                          -82.001 57.1023 42.7408,
+                          -82.001 40.9964 46.1274,
+                          -84.4615 40.8107 52.295,
+                          -82.001 40.9964 46.1274,
+                          -82.001 57.1023 42.7408,
+                          -82.001 47.5146 -33.3379,
+                          -82.001 53.8534 -31.75,
+                          -82.001 40.9964 46.1274,
+                          -82.001 40.9964 -33.8726,
+                          -82.001 47.5146 -33.3379,
+                          -82.001 40.9964 46.1274,
+                          -82.001 24.7769 42.6906,
+                          -82.001 40.9964 -33.8726,
+                          -82.001 40.9964 46.1274,
+                          -84.2967 19.7488 53.6572,
+                          -82.001 24.7769 42.6906,
+                          -82.001 40.9964 46.1274,
+                          -84.2967 19.7488 53.6572,
+                          -82.001 40.9964 46.1274,
+                          -84.5852 30.4841 57.6103,
+                          -84.4615 40.8107 52.295,
+                          -84.5852 30.4841 57.6103,
+                          -82.001 40.9964 46.1274,
+                          -82.001 65.3401 -25.6119,
+                          -82.001 70.489 33.1483,
+                          -82.001 57.1023 42.7408,
+                          -84.9597 67.098 52.3178,
+                          -82.001 57.1023 42.7408,
+                          -82.001 70.489 33.1483,
+                          -82.001 59.8487 -29.1514,
+                          -82.001 65.3401 -25.6119,
+                          -82.001 57.1023 42.7408,
+                          -82.001 53.8534 -31.75,
+                          -82.001 59.8487 -29.1514,
+                          -82.001 57.1023 42.7408,
+                          -84.9147 54.2367 57.4132,
+                          -82.001 57.1023 42.7408,
+                          -84.9597 67.098 52.3178,
+                          -84.7656 40.6455 58.9289,
+                          -82.001 57.1023 42.7408,
+                          -84.9147 54.2367 57.4132,
+                          -84.4615 40.8107 52.295,
+                          -82.001 57.1023 42.7408,
+                          -84.7656 40.6455 58.9289,
+                          -82.001 78.3755 -8.11303,
+                          -82.001 78.8744 18.9825,
+                          -82.001 70.489 33.1483,
+                          -84.9077 87.7317 32.054,
+                          -82.001 70.489 33.1483,
+                          -82.001 78.8744 18.9825,
+                          -82.001 73.0753 -17.7654,
+                          -82.001 78.3755 -8.11303,
+                          -82.001 70.489 33.1483,
+                          -82.001 65.3401 -25.6119,
+                          -82.001 73.0753 -17.7654,
+                          -82.001 70.489 33.1483,
+                          -84.9597 67.098 52.3178,
+                          -82.001 70.489 33.1483,
+                          -84.9306 77.3031 44.9498,
+                          -84.9077 87.7317 32.054,
+                          -84.9306 77.3031 44.9498,
+                          -82.001 70.489 33.1483,
+                          -82.001 78.3755 -8.11303,
+                          -82.001 80.8428 2.63387,
+                          -82.001 78.8744 18.9825,
+                          -85.2058 93.7307 18.016,
+                          -82.001 78.8744 18.9825,
+                          -82.001 80.8428 2.63387,
+                          -84.9077 87.7317 32.054,
+                          -82.001 78.8744 18.9825,
+                          -85.2058 93.7307 18.016,
+                          -85.9426 95.5969 4.24845,
+                          -82.001 80.8428 2.63387,
+                          -82.001 78.3755 -8.11303,
+                          -85.2058 93.7307 18.016,
+                          -82.001 80.8428 2.63387,
+                          -85.9426 95.5969 4.24845,
+                          -85.6609 89.7553 -19.3134,
+                          -82.001 78.3755 -8.11303,
+                          -82.001 73.0753 -17.7654,
+                          -85.9426 95.5969 4.24845,
+                          -82.001 78.3755 -8.11303,
+                          -85.6609 89.7553 -19.3134,
+                          -80.6016 77.4356 -34.4485,
+                          -82.001 73.0753 -17.7654,
+                          -82.001 65.3401 -25.6119,
+                          -85.6609 89.7553 -19.3134,
+                          -82.001 73.0753 -17.7654,
+                          -85.3677 88.7782 -21.1588,
+                          -80.6016 77.4356 -34.4485,
+                          -85.3677 88.7782 -21.1588,
+                          -82.001 73.0753 -17.7654,
+                          -92.9748 65.1012 -28.7062,
+                          -82.001 65.3401 -25.6119,
+                          -82.001 59.8487 -29.1514,
+                          -90.2975 64.9173 -32.5566,
+                          -82.001 65.3401 -25.6119,
+                          -92.9748 65.1012 -28.7062,
+                          -80.9515 65.0305 -32.1047,
+                          -80.6016 77.4356 -34.4485,
+                          -82.001 65.3401 -25.6119,
+                          -80.9515 65.0305 -32.1047,
+                          -82.001 65.3401 -25.6119,
+                          -90.2975 64.9173 -32.5566,
+                          -106.429 59.3252 -34.8844,
+                          -82.001 59.8487 -29.1514,
+                          -82.001 53.8534 -31.75,
+                          -103.367 64.9061 -31.516,
+                          -92.9748 65.1012 -28.7062,
+                          -82.001 59.8487 -29.1514,
+                          -106.372 64.8029 -32.3337,
+                          -103.367 64.9061 -31.516,
+                          -82.001 59.8487 -29.1514,
+                          -106.429 59.3252 -34.8844,
+                          -106.372 64.8029 -32.3337,
+                          -82.001 59.8487 -29.1514,
+                          -106.429 59.3252 -34.8844,
+                          -82.001 53.8534 -31.75,
+                          -82.001 47.5146 -33.3379,
+                          -106.542 54.2085 -36.1646,
+                          -82.001 47.5146 -33.3379,
+                          -82.001 40.9964 -33.8726,
+                          -106.542 54.2085 -36.1646,
+                          -106.429 59.3252 -34.8844,
+                          -82.001 47.5146 -33.3379,
+                          -82.001 24.7769 42.6906,
+                          -82.001 30.8575 -32.5654,
+                          -82.001 40.9964 -33.8726,
+                          -106.681 49.8108 -36.5169,
+                          -82.001 40.9964 -33.8726,
+                          -82.001 30.8575 -32.5654,
+                          -106.681 49.8108 -36.5169,
+                          -106.542 54.2085 -36.1646,
+                          -82.001 40.9964 -33.8726,
+                          -82.001 24.7769 42.6906,
+                          -82.001 21.3771 -28.7305,
+                          -82.001 30.8575 -32.5654,
+                          -107.077 41.1406 -35.2007,
+                          -82.001 30.8575 -32.5654,
+                          -82.001 21.3771 -28.7305,
+                          -106.843 45.8108 -36.2525,
+                          -106.681 49.8108 -36.5169,
+                          -82.001 30.8575 -32.5654,
+                          -107.077 41.1406 -35.2007,
+                          -106.843 45.8108 -36.2525,
+                          -82.001 30.8575 -32.5654,
+                          -82.001 11.3339 32.9628,
+                          -82.001 13.1869 -22.6229,
+                          -82.001 21.3771 -28.7305,
+                          -107.419 35.6265 -32.757,
+                          -82.001 21.3771 -28.7305,
+                          -82.001 13.1869 -22.6229,
+                          -82.001 24.7769 42.6906,
+                          -82.001 11.3339 32.9628,
+                          -82.001 21.3771 -28.7305,
+                          -107.419 35.6265 -32.757,
+                          -107.077 41.1406 -35.2007,
+                          -82.001 21.3771 -28.7305,
+                          -82.001 11.3339 32.9628,
+                          -82.001 6.80462 -14.6305,
+                          -82.001 13.1869 -22.6229,
+                          -107.888 29.5793 -27.9546,
+                          -82.001 13.1869 -22.6229,
+                          -82.001 6.80462 -14.6305,
+                          -107.888 29.5793 -27.9546,
+                          -107.419 35.6265 -32.757,
+                          -82.001 13.1869 -22.6229,
+                          -82.001 5.50284 24.5702,
+                          -82.001 2.6621 -5.29399,
+                          -82.001 6.80462 -14.6305,
+                          -108.244 25.8058 -22.8779,
+                          -82.001 6.80462 -14.6305,
+                          -82.001 2.6621 -5.29399,
+                          -82.001 11.3339 32.9628,
+                          -82.001 5.50284 24.5702,
+                          -82.001 6.80462 -14.6305,
+                          -108.244 25.8058 -22.8779,
+                          -107.888 29.5793 -27.9546,
+                          -82.001 6.80462 -14.6305,
+                          -82.001 1.98608 14.9697,
+                          -82.001 1.01913 4.80039,
+                          -82.001 2.6621 -5.29399,
+                          -108.585 23.0226 -16.1054,
+                          -82.001 2.6621 -5.29399,
+                          -82.001 1.01913 4.80039,
+                          -82.001 5.50284 24.5702,
+                          -82.001 1.98608 14.9697,
+                          -82.001 2.6621 -5.29399,
+                          -108.585 23.0226 -16.1054,
+                          -108.244 25.8058 -22.8779,
+                          -82.001 2.6621 -5.29399,
+                          -108.855 22.0962 -8.22725,
+                          -82.001 1.01913 4.80039,
+                          -82.001 1.98608 14.9697,
+                          -108.855 22.0962 -8.22725,
+                          -108.585 23.0226 -16.1054,
+                          -82.001 1.01913 4.80039,
+                          -109.011 23.0314 -1.59438,
+                          -82.001 1.98608 14.9697,
+                          -82.001 5.50284 24.5702,
+                          -109.011 23.0314 -1.59438,
+                          -108.855 22.0962 -8.22725,
+                          -82.001 1.98608 14.9697,
+                          -109.135 26.4407 6.32377,
+                          -82.001 5.50284 24.5702,
+                          -82.001 11.3339 32.9628,
+                          -109.034 23.3807 -0.373823,
+                          -109.011 23.0314 -1.59438,
+                          -82.001 5.50284 24.5702,
+                          -109.135 26.4407 6.32377,
+                          -109.034 23.3807 -0.373823,
+                          -82.001 5.50284 24.5702,
+                          -83.3216 7.94414 36.2744,
+                          -82.001 11.3339 32.9628,
+                          -82.001 24.7769 42.6906,
+                          -109.135 26.4407 6.32377,
+                          -82.001 11.3339 32.9628,
+                          -83.6226 12.4637 31.6668,
+                          -84.7175 11.599 32.4235,
+                          -83.6226 12.4637 31.6668,
+                          -82.001 11.3339 32.9628,
+                          -84.1508 8.15085 35.9712,
+                          -84.7175 11.599 32.4235,
+                          -82.001 11.3339 32.9628,
+                          -83.3216 7.94414 36.2744,
+                          -84.1508 8.15085 35.9712,
+                          -82.001 11.3339 32.9628,
+                          -83.3861 3.87721 40.5514,
+                          -82.001 24.7769 42.6906,
+                          -84.2967 19.7488 53.6572,
+                          -83.4462 4.21515 40.1792,
+                          -82.001 24.7769 42.6906,
+                          -83.3861 3.87721 40.5514,
+                          -83.3216 7.94414 36.2744,
+                          -82.001 24.7769 42.6906,
+                          -83.494 4.55423 39.8092,
+                          -83.4462 4.21515 40.1792,
+                          -83.494 4.55423 39.8092,
+                          -82.001 24.7769 42.6906,
+                          104.118 78.1613 2.94008,
+                          107.677 78.0494 0.327132,
+                          107.254 79.1829 -6.65619,
+                          108.884 77.9717 -12.957,
+                          107.254 79.1829 -6.65619,
+                          107.677 78.0494 0.327132,
+                          91.146 83.0248 15.7651,
+                          104.118 78.1613 2.94008,
+                          107.254 79.1829 -6.65619,
+                          107.043 76.9716 -18.4509,
+                          107.254 79.1829 -6.65619,
+                          108.884 77.9717 -12.957,
+                          94.4943 82.2003 -18.3975,
+                          107.254 79.1829 -6.65619,
+                          107.043 76.9716 -18.4509,
+                          95.084 84.6951 -6.36765,
+                          107.254 79.1829 -6.65619,
+                          94.4943 82.2003 -18.3975,
+                          91.146 83.0248 15.7651,
+                          107.254 79.1829 -6.65619,
+                          95.084 84.6951 -6.36765,
+                          104.118 78.1613 2.94008,
+                          108.095 75.1545 6.75687,
+                          107.677 78.0494 0.327132,
+                          108.884 75.0168 6.07596,
+                          107.677 78.0494 0.327132,
+                          108.095 75.1545 6.75687,
+                          108.884 75.0168 6.07596,
+                          108.884 77.9717 -12.957,
+                          107.677 78.0494 0.327132,
+                          100.983 74.9542 12.591,
+                          108.458 70.6551 12.2756,
+                          108.095 75.1545 6.75687,
+                          108.884 75.0168 6.07596,
+                          108.095 75.1545 6.75687,
+                          108.458 70.6551 12.2756,
+                          104.118 78.1613 2.94008,
+                          100.983 74.9542 12.591,
+                          108.095 75.1545 6.75687,
+                          98.7555 69.8258 20.7127,
+                          108.743 64.806 16.5218,
+                          108.458 70.6551 12.2756,
+                          108.884 75.0168 6.07596,
+                          108.458 70.6551 12.2756,
+                          108.743 64.806 16.5218,
+                          100.983 74.9542 12.591,
+                          98.7555 69.8258 20.7127,
+                          108.458 70.6551 12.2756,
+                          97.1537 62.9266 27.1594,
+                          108.891 60.2064 18.5269,
+                          108.743 64.806 16.5218,
+                          108.884 75.0168 6.07596,
+                          108.743 64.806 16.5218,
+                          108.891 60.2064 18.5269,
+                          98.7555 69.8258 20.7127,
+                          97.1537 62.9266 27.1594,
+                          108.743 64.806 16.5218,
+                          96.0172 54.9653 31.407,
+                          108.947 57.9848 19.1726,
+                          108.891 60.2064 18.5269,
+                          97.1537 62.9266 27.1594,
+                          96.0172 54.9653 31.407,
+                          108.891 60.2064 18.5269,
+                          95.1191 45.6821 33.4759,
+                          109.081 50.6687 20.0122,
+                          108.947 57.9848 19.1726,
+                          96.0172 54.9653 31.407,
+                          95.1191 45.6821 33.4759,
+                          108.947 57.9848 19.1726,
+                          94.6391 39.5033 33.4129,
+                          109.081 50.6687 20.0122,
+                          95.1191 45.6821 33.4759,
+                          109.13 46.6503 19.6764,
+                          109.081 50.6687 20.0122,
+                          94.6391 39.5033 33.4129,
+                          109.76 50.6687 19.0259,
+                          109.081 50.6687 20.0122,
+                          109.13 46.6503 19.6764,
+                          90.9162 45.7361 39.3341,
+                          95.1191 45.6821 33.4759,
+                          96.0172 54.9653 31.407,
+                          88.9881 38.6057 45.8589,
+                          94.6391 39.5033 33.4129,
+                          95.1191 45.6821 33.4759,
+                          90.9162 45.7361 39.3341,
+                          88.9881 38.6057 45.8589,
+                          95.1191 45.6821 33.4759,
+                          89.1516 45.7781 45.4317,
+                          96.0172 54.9653 31.407,
+                          97.1537 62.9266 27.1594,
+                          90.9162 45.7361 39.3341,
+                          96.0172 54.9653 31.407,
+                          89.1516 45.7781 45.4317,
+                          89.5701 69.2939 35.9017,
+                          97.1537 62.9266 27.1594,
+                          98.7555 69.8258 20.7127,
+                          89.1516 45.7781 45.4317,
+                          97.1537 62.9266 27.1594,
+                          89.5701 69.2939 35.9017,
+                          89.5701 69.2939 35.9017,
+                          98.7555 69.8258 20.7127,
+                          100.983 74.9542 12.591,
+                          91.146 83.0248 15.7651,
+                          100.983 74.9542 12.591,
+                          104.118 78.1613 2.94008,
+                          89.5701 69.2939 35.9017,
+                          100.983 74.9542 12.591,
+                          91.146 83.0248 15.7651,
+                          108.884 49.8108 -35.8679,
+                          106.679 49.8108 -36.5169,
+                          106.54 54.2085 -36.1646,
+                          109.004 34.1724 -30.9769,
+                          106.841 45.8108 -36.2525,
+                          106.679 49.8108 -36.5169,
+                          109.004 34.1724 -30.9769,
+                          106.679 49.8108 -36.5169,
+                          108.884 49.8108 -35.8679,
+                          108.884 49.8108 -35.8679,
+                          106.54 54.2085 -36.1646,
+                          106.427 59.3252 -34.8844,
+                          108.884 49.8108 -35.8679,
+                          106.427 59.3252 -34.8844,
+                          106.37 64.8029 -32.3337,
+                          104.987 67.7007 -29.9964,
+                          106.396 70.1433 -28.2805,
+                          106.37 64.8029 -32.3337,
+                          108.884 67.9516 -29.408,
+                          106.37 64.8029 -32.3337,
+                          106.396 70.1433 -28.2805,
+                          103.365 64.9061 -31.516,
+                          104.987 67.7007 -29.9964,
+                          106.37 64.8029 -32.3337,
+                          108.884 67.9516 -29.408,
+                          108.884 49.8108 -35.8679,
+                          106.37 64.8029 -32.3337,
+                          90.2955 64.9173 -32.5566,
+                          106.396 70.1433 -28.2805,
+                          104.987 67.7007 -29.9964,
+                          107.03 76.8374 -18.7668,
+                          108.884 67.9516 -29.408,
+                          106.396 70.1433 -28.2805,
+                          93.2656 74.4775 -27.1937,
+                          107.03 76.8374 -18.7668,
+                          106.396 70.1433 -28.2805,
+                          93.2656 74.4775 -27.1937,
+                          106.396 70.1433 -28.2805,
+                          90.2955 64.9173 -32.5566,
+                          90.2955 64.9173 -32.5566,
+                          104.987 67.7007 -29.9964,
+                          103.365 64.9061 -31.516,
+                          109.179 30.3508 11.3039,
+                          88.9708 16.9049 28.1475,
+                          85.203 13.5747 30.4113,
+                          84.9146 12.5877 31.4178,
+                          85.203 13.5747 30.4113,
+                          88.9708 16.9049 28.1475,
+                          109.133 26.4407 6.32377,
+                          109.179 30.3508 11.3039,
+                          85.203 13.5747 30.4113,
+                          83.6206 12.4637 31.6668,
+                          109.133 26.4407 6.32377,
+                          85.203 13.5747 30.4113,
+                          84.9146 12.5877 31.4178,
+                          83.6206 12.4637 31.6668,
+                          85.203 13.5747 30.4113,
+                          109.179 30.3508 11.3039,
+                          91.0777 19.1986 27.2797,
+                          88.9708 16.9049 28.1475,
+                          86.9024 11.9664 33.1138,
+                          88.9708 16.9049 28.1475,
+                          91.0777 19.1986 27.2797,
+                          84.9146 12.5877 31.4178,
+                          88.9708 16.9049 28.1475,
+                          84.7154 11.599 32.4235,
+                          86.9024 11.9664 33.1138,
+                          84.7154 11.599 32.4235,
+                          88.9708 16.9049 28.1475,
+                          109.192 36.4393 16.0523,
+                          93.3136 21.8556 26.4894,
+                          91.0777 19.1986 27.2797,
+                          89.5973 17.7899 30.2975,
+                          91.0777 19.1986 27.2797,
+                          93.3136 21.8556 26.4894,
+                          109.179 30.3508 11.3039,
+                          109.192 36.4393 16.0523,
+                          91.0777 19.1986 27.2797,
+                          86.9024 11.9664 33.1138,
+                          91.0777 19.1986 27.2797,
+                          89.5973 17.7899 30.2975,
+                          109.192 36.4393 16.0523,
+                          93.7493 27.2419 29.8367,
+                          93.3136 21.8556 26.4894,
+                          87.9036 13.3689 34.6449,
+                          93.3136 21.8556 26.4894,
+                          93.7493 27.2419 29.8367,
+                          89.5973 17.7899 30.2975,
+                          93.3136 21.8556 26.4894,
+                          87.9036 13.3689 34.6449,
+                          109.192 36.4393 16.0523,
+                          94.1873 33.2251 32.1924,
+                          93.7493 27.2419 29.8367,
+                          88.7442 28.4697 43.3876,
+                          93.7493 27.2419 29.8367,
+                          94.1873 33.2251 32.1924,
+                          87.9036 13.3689 34.6449,
+                          93.7493 27.2419 29.8367,
+                          88.7442 28.4697 43.3876,
+                          109.17 41.9596 18.5463,
+                          94.6391 39.5033 33.4129,
+                          94.1873 33.2251 32.1924,
+                          88.7442 28.4697 43.3876,
+                          94.1873 33.2251 32.1924,
+                          94.6391 39.5033 33.4129,
+                          109.192 36.4393 16.0523,
+                          109.17 41.9596 18.5463,
+                          94.1873 33.2251 32.1924,
+                          109.17 41.9596 18.5463,
+                          109.13 46.6503 19.6764,
+                          94.6391 39.5033 33.4129,
+                          88.7442 28.4697 43.3876,
+                          94.6391 39.5033 33.4129,
+                          88.9881 38.6057 45.8589,
+                          109.004 24.0184 -18.0865,
+                          109.009 23.0314 -1.59438,
+                          108.853 22.0962 -8.22725,
+                          109.004 24.0184 -18.0865,
+                          108.853 22.0962 -8.22725,
+                          108.583 23.0226 -16.1054,
+                          109.004 24.0184 -18.0865,
+                          108.583 23.0226 -16.1054,
+                          108.242 25.8058 -22.8779,
+                          109.004 24.0184 -18.0865,
+                          108.242 25.8058 -22.8779,
+                          107.886 29.5793 -27.9546,
+                          109.004 34.1724 -30.9769,
+                          107.886 29.5793 -27.9546,
+                          107.417 35.6265 -32.757,
+                          109.004 24.0184 -18.0865,
+                          107.886 29.5793 -27.9546,
+                          109.004 34.1724 -30.9769,
+                          109.004 34.1724 -30.9769,
+                          107.417 35.6265 -32.757,
+                          107.075 41.1406 -35.2007,
+                          109.004 34.1724 -30.9769,
+                          107.075 41.1406 -35.2007,
+                          106.841 45.8108 -36.2525,
+                          84.9146 12.5877 31.4178,
+                          84.7154 11.599 32.4235,
+                          83.6206 12.4637 31.6668,
+                          -107.679 78.0494 0.327132,
+                          -104.12 78.1613 2.94008,
+                          -107.256 79.1829 -6.65619,
+                          -95.0861 84.6951 -6.36765,
+                          -107.256 79.1829 -6.65619,
+                          -104.12 78.1613 2.94008,
+                          -108.886 75.0168 6.07596,
+                          -107.679 78.0494 0.327132,
+                          -107.256 79.1829 -6.65619,
+                          -108.886 77.9717 -12.957,
+                          -107.256 79.1829 -6.65619,
+                          -107.045 76.9716 -18.4509,
+                          -95.0861 84.6951 -6.36765,
+                          -107.045 76.9716 -18.4509,
+                          -107.256 79.1829 -6.65619,
+                          -108.886 77.9717 -12.957,
+                          -108.886 75.0168 6.07596,
+                          -107.256 79.1829 -6.65619,
+                          -108.097 75.1545 6.75687,
+                          -100.985 74.9542 12.591,
+                          -104.12 78.1613 2.94008,
+                          -91.148 83.0248 15.7651,
+                          -104.12 78.1613 2.94008,
+                          -100.985 74.9542 12.591,
+                          -107.679 78.0494 0.327132,
+                          -108.097 75.1545 6.75687,
+                          -104.12 78.1613 2.94008,
+                          -91.148 83.0248 15.7651,
+                          -95.0861 84.6951 -6.36765,
+                          -104.12 78.1613 2.94008,
+                          -108.46 70.6551 12.2756,
+                          -98.7575 69.8258 20.7127,
+                          -100.985 74.9542 12.591,
+                          -91.148 83.0248 15.7651,
+                          -100.985 74.9542 12.591,
+                          -98.7575 69.8258 20.7127,
+                          -108.097 75.1545 6.75687,
+                          -108.46 70.6551 12.2756,
+                          -100.985 74.9542 12.591,
+                          -108.745 64.806 16.5218,
+                          -97.1557 62.9266 27.1594,
+                          -98.7575 69.8258 20.7127,
+                          -89.5722 69.2939 35.9017,
+                          -98.7575 69.8258 20.7127,
+                          -97.1557 62.9266 27.1594,
+                          -108.46 70.6551 12.2756,
+                          -108.745 64.806 16.5218,
+                          -98.7575 69.8258 20.7127,
+                          -91.148 83.0248 15.7651,
+                          -98.7575 69.8258 20.7127,
+                          -89.5722 69.2939 35.9017,
+                          -108.893 60.2064 18.5269,
+                          -96.0193 54.9653 31.407,
+                          -97.1557 62.9266 27.1594,
+                          -89.5722 69.2939 35.9017,
+                          -97.1557 62.9266 27.1594,
+                          -96.0193 54.9653 31.407,
+                          -108.745 64.806 16.5218,
+                          -108.893 60.2064 18.5269,
+                          -97.1557 62.9266 27.1594,
+                          -109.083 50.6687 20.0122,
+                          -95.1211 45.6821 33.4759,
+                          -96.0193 54.9653 31.407,
+                          -89.5722 69.2939 35.9017,
+                          -96.0193 54.9653 31.407,
+                          -95.1211 45.6821 33.4759,
+                          -108.949 57.9848 19.1726,
+                          -109.083 50.6687 20.0122,
+                          -96.0193 54.9653 31.407,
+                          -108.893 60.2064 18.5269,
+                          -108.949 57.9848 19.1726,
+                          -96.0193 54.9653 31.407,
+                          -109.132 46.6503 19.6764,
+                          -95.1211 45.6821 33.4759,
+                          -109.083 50.6687 20.0122,
+                          -109.132 46.6503 19.6764,
+                          -94.6411 39.5033 33.4129,
+                          -95.1211 45.6821 33.4759,
+                          -90.9182 45.7361 39.3341,
+                          -95.1211 45.6821 33.4759,
+                          -94.6411 39.5033 33.4129,
+                          -90.9182 45.7361 39.3341,
+                          -89.5722 69.2939 35.9017,
+                          -95.1211 45.6821 33.4759,
+                          -109.762 50.6687 19.0259,
+                          -109.083 50.6687 20.0122,
+                          -108.949 57.9848 19.1726,
+                          -108.886 75.0168 6.07596,
+                          -108.893 60.2064 18.5269,
+                          -108.745 64.806 16.5218,
+                          -108.886 75.0168 6.07596,
+                          -108.745 64.806 16.5218,
+                          -108.46 70.6551 12.2756,
+                          -108.886 75.0168 6.07596,
+                          -108.46 70.6551 12.2756,
+                          -108.097 75.1545 6.75687,
+                          -108.886 75.0168 6.07596,
+                          -108.097 75.1545 6.75687,
+                          -107.679 78.0494 0.327132,
+                          -90.2975 64.9173 -32.5566,
+                          -92.9748 65.1012 -28.7062,
+                          -103.367 64.9061 -31.516,
+                          -106.372 64.8029 -32.3337,
+                          -104.989 67.7007 -29.9964,
+                          -103.367 64.9061 -31.516,
+                          -90.2975 64.9173 -32.5566,
+                          -103.367 64.9061 -31.516,
+                          -104.989 67.7007 -29.9964,
+                          -106.372 64.8029 -32.3337,
+                          -106.398 70.1433 -28.2805,
+                          -104.989 67.7007 -29.9964,
+                          -93.2676 74.4775 -27.1937,
+                          -104.989 67.7007 -29.9964,
+                          -106.398 70.1433 -28.2805,
+                          -93.2676 74.4775 -27.1937,
+                          -90.2975 64.9173 -32.5566,
+                          -104.989 67.7007 -29.9964,
+                          -108.886 67.9516 -29.408,
+                          -106.398 70.1433 -28.2805,
+                          -106.372 64.8029 -32.3337,
+                          -108.886 77.9717 -12.957,
+                          -107.032 76.8374 -18.7668,
+                          -106.398 70.1433 -28.2805,
+                          -94.4964 82.2003 -18.3975,
+                          -106.398 70.1433 -28.2805,
+                          -107.032 76.8374 -18.7668,
+                          -108.886 67.9516 -29.408,
+                          -108.886 77.9717 -12.957,
+                          -106.398 70.1433 -28.2805,
+                          -94.4964 82.2003 -18.3975,
+                          -93.2676 74.4775 -27.1937,
+                          -106.398 70.1433 -28.2805,
+                          -108.886 67.9516 -29.408,
+                          -106.372 64.8029 -32.3337,
+                          -106.429 59.3252 -34.8844,
+                          -108.886 67.9516 -29.408,
+                          -106.429 59.3252 -34.8844,
+                          -106.542 54.2085 -36.1646,
+                          -108.886 67.9516 -29.408,
+                          -106.542 54.2085 -36.1646,
+                          -106.681 49.8108 -36.5169,
+                          -108.886 49.8108 -35.8679,
+                          -106.681 49.8108 -36.5169,
+                          -106.843 45.8108 -36.2525,
+                          -108.886 49.8108 -35.8679,
+                          -108.886 67.9516 -29.408,
+                          -106.681 49.8108 -36.5169,
+                          -109.172 41.9596 18.5463,
+                          -94.1893 33.2251 32.1924,
+                          -94.6411 39.5033 33.4129,
+                          -88.9901 38.6057 45.8589,
+                          -94.6411 39.5033 33.4129,
+                          -94.1893 33.2251 32.1924,
+                          -109.132 46.6503 19.6764,
+                          -109.172 41.9596 18.5463,
+                          -94.6411 39.5033 33.4129,
+                          -89.0659 45.7831 46.302,
+                          -94.6411 39.5033 33.4129,
+                          -88.9901 38.6057 45.8589,
+                          -89.1536 45.7781 45.4317,
+                          -94.6411 39.5033 33.4129,
+                          -89.0659 45.7831 46.302,
+                          -90.9182 45.7361 39.3341,
+                          -94.6411 39.5033 33.4129,
+                          -89.1536 45.7781 45.4317,
+                          -109.194 36.4393 16.0523,
+                          -93.7514 27.2419 29.8367,
+                          -94.1893 33.2251 32.1924,
+                          -88.7462 28.4697 43.3876,
+                          -94.1893 33.2251 32.1924,
+                          -93.7514 27.2419 29.8367,
+                          -109.172 41.9596 18.5463,
+                          -109.194 36.4393 16.0523,
+                          -94.1893 33.2251 32.1924,
+                          -88.7462 28.4697 43.3876,
+                          -88.9901 38.6057 45.8589,
+                          -94.1893 33.2251 32.1924,
+                          -109.181 30.3508 11.3039,
+                          -93.3156 21.8556 26.4893,
+                          -93.7514 27.2419 29.8367,
+                          -88.7462 28.4697 43.3876,
+                          -93.7514 27.2419 29.8367,
+                          -93.3156 21.8556 26.4893,
+                          -109.194 36.4393 16.0523,
+                          -109.181 30.3508 11.3039,
+                          -93.7514 27.2419 29.8367,
+                          -109.181 30.3508 11.3039,
+                          -91.0786 19.1973 27.2801,
+                          -93.3156 21.8556 26.4893,
+                          -89.5997 17.7905 30.297,
+                          -93.3156 21.8556 26.4893,
+                          -91.0786 19.1973 27.2801,
+                          -89.5997 17.7905 30.297,
+                          -88.7462 28.4697 43.3876,
+                          -93.3156 21.8556 26.4893,
+                          -109.181 30.3508 11.3039,
+                          -88.9756 16.9077 28.1462,
+                          -91.0786 19.1973 27.2801,
+                          -86.9046 11.9664 33.1138,
+                          -91.0786 19.1973 27.2801,
+                          -88.9756 16.9077 28.1462,
+                          -89.5997 17.7905 30.297,
+                          -91.0786 19.1973 27.2801,
+                          -87.9057 13.3688 34.6449,
+                          -86.9046 11.9664 33.1138,
+                          -87.9057 13.3688 34.6449,
+                          -91.0786 19.1973 27.2801,
+                          -109.135 26.4407 6.32377,
+                          -85.205 13.5747 30.4113,
+                          -88.9756 16.9077 28.1462,
+                          -84.9166 12.5877 31.4178,
+                          -88.9756 16.9077 28.1462,
+                          -85.205 13.5747 30.4113,
+                          -109.181 30.3508 11.3039,
+                          -109.135 26.4407 6.32377,
+                          -88.9756 16.9077 28.1462,
+                          -84.7175 11.599 32.4235,
+                          -88.9756 16.9077 28.1462,
+                          -84.9166 12.5877 31.4178,
+                          -86.9046 11.9664 33.1138,
+                          -88.9756 16.9077 28.1462,
+                          -84.7175 11.599 32.4235,
+                          -109.135 26.4407 6.32377,
+                          -83.6226 12.4637 31.6668,
+                          -85.205 13.5747 30.4113,
+                          -84.9166 12.5877 31.4178,
+                          -85.205 13.5747 30.4113,
+                          -83.6226 12.4637 31.6668,
+                          -84.7175 11.599 32.4235,
+                          -84.9166 12.5877 31.4178,
+                          -83.6226 12.4637 31.6668,
+                          -109.006 49.8108 -35.7655,
+                          -106.843 45.8108 -36.2525,
+                          -107.077 41.1406 -35.2007,
+                          -109.006 49.8108 -35.7655,
+                          -108.886 49.8108 -35.8679,
+                          -106.843 45.8108 -36.2525,
+                          -109.006 49.8108 -35.7655,
+                          -107.077 41.1406 -35.2007,
+                          -107.419 35.6265 -32.757,
+                          -109.006 34.1724 -30.9769,
+                          -107.419 35.6265 -32.757,
+                          -107.888 29.5793 -27.9546,
+                          -109.006 34.1724 -30.9769,
+                          -109.006 49.8108 -35.7655,
+                          -107.419 35.6265 -32.757,
+                          -109.006 34.1724 -30.9769,
+                          -107.888 29.5793 -27.9546,
+                          -108.244 25.8058 -22.8779,
+                          -109.006 24.0184 -18.0865,
+                          -108.244 25.8058 -22.8779,
+                          -108.585 23.0226 -16.1054,
+                          -109.006 34.1724 -30.9769,
+                          -108.244 25.8058 -22.8779,
+                          -109.006 24.0184 -18.0865,
+                          -109.006 24.0184 -18.0865,
+                          -108.585 23.0226 -16.1054,
+                          -108.855 22.0962 -8.22725,
+                          -109.006 24.0184 -18.0865,
+                          -108.855 22.0962 -8.22725,
+                          -109.011 23.0314 -1.59438,
+                          109.004 49.8108 -35.7655,
+                          108.884 49.8108 -35.8679,
+                          108.884 67.9516 -29.408,
+                          109.004 34.1724 -30.9769,
+                          108.884 49.8108 -35.8679,
+                          109.004 49.8108 -35.7655,
+                          107.043 76.9716 -18.4509,
+                          108.884 77.9717 -12.957,
+                          108.884 67.9516 -29.408,
+                          107.03 76.8374 -18.7668,
+                          107.043 76.9716 -18.4509,
+                          108.884 67.9516 -29.408,
+                          93.2656 74.4775 -27.1937,
+                          107.043 76.9716 -18.4509,
+                          107.03 76.8374 -18.7668,
+                          94.4943 82.2003 -18.3975,
+                          107.043 76.9716 -18.4509,
+                          93.2656 74.4775 -27.1937,
+                          -108.886 77.9717 -12.957,
+                          -107.045 76.9716 -18.4509,
+                          -107.032 76.8374 -18.7668,
+                          -94.4964 82.2003 -18.3975,
+                          -107.032 76.8374 -18.7668,
+                          -107.045 76.9716 -18.4509,
+                          -95.0861 84.6951 -6.36765,
+                          -94.4964 82.2003 -18.3975,
+                          -107.045 76.9716 -18.4509,
+                          13.9074 26.1377 118.086,
+                          24.1676 42.6026 118.414,
+                          21.999 52.9964 119.008,
+                          21.999 52.9964 115.994,
+                          21.999 52.9964 119.008,
+                          24.1676 42.6026 118.414,
+                          6.83515 70.9964 119.288,
+                          13.9074 26.1377 118.086,
+                          21.999 52.9964 119.008,
+                          23.574 61.9167 118.839,
+                          6.83515 70.9964 119.288,
+                          21.999 52.9964 119.008,
+                          23.3947 61.4103 115.852,
+                          23.574 61.9167 118.839,
+                          21.999 52.9964 119.008,
+                          23.3947 61.4103 115.852,
+                          21.999 52.9964 119.008,
+                          21.999 52.9964 115.994,
+                          13.9074 26.1377 118.086,
+                          30.1039 34.1267 116.914,
+                          24.1676 42.6026 118.414,
+                          29.7658 34.4561 113.947,
+                          24.1676 42.6026 118.414,
+                          30.1039 34.1267 116.914,
+                          24.0457 42.8865 115.419,
+                          24.1676 42.6026 118.414,
+                          29.7658 34.4561 113.947,
+                          21.999 52.9964 115.994,
+                          24.1676 42.6026 118.414,
+                          24.0457 42.8865 115.419,
+                          13.9074 26.1377 118.086,
+                          38.4501 28.8155 114.565,
+                          30.1039 34.1267 116.914,
+                          37.9625 29.013 111.595,
+                          30.1039 34.1267 116.914,
+                          38.4501 28.8155 114.565,
+                          29.7658 34.4561 113.947,
+                          30.1039 34.1267 116.914,
+                          37.9625 29.013 111.595,
+                          42.5845 26.4015 113.101,
+                          48.1095 26.9942 111.391,
+                          38.4501 28.8155 114.565,
+                          47.5034 27.0006 108.385,
+                          38.4501 28.8155 114.565,
+                          48.1095 26.9942 111.391,
+                          13.9074 26.1377 118.086,
+                          42.5845 26.4015 113.101,
+                          38.4501 28.8155 114.565,
+                          37.9625 29.013 111.595,
+                          38.4501 28.8155 114.565,
+                          47.5034 27.0006 108.385,
+                          68.2122 26.8807 100.541,
+                          57.7119 28.8752 107.594,
+                          48.1095 26.9942 111.391,
+                          56.5972 28.4599 104.687,
+                          48.1095 26.9942 111.391,
+                          57.7119 28.8752 107.594,
+                          42.5845 26.4015 113.101,
+                          68.2122 26.8807 100.541,
+                          48.1095 26.9942 111.391,
+                          47.5034 27.0006 108.385,
+                          48.1095 26.9942 111.391,
+                          56.5972 28.4599 104.687,
+                          68.2122 26.8807 100.541,
+                          66.8667 35.1128 102.974,
+                          57.7119 28.8752 107.594,
+                          63.9952 32.502 100.924,
+                          57.7119 28.8752 107.594,
+                          66.8667 35.1128 102.974,
+                          56.5972 28.4599 104.687,
+                          57.7119 28.8752 107.594,
+                          63.9952 32.502 100.924,
+                          68.2122 26.8807 100.541,
+                          72.4035 44.0293 99.2289,
+                          66.8667 35.1128 102.974,
+                          71.6058 42.0986 95.4497,
+                          66.8667 35.1128 102.974,
+                          72.4035 44.0293 99.2289,
+                          63.9952 32.502 100.924,
+                          66.8667 35.1128 102.974,
+                          71.6058 42.0986 95.4497,
+                          84.0925 28.6546 76.0068,
+                          73.999 52.9964 98.1071,
+                          72.4035 44.0293 99.2289,
+                          71.6058 42.0986 95.4497,
+                          72.4035 44.0293 99.2289,
+                          73.999 52.9964 98.1071,
+                          68.2122 26.8807 100.541,
+                          84.0925 28.6546 76.0068,
+                          72.4035 44.0293 99.2289,
+                          79.7021 73.8569 87.593,
+                          72.8639 60.5869 99.539,
+                          73.999 52.9964 98.1071,
+                          73.999 52.9964 93.2042,
+                          73.999 52.9964 98.1071,
+                          72.8639 60.5869 99.539,
+                          84.0925 28.6546 76.0068,
+                          79.7021 73.8569 87.593,
+                          73.999 52.9964 98.1071,
+                          71.6058 42.0986 95.4497,
+                          73.999 52.9964 98.1071,
+                          73.999 52.9964 93.2042,
+                          79.7021 73.8569 87.593,
+                          69.3212 67.8695 102.923,
+                          72.8639 60.5869 99.539,
+                          70.4142 66.1694 97.6331,
+                          72.8639 60.5869 99.539,
+                          69.3212 67.8695 102.923,
+                          70.4142 66.1694 97.6331,
+                          73.999 52.9964 93.2042,
+                          72.8639 60.5869 99.539,
+                          79.7021 73.8569 87.593,
+                          63.2983 74.0262 107.204,
+                          69.3212 67.8695 102.923,
+                          66.1733 71.5871 101.497,
+                          69.3212 67.8695 102.923,
+                          63.2983 74.0262 107.204,
+                          70.4142 66.1694 97.6331,
+                          69.3212 67.8695 102.923,
+                          66.1733 71.5871 101.497,
+                          59.8022 114.745 100.233,
+                          63.2983 74.0262 107.204,
+                          79.7021 73.8569 87.593,
+                          59.8022 114.745 100.233,
+                          36.2708 114.244 109.354,
+                          63.2983 74.0262 107.204,
+                          57.434 77.2219 110.253,
+                          63.2983 74.0262 107.204,
+                          36.2708 114.244 109.354,
+                          66.1733 71.5871 101.497,
+                          63.2983 74.0262 107.204,
+                          57.434 77.2219 110.253,
+                          84.0925 28.6546 76.0068,
+                          86.6339 76.42 58.0149,
+                          79.7021 73.8569 87.593,
+                          73.6486 115.059 80.8969,
+                          79.7021 73.8569 87.593,
+                          86.6339 76.42 58.0149,
+                          73.6486 115.059 80.8969,
+                          59.8022 114.745 100.233,
+                          79.7021 73.8569 87.593,
+                          88.9128 69.7612 39.8198,
+                          88.6616 82.9264 28.9276,
+                          86.6339 76.42 58.0149,
+                          80.5081 115.014 53.2499,
+                          86.6339 76.42 58.0149,
+                          88.6616 82.9264 28.9276,
+                          89.0638 45.7831 46.302,
+                          88.9128 69.7612 39.8198,
+                          86.6339 76.42 58.0149,
+                          88.9881 38.6057 45.8589,
+                          89.0638 45.7831 46.302,
+                          86.6339 76.42 58.0149,
+                          84.0925 28.6546 76.0068,
+                          88.9881 38.6057 45.8589,
+                          86.6339 76.42 58.0149,
+                          80.5081 115.014 53.2499,
+                          73.6486 115.059 80.8969,
+                          86.6339 76.42 58.0149,
+                          89.5701 69.2939 35.9017,
+                          88.6616 82.9264 28.9276,
+                          88.9128 69.7612 39.8198,
+                          83.5289 115.141 24.27,
+                          80.5081 115.014 53.2499,
+                          88.6616 82.9264 28.9276,
+                          88.6347 88.616 20.8448,
+                          83.5289 115.141 24.27,
+                          88.6616 82.9264 28.9276,
+                          91.146 83.0248 15.7651,
+                          88.6347 88.616 20.8448,
+                          88.6616 82.9264 28.9276,
+                          89.5701 69.2939 35.9017,
+                          91.146 83.0248 15.7651,
+                          88.6616 82.9264 28.9276,
+                          89.5701 69.2939 35.9017,
+                          88.9128 69.7612 39.8198,
+                          89.0638 45.7831 46.302,
+                          89.1516 45.7781 45.4317,
+                          89.0638 45.7831 46.302,
+                          88.9881 38.6057 45.8589,
+                          89.1516 45.7781 45.4317,
+                          89.5701 69.2939 35.9017,
+                          89.0638 45.7831 46.302,
+                          85.105 -0.830204 50.5316,
+                          88.9881 38.6057 45.8589,
+                          84.0925 28.6546 76.0068,
+                          85.105 -0.830204 50.5316,
+                          88.7442 28.4697 43.3876,
+                          88.9881 38.6057 45.8589,
+                          90.9162 45.7361 39.3341,
+                          89.1516 45.7781 45.4317,
+                          88.9881 38.6057 45.8589,
+                          65.6969 -13.4203 90.4642,
+                          84.0925 28.6546 76.0068,
+                          68.2122 26.8807 100.541,
+                          81.5469 -8.92679 65.2278,
+                          85.105 -0.830204 50.5316,
+                          84.0925 28.6546 76.0068,
+                          65.6969 -13.4203 90.4642,
+                          81.5469 -8.92679 65.2278,
+                          84.0925 28.6546 76.0068,
+                          50.3635 -14.2474 99.9054,
+                          68.2122 26.8807 100.541,
+                          42.5845 26.4015 113.101,
+                          50.3635 -14.2474 99.9054,
+                          65.6969 -13.4203 90.4642,
+                          68.2122 26.8807 100.541,
+                          30.832 -15.1118 106.961,
+                          42.5845 26.4015 113.101,
+                          13.9074 26.1377 118.086,
+                          30.832 -15.1118 106.961,
+                          50.3635 -14.2474 99.9054,
+                          42.5845 26.4015 113.101,
+                          6.83515 70.9964 119.288,
+                          13.4339 29.4521 118.439,
+                          13.9074 26.1377 118.086,
+                          16.5406 7.7048 134.41,
+                          13.9074 26.1377 118.086,
+                          13.4339 29.4521 118.439,
+                          17.3203 2.24751 114.198,
+                          17.499 0.996376 113.925,
+                          13.9074 26.1377 118.086,
+                          30.832 -15.1118 106.961,
+                          13.9074 26.1377 118.086,
+                          17.499 0.996376 113.925,
+                          16.5406 7.7048 134.41,
+                          17.3203 2.24751 114.198,
+                          13.9074 26.1377 118.086,
+                          6.83515 70.9964 119.288,
+                          9.40252 57.6716 119.745,
+                          13.4339 29.4521 118.439,
+                          13.0494 32.1433 125.276,
+                          13.4339 29.4521 118.439,
+                          9.40252 57.6716 119.745,
+                          13.0494 32.1433 125.276,
+                          16.5406 7.7048 134.41,
+                          13.4339 29.4521 118.439,
+                          6.83515 70.9964 119.288,
+                          8.27983 63.8251 119.629,
+                          9.40252 57.6716 119.745,
+                          11.1313 38.7451 124.468,
+                          9.40252 57.6716 119.745,
+                          8.27983 63.8251 119.629,
+                          13.0494 32.1433 125.276,
+                          9.40252 57.6716 119.745,
+                          11.1313 38.7451 124.468,
+                          11.1313 38.7451 124.468,
+                          8.27983 63.8251 119.629,
+                          6.83515 70.9964 119.288,
+                          -0.00101543 72.0671 119.271,
+                          3.46161 70.9964 119.331,
+                          6.83515 70.9964 119.288,
+                          6.67121 70.9964 119.33,
+                          6.83515 70.9964 119.288,
+                          3.46161 70.9964 119.331,
+                          28.2336 69.8858 118.083,
+                          -0.00101543 72.0671 119.271,
+                          6.83515 70.9964 119.288,
+                          23.574 61.9167 118.839,
+                          28.2336 69.8858 118.083,
+                          6.83515 70.9964 119.288,
+                          11.1313 38.7451 124.468,
+                          6.83515 70.9964 119.288,
+                          6.67121 70.9964 119.33,
+                          -0.00101543 72.0671 119.271,
+                          -0.00101543 70.9964 119.345,
+                          3.46161 70.9964 119.331,
+                          6.49835 70.9964 119.345,
+                          3.46161 70.9964 119.331,
+                          -0.00101543 70.9964 119.345,
+                          6.67121 70.9964 119.33,
+                          3.46161 70.9964 119.331,
+                          6.49835 70.9964 119.345,
+                          -31.9213 73.4254 117.424,
+                          -0.00101543 70.9964 119.345,
+                          -0.00101543 72.0671 119.271,
+                          -3.4635 70.9964 119.331,
+                          -0.00101543 70.9964 119.345,
+                          -31.9213 73.4254 117.424,
+                          -6.50038 70.9964 119.345,
+                          -0.00101543 70.9964 119.345,
+                          -3.4635 70.9964 119.331,
+                          -11.1333 38.7453 124.468,
+                          -0.00101543 70.9964 119.345,
+                          -6.50038 70.9964 119.345,
+                          -11.1333 38.7453 124.468,
+                          6.49835 70.9964 119.345,
+                          -0.00101543 70.9964 119.345,
+                          28.2336 69.8858 118.083,
+                          31.9193 73.4254 117.424,
+                          -0.00101543 72.0671 119.271,
+                          -0.00101543 111.898 112.336,
+                          -0.00101543 72.0671 119.271,
+                          31.9193 73.4254 117.424,
+                          -36.2729 114.244 109.354,
+                          -0.00101543 72.0671 119.271,
+                          -0.00101543 111.898 112.336,
+                          -36.2729 114.244 109.354,
+                          -31.9213 73.4254 117.424,
+                          -0.00101543 72.0671 119.271,
+                          28.3246 69.9917 115.044,
+                          31.9193 73.4254 117.424,
+                          28.2336 69.8858 118.083,
+                          36.2708 114.244 109.354,
+                          31.9193 73.4254 117.424,
+                          41.831 78.2545 115.348,
+                          40.4805 77.8876 112.59,
+                          41.831 78.2545 115.348,
+                          31.9193 73.4254 117.424,
+                          -0.00101543 113.928 111.706,
+                          -0.00101543 111.898 112.336,
+                          31.9193 73.4254 117.424,
+                          36.2708 114.244 109.354,
+                          -0.00101543 113.928 111.706,
+                          31.9193 73.4254 117.424,
+                          33.8875 74.8351 114.009,
+                          31.9193 73.4254 117.424,
+                          28.3246 69.9917 115.044,
+                          40.4805 77.8876 112.59,
+                          31.9193 73.4254 117.424,
+                          33.8875 74.8351 114.009,
+                          27.5627 69.071 115.176,
+                          28.2336 69.8858 118.083,
+                          23.574 61.9167 118.839,
+                          28.3246 69.9917 115.044,
+                          28.2336 69.8858 118.083,
+                          27.5627 69.071 115.176,
+                          27.5627 69.071 115.176,
+                          23.574 61.9167 118.839,
+                          23.3947 61.4103 115.852,
+                          49.4978 78.9531 113.246,
+                          36.2708 114.244 109.354,
+                          41.831 78.2545 115.348,
+                          48.6514 78.9881 110.354,
+                          49.4978 78.9531 113.246,
+                          41.831 78.2545 115.348,
+                          48.6514 78.9881 110.354,
+                          41.831 78.2545 115.348,
+                          40.4805 77.8876 112.59,
+                          -36.2729 114.244 109.354,
+                          -0.00101543 111.898 112.336,
+                          -0.00101543 113.928 111.706,
+                          -0.00101543 144 96.8424,
+                          -0.00101543 113.928 111.706,
+                          36.2708 114.244 109.354,
+                          -28.8059 146 93.3119,
+                          -0.00101543 113.928 111.706,
+                          -0.00101543 144 96.8424,
+                          -28.8059 146 93.3119,
+                          -36.2729 114.244 109.354,
+                          -0.00101543 113.928 111.706,
+                          28.8038 146 93.3119,
+                          36.2708 114.244 109.354,
+                          59.8022 114.745 100.233,
+                          49.4978 78.9531 113.246,
+                          57.434 77.2219 110.253,
+                          36.2708 114.244 109.354,
+                          -0.00101543 145.998 95.3073,
+                          -0.00101543 144 96.8424,
+                          36.2708 114.244 109.354,
+                          28.8038 146 93.3119,
+                          -0.00101543 145.998 95.3073,
+                          36.2708 114.244 109.354,
+                          47.8569 145.854 86.0346,
+                          59.8022 114.745 100.233,
+                          73.6486 115.059 80.8969,
+                          47.8569 145.854 86.0346,
+                          28.8038 146 93.3119,
+                          59.8022 114.745 100.233,
+                          59.8762 145.719 71.561,
+                          73.6486 115.059 80.8969,
+                          80.5081 115.014 53.2499,
+                          59.8762 145.719 71.561,
+                          47.8569 145.854 86.0346,
+                          73.6486 115.059 80.8969,
+                          67.0371 144.824 51.0308,
+                          80.5081 115.014 53.2499,
+                          83.5289 115.141 24.27,
+                          67.0371 144.824 51.0308,
+                          59.8762 145.719 71.561,
+                          80.5081 115.014 53.2499,
+                          88.9423 94.4015 7.22056,
+                          85.1135 116.189 -0.512584,
+                          83.5289 115.141 24.27,
+                          70.4981 143.238 28.4567,
+                          83.5289 115.141 24.27,
+                          85.1135 116.189 -0.512584,
+                          88.6347 88.616 20.8448,
+                          88.9423 94.4015 7.22056,
+                          83.5289 115.141 24.27,
+                          70.4981 143.238 28.4567,
+                          67.0371 144.824 51.0308,
+                          83.5289 115.141 24.27,
+                          87.1227 91.3435 -25.6992,
+                          82.9223 117.012 -21.6197,
+                          85.1135 116.189 -0.512584,
+                          71.7634 142.623 7.65489,
+                          85.1135 116.189 -0.512584,
+                          82.9223 117.012 -21.6197,
+                          87.8058 93.3198 -22.3592,
+                          87.1227 91.3435 -25.6992,
+                          85.1135 116.189 -0.512584,
+                          87.8736 93.5134 -21.965,
+                          87.8058 93.3198 -22.3592,
+                          85.1135 116.189 -0.512584,
+                          89.1054 96.6406 -5.98052,
+                          87.8736 93.5134 -21.965,
+                          85.1135 116.189 -0.512584,
+                          88.9423 94.4015 7.22056,
+                          89.1054 96.6406 -5.98052,
+                          85.1135 116.189 -0.512584,
+                          71.7634 142.623 7.65489,
+                          70.4981 143.238 28.4567,
+                          85.1135 116.189 -0.512584,
+                          76.8394 104.939 -42.0756,
+                          74.1281 117.215 -39.8012,
+                          82.9223 117.012 -21.6197,
+                          69.2731 142.038 -11.1812,
+                          82.9223 117.012 -21.6197,
+                          74.1281 117.215 -39.8012,
+                          77.8428 92.6298 -42.9524,
+                          76.8394 104.939 -42.0756,
+                          82.9223 117.012 -21.6197,
+                          87.1227 91.3435 -25.6992,
+                          77.8428 92.6298 -42.9524,
+                          82.9223 117.012 -21.6197,
+                          69.2731 142.038 -11.1812,
+                          71.7634 142.623 7.65489,
+                          82.9223 117.012 -21.6197,
+                          72.1318 115.401 -38.2936,
+                          74.1281 117.215 -39.8012,
+                          76.8394 104.939 -42.0756,
+                          66.0121 134.047 -32.6816,
+                          69.2731 142.038 -11.1812,
+                          74.1281 117.215 -39.8012,
+                          67.7293 126.189 -34.3953,
+                          66.0121 134.047 -32.6816,
+                          74.1281 117.215 -39.8012,
+                          67.7293 126.189 -34.3953,
+                          74.1281 117.215 -39.8012,
+                          72.1318 115.401 -38.2936,
+                          74.1471 106.765 -39.9622,
+                          76.8394 104.939 -42.0756,
+                          77.8428 92.6298 -42.9524,
+                          72.1318 115.401 -38.2936,
+                          76.8394 104.939 -42.0756,
+                          74.1471 106.765 -39.9622,
+                          77.9092 79.2485 -43.2008,
+                          77.8428 92.6298 -42.9524,
+                          87.1227 91.3435 -25.6992,
+                          75.5912 91.0743 -41.0762,
+                          77.8428 92.6298 -42.9524,
+                          77.9092 79.2485 -43.2008,
+                          74.1471 106.765 -39.9622,
+                          77.8428 92.6298 -42.9524,
+                          75.5912 91.0743 -41.0762,
+                          93.2656 74.4775 -27.1937,
+                          87.1227 91.3435 -25.6992,
+                          87.8058 93.3198 -22.3592,
+                          84.5148 83.2439 -33.4352,
+                          77.9092 79.2485 -43.2008,
+                          87.1227 91.3435 -25.6992,
+                          93.2656 74.4775 -27.1937,
+                          84.5148 83.2439 -33.4352,
+                          87.1227 91.3435 -25.6992,
+                          93.2656 74.4775 -27.1937,
+                          87.8058 93.3198 -22.3592,
+                          87.8736 93.5134 -21.965,
+                          94.4943 82.2003 -18.3975,
+                          87.8736 93.5134 -21.965,
+                          89.1054 96.6406 -5.98052,
+                          94.4943 82.2003 -18.3975,
+                          93.2656 74.4775 -27.1937,
+                          87.8736 93.5134 -21.965,
+                          95.084 84.6951 -6.36765,
+                          89.1054 96.6406 -5.98052,
+                          88.9423 94.4015 7.22056,
+                          95.084 84.6951 -6.36765,
+                          94.4943 82.2003 -18.3975,
+                          89.1054 96.6406 -5.98052,
+                          91.146 83.0248 15.7651,
+                          88.9423 94.4015 7.22056,
+                          88.6347 88.616 20.8448,
+                          91.146 83.0248 15.7651,
+                          95.084 84.6951 -6.36765,
+                          88.9423 94.4015 7.22056,
+                          57.2631 77.2886 106.979,
+                          57.434 77.2219 110.253,
+                          49.4978 78.9531 113.246,
+                          57.2631 77.2886 106.979,
+                          66.1733 71.5871 101.497,
+                          57.434 77.2219 110.253,
+                          48.6514 78.9881 110.354,
+                          57.2631 77.2886 106.979,
+                          49.4978 78.9531 113.246,
+                          16.3443 1.04248 114.095,
+                          17.499 0.996376 113.925,
+                          16.9201 1.01986 114.012,
+                          17.0941 1.38508 114.06,
+                          16.9201 1.01986 114.012,
+                          17.499 0.996376 113.925,
+                          -16.3464 1.04248 114.095,
+                          17.499 0.996376 113.925,
+                          16.3443 1.04248 114.095,
+                          17.3203 2.24751 114.198,
+                          17.0941 1.38508 114.06,
+                          17.499 0.996376 113.925,
+                          13.7745 -15.4535 110.666,
+                          30.832 -15.1118 106.961,
+                          17.499 0.996376 113.925,
+                          8.79222 0.996376 114.888,
+                          13.7745 -15.4535 110.666,
+                          17.499 0.996376 113.925,
+                          -17.501 0.996376 113.925,
+                          8.79222 0.996376 114.888,
+                          17.499 0.996376 113.925,
+                          -16.9222 1.01986 114.012,
+                          17.499 0.996376 113.925,
+                          -16.3464 1.04248 114.095,
+                          -17.501 0.996376 113.925,
+                          17.499 0.996376 113.925,
+                          -16.9222 1.01986 114.012,
+                          17.0941 1.38508 114.06,
+                          16.3443 1.04248 114.095,
+                          16.9201 1.01986 114.012,
+                          15.5507 6.59799 134.671,
+                          16.3443 1.04248 114.095,
+                          17.0941 1.38508 114.06,
+                          -15.5527 6.59799 134.671,
+                          -16.3464 1.04248 114.095,
+                          16.3443 1.04248 114.095,
+                          -15.5527 6.59799 134.671,
+                          16.3443 1.04248 114.095,
+                          15.5507 6.59799 134.671,
+                          16.3077 6.9406 134.608,
+                          17.0941 1.38508 114.06,
+                          17.3203 2.24751 114.198,
+                          16.3077 6.9406 134.608,
+                          15.5507 6.59799 134.671,
+                          17.0941 1.38508 114.06,
+                          16.3077 6.9406 134.608,
+                          17.3203 2.24751 114.198,
+                          16.5406 7.7048 134.41,
+                          85.105 -0.830204 50.5316,
+                          87.9036 13.3689 34.6449,
+                          88.7442 28.4697 43.3876,
+                          86.9024 11.9664 33.1138,
+                          87.9036 13.3689 34.6449,
+                          85.105 -0.830204 50.5316,
+                          86.9024 11.9664 33.1138,
+                          89.5973 17.7899 30.2975,
+                          87.9036 13.3689 34.6449,
+                          81.5929 -8.99319 60.1144,
+                          85.105 -0.830204 50.5316,
+                          81.5469 -8.92679 65.2278,
+                          81.5929 -8.99319 60.1144,
+                          86.9024 11.9664 33.1138,
+                          85.105 -0.830204 50.5316,
+                          81.5929 -8.99319 60.1144,
+                          81.5469 -8.92679 65.2278,
+                          65.6969 -13.4203 90.4642,
+                          64.6017 -15.1758 89.4087,
+                          65.6969 -13.4203 90.4642,
+                          50.3635 -14.2474 99.9054,
+                          64.6017 -15.1758 89.4087,
+                          81.5929 -8.99319 60.1144,
+                          65.6969 -13.4203 90.4642,
+                          33.857 -16.7893 104.531,
+                          50.3635 -14.2474 99.9054,
+                          30.832 -15.1118 106.961,
+                          33.857 -16.7893 104.531,
+                          64.6017 -15.1758 89.4087,
+                          50.3635 -14.2474 99.9054,
+                          33.857 -16.7893 104.531,
+                          30.832 -15.1118 106.961,
+                          13.7745 -15.4535 110.666,
+                          -0.00101543 -7.40259 113.631,
+                          -0.00101543 -15.714 111.779,
+                          13.7745 -15.4535 110.666,
+                          33.857 -16.7893 104.531,
+                          13.7745 -15.4535 110.666,
+                          -0.00101543 -15.714 111.779,
+                          -0.00101543 0.996376 115.232,
+                          -0.00101543 -7.40259 113.631,
+                          13.7745 -15.4535 110.666,
+                          8.79222 0.996376 114.888,
+                          -0.00101543 0.996376 115.232,
+                          13.7745 -15.4535 110.666,
+                          -8.79901 0.996376 114.887,
+                          -0.00101543 -15.714 111.779,
+                          -0.00101543 -7.40259 113.631,
+                          -13.7647 -15.4537 110.668,
+                          -0.00101543 -15.714 111.779,
+                          -8.79901 0.996376 114.887,
+                          -0.00101065 -17.577 110.421,
+                          -0.00101543 -15.714 111.779,
+                          -13.7647 -15.4537 110.668,
+                          33.857 -16.7893 104.531,
+                          -0.00101543 -15.714 111.779,
+                          -0.00101065 -17.577 110.421,
+                          -8.79901 0.996376 114.887,
+                          -0.00101543 -7.40259 113.631,
+                          -0.00101543 0.996376 115.232,
+                          -17.501 0.996376 113.925,
+                          -0.00101543 0.996376 115.232,
+                          8.79222 0.996376 114.888,
+                          -8.79901 0.996376 114.887,
+                          -0.00101543 0.996376 115.232,
+                          -17.501 0.996376 113.925,
+                          -28.8059 146 93.3119,
+                          -0.00101543 144 96.8424,
+                          -0.00101543 145.998 95.3073,
+                          -0.00101543 165.532 70.7474,
+                          -0.00101543 145.998 95.3073,
+                          28.8038 146 93.3119,
+                          -16.5665 165.654 68.9406,
+                          -0.00101543 145.998 95.3073,
+                          -0.00101543 165.532 70.7474,
+                          -28.8059 146 93.3119,
+                          -0.00101543 145.998 95.3073,
+                          -16.5665 165.654 68.9406,
+                          16.5645 165.654 68.9406,
+                          28.8038 146 93.3119,
+                          47.8569 145.854 86.0346,
+                          -0.00101543 165.811 70.1316,
+                          -0.00101543 165.532 70.7474,
+                          28.8038 146 93.3119,
+                          16.5645 165.654 68.9406,
+                          -0.00101543 165.811 70.1316,
+                          28.8038 146 93.3119,
+                          28.8851 165.358 64.6061,
+                          47.8569 145.854 86.0346,
+                          59.8762 145.719 71.561,
+                          28.8851 165.358 64.6061,
+                          16.5645 165.654 68.9406,
+                          47.8569 145.854 86.0346,
+                          37.6426 165.101 56.4764,
+                          59.8762 145.719 71.561,
+                          67.0371 144.824 51.0308,
+                          37.6426 165.101 56.4764,
+                          28.8851 165.358 64.6061,
+                          59.8762 145.719 71.561,
+                          43.1691 164.686 45.0235,
+                          67.0371 144.824 51.0308,
+                          70.4981 143.238 28.4567,
+                          43.1691 164.686 45.0235,
+                          37.6426 165.101 56.4764,
+                          67.0371 144.824 51.0308,
+                          45.6738 164.015 31.9401,
+                          70.4981 143.238 28.4567,
+                          71.7634 142.623 7.65489,
+                          45.6738 164.015 31.9401,
+                          43.1691 164.686 45.0235,
+                          70.4981 143.238 28.4567,
+                          45.7899 163.478 19.0623,
+                          71.7634 142.623 7.65489,
+                          69.2731 142.038 -11.1812,
+                          45.7899 163.478 19.0623,
+                          45.6738 164.015 31.9401,
+                          71.7634 142.623 7.65489,
+                          66.0121 134.047 -32.6816,
+                          61.1464 140.689 -28.2737,
+                          69.2731 142.038 -11.1812,
+                          42.8508 162.991 6.88559,
+                          69.2731 142.038 -11.1812,
+                          61.1464 140.689 -28.2737,
+                          42.8508 162.991 6.88559,
+                          45.7899 163.478 19.0623,
+                          69.2731 142.038 -11.1812,
+                          60.0182 137.977 -27.3098,
+                          61.1464 140.689 -28.2737,
+                          66.0121 134.047 -32.6816,
+                          51.435 151.007 -19.2629,
+                          42.8508 162.991 6.88559,
+                          61.1464 140.689 -28.2737,
+                          49.0539 149.572 -17.0027,
+                          51.435 151.007 -19.2629,
+                          61.1464 140.689 -28.2737,
+                          49.0539 149.572 -17.0027,
+                          61.1464 140.689 -28.2737,
+                          60.0182 137.977 -27.3098,
+                          61.2249 136.411 -28.4289,
+                          60.0182 137.977 -27.3098,
+                          66.0121 134.047 -32.6816,
+                          61.2249 136.411 -28.4289,
+                          66.0121 134.047 -32.6816,
+                          67.7293 126.189 -34.3953,
+                          -16.5665 165.654 68.9406,
+                          -0.00101543 165.532 70.7474,
+                          -0.00101543 165.811 70.1316,
+                          -0.00101543 172.167 36.9921,
+                          -0.00101543 165.811 70.1316,
+                          16.5645 165.654 68.9406,
+                          -1.59975 172.172 36.7106,
+                          -0.00101543 165.811 70.1316,
+                          -0.00101543 172.167 36.9921,
+                          -16.5665 165.654 68.9406,
+                          -0.00101543 165.811 70.1316,
+                          -1.59975 172.172 36.7106,
+                          2.78304 172.189 35.9007,
+                          16.5645 165.654 68.9406,
+                          28.8851 165.358 64.6061,
+                          1.59772 172.172 36.7106,
+                          -0.00101543 172.167 36.9921,
+                          16.5645 165.654 68.9406,
+                          2.78304 172.189 35.9007,
+                          1.59772 172.172 36.7106,
+                          16.5645 165.654 68.9406,
+                          2.78304 172.189 35.9007,
+                          28.8851 165.358 64.6061,
+                          37.6426 165.101 56.4764,
+                          3.59464 172.217 34.5175,
+                          37.6426 165.101 56.4764,
+                          43.1691 164.686 45.0235,
+                          3.59464 172.217 34.5175,
+                          2.78304 172.189 35.9007,
+                          37.6426 165.101 56.4764,
+                          3.85684 172.238 33.4559,
+                          43.1691 164.686 45.0235,
+                          45.6738 164.015 31.9401,
+                          3.85684 172.238 33.4559,
+                          3.59464 172.217 34.5175,
+                          43.1691 164.686 45.0235,
+                          3.94115 172.262 32.2732,
+                          45.6738 164.015 31.9401,
+                          45.7899 163.478 19.0623,
+                          3.94115 172.262 32.2732,
+                          3.85684 172.238 33.4559,
+                          45.6738 164.015 31.9401,
+                          3.85274 172.287 31.1034,
+                          45.7899 163.478 19.0623,
+                          42.8508 162.991 6.88559,
+                          3.85274 172.287 31.1034,
+                          3.94115 172.262 32.2732,
+                          45.7899 163.478 19.0623,
+                          38.8515 160.728 -7.21946,
+                          35.4263 162.822 -3.87114,
+                          42.8508 162.991 6.88559,
+                          3.61577 172.308 30.1029,
+                          42.8508 162.991 6.88559,
+                          35.4263 162.822 -3.87114,
+                          51.435 151.007 -19.2629,
+                          38.8515 160.728 -7.21946,
+                          42.8508 162.991 6.88559,
+                          3.61577 172.308 30.1029,
+                          3.85274 172.287 31.1034,
+                          42.8508 162.991 6.88559,
+                          35.3118 159.641 -3.7465,
+                          35.4263 162.822 -3.87114,
+                          38.8515 160.728 -7.21946,
+                          18.6814 170.058 12.9565,
+                          3.61577 172.308 30.1029,
+                          35.4263 162.822 -3.87114,
+                          32.9964 160.962 -1.47427,
+                          18.6814 170.058 12.9565,
+                          35.4263 162.822 -3.87114,
+                          32.9964 160.962 -1.47427,
+                          35.4263 162.822 -3.87114,
+                          35.3118 159.641 -3.7465,
+                          49.0539 149.572 -17.0027,
+                          38.8515 160.728 -7.21946,
+                          51.435 151.007 -19.2629,
+                          49.0539 149.572 -17.0027,
+                          35.3118 159.641 -3.7465,
+                          38.8515 160.728 -7.21946,
+                          -0.00101543 169.167 37.023,
+                          -0.00101543 172.167 36.9921,
+                          1.59772 172.172 36.7106,
+                          -1.5397 169.172 36.7644,
+                          -1.59975 172.172 36.7106,
+                          -0.00101543 172.167 36.9921,
+                          -1.5397 169.172 36.7644,
+                          -0.00101543 172.167 36.9921,
+                          -0.00101543 169.167 37.023,
+                          2.71013 169.187 36.0093,
+                          1.59772 172.172 36.7106,
+                          2.78304 172.189 35.9007,
+                          1.53767 169.172 36.7644,
+                          -0.00101543 169.167 37.023,
+                          1.59772 172.172 36.7106,
+                          1.53767 169.172 36.7644,
+                          1.59772 172.172 36.7106,
+                          2.71013 169.187 36.0093,
+                          3.53235 169.212 34.7115,
+                          2.78304 172.189 35.9007,
+                          3.59464 172.217 34.5175,
+                          2.71013 169.187 36.0093,
+                          2.78304 172.189 35.9007,
+                          3.53235 169.212 34.7115,
+                          3.80572 169.231 33.7722,
+                          3.59464 172.217 34.5175,
+                          3.85684 172.238 33.4559,
+                          3.53235 169.212 34.7115,
+                          3.59464 172.217 34.5175,
+                          3.80572 169.231 33.7722,
+                          3.91911 169.254 32.6716,
+                          3.85684 172.238 33.4559,
+                          3.94115 172.262 32.2732,
+                          3.80572 169.231 33.7722,
+                          3.85684 172.238 33.4559,
+                          3.91911 169.254 32.6716,
+                          3.84804 169.281 31.3686,
+                          3.94115 172.262 32.2732,
+                          3.85274 172.287 31.1034,
+                          3.91911 169.254 32.6716,
+                          3.94115 172.262 32.2732,
+                          3.84804 169.281 31.3686,
+                          3.60833 169.305 30.2263,
+                          3.85274 172.287 31.1034,
+                          3.61577 172.308 30.1029,
+                          3.84804 169.281 31.3686,
+                          3.85274 172.287 31.1034,
+                          3.60833 169.305 30.2263,
+                          18.6814 170.058 12.9565,
+                          3.23422 172.326 29.2438,
+                          3.61577 172.308 30.1029,
+                          3.60833 169.305 30.2263,
+                          3.61577 172.308 30.1029,
+                          3.23422 172.326 29.2438,
+                          3.18807 169.327 29.2068,
+                          3.23422 172.326 29.2438,
+                          18.6814 170.058 12.9565,
+                          3.60833 169.305 30.2263,
+                          3.23422 172.326 29.2438,
+                          3.18807 169.327 29.2068,
+                          16.4703 167.59 15.1264,
+                          18.6814 170.058 12.9565,
+                          32.9964 160.962 -1.47427,
+                          3.18807 169.327 29.2068,
+                          18.6814 170.058 12.9565,
+                          16.4703 167.59 15.1264,
+                          84.5148 83.2439 -33.4352,
+                          77.4455 64.1357 -43.0072,
+                          77.9092 79.2485 -43.2008,
+                          75.647 78.567 -41.2221,
+                          77.9092 79.2485 -43.2008,
+                          77.4455 64.1357 -43.0072,
+                          75.647 78.567 -41.2221,
+                          75.5912 91.0743 -41.0762,
+                          77.9092 79.2485 -43.2008,
+                          84.5148 83.2439 -33.4352,
+                          78.6196 64.2599 -41.6844,
+                          77.4455 64.1357 -43.0072,
+                          75.2308 64.3271 -40.9931,
+                          77.4455 64.1357 -43.0072,
+                          78.6196 64.2599 -41.6844,
+                          75.647 78.567 -41.2221,
+                          77.4455 64.1357 -43.0072,
+                          75.2308 64.3271 -40.9931,
+                          82.1767 74.6857 -37.5445,
+                          79.7046 64.3772 -40.3764,
+                          78.6196 64.2599 -41.6844,
+                          76.5676 64.4671 -39.4751,
+                          78.6196 64.2599 -41.6844,
+                          79.7046 64.3772 -40.3764,
+                          84.5148 83.2439 -33.4352,
+                          82.1767 74.6857 -37.5445,
+                          78.6196 64.2599 -41.6844,
+                          75.2308 64.3271 -40.9931,
+                          78.6196 64.2599 -41.6844,
+                          76.5676 64.4671 -39.4751,
+                          93.2656 74.4775 -27.1937,
+                          79.7046 64.3772 -40.3764,
+                          82.1767 74.6857 -37.5445,
+                          76.5676 64.4671 -39.4751,
+                          79.7046 64.3772 -40.3764,
+                          77.838 64.603 -37.9042,
+                          90.2955 64.9173 -32.5566,
+                          77.838 64.603 -37.9042,
+                          79.7046 64.3772 -40.3764,
+                          93.2656 74.4775 -27.1937,
+                          90.2955 64.9173 -32.5566,
+                          79.7046 64.3772 -40.3764,
+                          93.2656 74.4775 -27.1937,
+                          82.1767 74.6857 -37.5445,
+                          84.5148 83.2439 -33.4352,
+                          -13.913 26.1124 118.083,
+                          -23.576 61.9167 118.839,
+                          -22.001 52.9964 119.008,
+                          -22.001 52.9964 115.994,
+                          -22.001 52.9964 119.008,
+                          -23.576 61.9167 118.839,
+                          -24.1697 42.6026 118.414,
+                          -13.913 26.1124 118.083,
+                          -22.001 52.9964 119.008,
+                          -24.0477 42.8865 115.419,
+                          -24.1697 42.6026 118.414,
+                          -22.001 52.9964 119.008,
+                          -24.0477 42.8865 115.419,
+                          -22.001 52.9964 119.008,
+                          -22.001 52.9964 115.994,
+                          -9.40455 57.6716 119.745,
+                          -28.2356 69.8858 118.083,
+                          -23.576 61.9167 118.839,
+                          -27.5647 69.071 115.176,
+                          -23.576 61.9167 118.839,
+                          -28.2356 69.8858 118.083,
+                          -13.4835 29.1187 118.406,
+                          -9.40455 57.6716 119.745,
+                          -23.576 61.9167 118.839,
+                          -13.913 26.1124 118.083,
+                          -13.4835 29.1187 118.406,
+                          -23.576 61.9167 118.839,
+                          -23.3968 61.4103 115.852,
+                          -23.576 61.9167 118.839,
+                          -27.5647 69.071 115.176,
+                          -22.001 52.9964 115.994,
+                          -23.576 61.9167 118.839,
+                          -23.3968 61.4103 115.852,
+                          -8.27658 63.8696 119.623,
+                          -31.9213 73.4254 117.424,
+                          -28.2356 69.8858 118.083,
+                          -28.3267 69.9917 115.044,
+                          -28.2356 69.8858 118.083,
+                          -31.9213 73.4254 117.424,
+                          -9.40455 57.6716 119.745,
+                          -8.27658 63.8696 119.623,
+                          -28.2356 69.8858 118.083,
+                          -27.5647 69.071 115.176,
+                          -28.2356 69.8858 118.083,
+                          -28.3267 69.9917 115.044,
+                          -6.83718 70.9964 119.288,
+                          -3.4635 70.9964 119.331,
+                          -31.9213 73.4254 117.424,
+                          -8.27658 63.8696 119.623,
+                          -6.83718 70.9964 119.288,
+                          -31.9213 73.4254 117.424,
+                          -36.2729 114.244 109.354,
+                          -41.833 78.2545 115.348,
+                          -31.9213 73.4254 117.424,
+                          -33.8895 74.8351 114.009,
+                          -31.9213 73.4254 117.424,
+                          -41.833 78.2545 115.348,
+                          -33.8895 74.8351 114.009,
+                          -28.3267 69.9917 115.044,
+                          -31.9213 73.4254 117.424,
+                          -6.50038 70.9964 119.345,
+                          -3.4635 70.9964 119.331,
+                          -6.83718 70.9964 119.288,
+                          -6.67324 70.9964 119.33,
+                          -6.83718 70.9964 119.288,
+                          -8.27658 63.8696 119.623,
+                          -6.67324 70.9964 119.33,
+                          -6.50038 70.9964 119.345,
+                          -6.83718 70.9964 119.288,
+                          -6.50038 70.9964 119.345,
+                          -8.27658 63.8696 119.623,
+                          -9.40455 57.6716 119.745,
+                          -6.67324 70.9964 119.33,
+                          -8.27658 63.8696 119.623,
+                          -6.50038 70.9964 119.345,
+                          -13.0515 32.1433 125.276,
+                          -9.40455 57.6716 119.745,
+                          -13.4835 29.1187 118.406,
+                          -11.1333 38.7453 124.468,
+                          -6.50038 70.9964 119.345,
+                          -9.40455 57.6716 119.745,
+                          -13.0515 32.1433 125.276,
+                          -11.1333 38.7453 124.468,
+                          -9.40455 57.6716 119.745,
+                          -13.0515 32.1433 125.276,
+                          -13.4835 29.1187 118.406,
+                          -13.913 26.1124 118.083,
+                          -38.4521 28.8155 114.565,
+                          -42.5804 26.4014 113.103,
+                          -13.913 26.1124 118.083,
+                          -17.3223 2.24751 114.198,
+                          -13.913 26.1124 118.083,
+                          -42.5804 26.4014 113.103,
+                          -30.106 34.1267 116.914,
+                          -38.4521 28.8155 114.565,
+                          -13.913 26.1124 118.083,
+                          -24.1697 42.6026 118.414,
+                          -30.106 34.1267 116.914,
+                          -13.913 26.1124 118.083,
+                          -16.5427 7.7048 134.41,
+                          -13.913 26.1124 118.083,
+                          -17.3223 2.24751 114.198,
+                          -13.0515 32.1433 125.276,
+                          -13.913 26.1124 118.083,
+                          -16.5427 7.7048 134.41,
+                          -48.1115 26.9942 111.391,
+                          -68.2109 26.8806 100.544,
+                          -42.5804 26.4014 113.103,
+                          -50.5068 -14.237 99.8411,
+                          -42.5804 26.4014 113.103,
+                          -68.2109 26.8806 100.544,
+                          -38.4521 28.8155 114.565,
+                          -48.1115 26.9942 111.391,
+                          -42.5804 26.4014 113.103,
+                          -17.501 0.996376 113.925,
+                          -17.3223 2.24751 114.198,
+                          -42.5804 26.4014 113.103,
+                          -30.8632 -15.1111 106.952,
+                          -17.501 0.996376 113.925,
+                          -42.5804 26.4014 113.103,
+                          -50.5068 -14.237 99.8411,
+                          -30.8632 -15.1111 106.952,
+                          -42.5804 26.4014 113.103,
+                          -79.7041 73.8569 87.593,
+                          -84.0939 28.6543 76.009,
+                          -68.2109 26.8806 100.544,
+                          -65.7533 -13.4182 90.4173,
+                          -68.2109 26.8806 100.544,
+                          -84.0939 28.6543 76.009,
+                          -74.001 52.9964 98.1071,
+                          -79.7041 73.8569 87.593,
+                          -68.2109 26.8806 100.544,
+                          -72.4055 44.0293 99.2289,
+                          -74.001 52.9964 98.1071,
+                          -68.2109 26.8806 100.544,
+                          -66.8688 35.1128 102.974,
+                          -72.4055 44.0293 99.2289,
+                          -68.2109 26.8806 100.544,
+                          -57.7139 28.8752 107.594,
+                          -66.8688 35.1128 102.974,
+                          -68.2109 26.8806 100.544,
+                          -48.1115 26.9942 111.391,
+                          -57.7139 28.8752 107.594,
+                          -68.2109 26.8806 100.544,
+                          -65.7533 -13.4182 90.4173,
+                          -50.5068 -14.237 99.8411,
+                          -68.2109 26.8806 100.544,
+                          -89.0659 45.7831 46.302,
+                          -88.9901 38.6057 45.8589,
+                          -84.0939 28.6543 76.009,
+                          -81.5654 -8.90714 65.1743,
+                          -84.0939 28.6543 76.009,
+                          -88.9901 38.6057 45.8589,
+                          -86.6359 76.42 58.0149,
+                          -89.0659 45.7831 46.302,
+                          -84.0939 28.6543 76.009,
+                          -79.7041 73.8569 87.593,
+                          -86.6359 76.42 58.0149,
+                          -84.0939 28.6543 76.009,
+                          -81.5654 -8.90714 65.1743,
+                          -65.7533 -13.4182 90.4173,
+                          -84.0939 28.6543 76.009,
+                          -85.1129 -0.808685 50.5027,
+                          -81.5654 -8.90714 65.1743,
+                          -88.9901 38.6057 45.8589,
+                          -88.7462 28.4697 43.3876,
+                          -85.1129 -0.808685 50.5027,
+                          -88.9901 38.6057 45.8589,
+                          -86.6359 76.42 58.0149,
+                          -88.9149 69.7612 39.8198,
+                          -89.0659 45.7831 46.302,
+                          -89.1536 45.7781 45.4317,
+                          -89.0659 45.7831 46.302,
+                          -88.9149 69.7612 39.8198,
+                          -86.6359 76.42 58.0149,
+                          -88.6636 82.9264 28.9276,
+                          -88.9149 69.7612 39.8198,
+                          -89.5722 69.2939 35.9017,
+                          -88.9149 69.7612 39.8198,
+                          -88.6636 82.9264 28.9276,
+                          -89.5722 69.2939 35.9017,
+                          -89.1536 45.7781 45.4317,
+                          -88.9149 69.7612 39.8198,
+                          -80.5101 115.014 53.2499,
+                          -88.6636 82.9264 28.9276,
+                          -86.6359 76.42 58.0149,
+                          -83.5309 115.141 24.27,
+                          -88.6367 88.616 20.8448,
+                          -88.6636 82.9264 28.9276,
+                          -89.5722 69.2939 35.9017,
+                          -88.6636 82.9264 28.9276,
+                          -88.6367 88.616 20.8448,
+                          -80.5101 115.014 53.2499,
+                          -83.5309 115.141 24.27,
+                          -88.6636 82.9264 28.9276,
+                          -73.6507 115.059 80.8969,
+                          -86.6359 76.42 58.0149,
+                          -79.7041 73.8569 87.593,
+                          -73.6507 115.059 80.8969,
+                          -80.5101 115.014 53.2499,
+                          -86.6359 76.42 58.0149,
+                          -69.3232 67.8695 102.923,
+                          -63.3004 74.0262 107.204,
+                          -79.7041 73.8569 87.593,
+                          -59.8042 114.745 100.233,
+                          -79.7041 73.8569 87.593,
+                          -63.3004 74.0262 107.204,
+                          -72.8659 60.5869 99.539,
+                          -69.3232 67.8695 102.923,
+                          -79.7041 73.8569 87.593,
+                          -74.001 52.9964 98.1071,
+                          -72.8659 60.5869 99.539,
+                          -79.7041 73.8569 87.593,
+                          -59.8042 114.745 100.233,
+                          -73.6507 115.059 80.8969,
+                          -79.7041 73.8569 87.593,
+                          -66.1754 71.5871 101.497,
+                          -63.3004 74.0262 107.204,
+                          -69.3232 67.8695 102.923,
+                          -59.8042 114.745 100.233,
+                          -63.3004 74.0262 107.204,
+                          -57.436 77.2219 110.253,
+                          -57.2651 77.2886 106.979,
+                          -57.436 77.2219 110.253,
+                          -63.3004 74.0262 107.204,
+                          -57.2651 77.2886 106.979,
+                          -63.3004 74.0262 107.204,
+                          -66.1754 71.5871 101.497,
+                          -70.4163 66.1694 97.6331,
+                          -69.3232 67.8695 102.923,
+                          -72.8659 60.5869 99.539,
+                          -66.1754 71.5871 101.497,
+                          -69.3232 67.8695 102.923,
+                          -70.4163 66.1694 97.6331,
+                          -70.4163 66.1694 97.6331,
+                          -72.8659 60.5869 99.539,
+                          -74.001 52.9964 98.1071,
+                          -74.001 52.9964 93.2042,
+                          -74.001 52.9964 98.1071,
+                          -72.4055 44.0293 99.2289,
+                          -70.4163 66.1694 97.6331,
+                          -74.001 52.9964 98.1071,
+                          -74.001 52.9964 93.2042,
+                          -71.6078 42.0986 95.4497,
+                          -72.4055 44.0293 99.2289,
+                          -66.8688 35.1128 102.974,
+                          -71.6078 42.0986 95.4497,
+                          -74.001 52.9964 93.2042,
+                          -72.4055 44.0293 99.2289,
+                          -63.9973 32.502 100.924,
+                          -66.8688 35.1128 102.974,
+                          -57.7139 28.8752 107.594,
+                          -71.6078 42.0986 95.4497,
+                          -66.8688 35.1128 102.974,
+                          -63.9973 32.502 100.924,
+                          -56.5993 28.4599 104.687,
+                          -57.7139 28.8752 107.594,
+                          -48.1115 26.9942 111.391,
+                          -63.9973 32.502 100.924,
+                          -57.7139 28.8752 107.594,
+                          -56.5993 28.4599 104.687,
+                          -47.5055 27.0006 108.385,
+                          -48.1115 26.9942 111.391,
+                          -38.4521 28.8155 114.565,
+                          -56.5993 28.4599 104.687,
+                          -48.1115 26.9942 111.391,
+                          -47.5055 27.0006 108.385,
+                          -37.9646 29.013 111.595,
+                          -38.4521 28.8155 114.565,
+                          -30.106 34.1267 116.914,
+                          -47.5055 27.0006 108.385,
+                          -38.4521 28.8155 114.565,
+                          -37.9646 29.013 111.595,
+                          -29.7679 34.4561 113.947,
+                          -30.106 34.1267 116.914,
+                          -24.1697 42.6026 118.414,
+                          -37.9646 29.013 111.595,
+                          -30.106 34.1267 116.914,
+                          -29.7679 34.4561 113.947,
+                          -29.7679 34.4561 113.947,
+                          -24.1697 42.6026 118.414,
+                          -24.0477 42.8865 115.419,
+                          -59.8042 114.745 100.233,
+                          -49.4998 78.9531 113.246,
+                          -41.833 78.2545 115.348,
+                          -48.6535 78.9881 110.354,
+                          -41.833 78.2545 115.348,
+                          -49.4998 78.9531 113.246,
+                          -36.2729 114.244 109.354,
+                          -59.8042 114.745 100.233,
+                          -41.833 78.2545 115.348,
+                          -40.4825 77.8876 112.59,
+                          -41.833 78.2545 115.348,
+                          -48.6535 78.9881 110.354,
+                          -33.8895 74.8351 114.009,
+                          -41.833 78.2545 115.348,
+                          -40.4825 77.8876 112.59,
+                          -59.8042 114.745 100.233,
+                          -57.436 77.2219 110.253,
+                          -49.4998 78.9531 113.246,
+                          -57.2651 77.2886 106.979,
+                          -49.4998 78.9531 113.246,
+                          -57.436 77.2219 110.253,
+                          -48.6535 78.9881 110.354,
+                          -49.4998 78.9531 113.246,
+                          -57.2651 77.2886 106.979,
+                          -85.1155 116.189 -0.512584,
+                          -88.9444 94.4015 7.22056,
+                          -88.6367 88.616 20.8448,
+                          -91.148 83.0248 15.7651,
+                          -88.6367 88.616 20.8448,
+                          -88.9444 94.4015 7.22056,
+                          -83.5309 115.141 24.27,
+                          -85.1155 116.189 -0.512584,
+                          -88.6367 88.616 20.8448,
+                          -91.148 83.0248 15.7651,
+                          -89.5722 69.2939 35.9017,
+                          -88.6367 88.616 20.8448,
+                          -85.1155 116.189 -0.512584,
+                          -89.1074 96.6406 -5.98052,
+                          -88.9444 94.4015 7.22056,
+                          -91.148 83.0248 15.7651,
+                          -88.9444 94.4015 7.22056,
+                          -89.1074 96.6406 -5.98052,
+                          -82.9243 117.012 -21.6197,
+                          -87.8756 93.5134 -21.965,
+                          -89.1074 96.6406 -5.98052,
+                          -94.4964 82.2003 -18.3975,
+                          -89.1074 96.6406 -5.98052,
+                          -87.8756 93.5134 -21.965,
+                          -85.1155 116.189 -0.512584,
+                          -82.9243 117.012 -21.6197,
+                          -89.1074 96.6406 -5.98052,
+                          -95.0861 84.6951 -6.36765,
+                          -89.1074 96.6406 -5.98052,
+                          -94.4964 82.2003 -18.3975,
+                          -91.148 83.0248 15.7651,
+                          -89.1074 96.6406 -5.98052,
+                          -95.0861 84.6951 -6.36765,
+                          -82.9243 117.012 -21.6197,
+                          -87.8078 93.3198 -22.3592,
+                          -87.8756 93.5134 -21.965,
+                          -93.2676 74.4775 -27.1937,
+                          -87.8756 93.5134 -21.965,
+                          -87.8078 93.3198 -22.3592,
+                          -94.4964 82.2003 -18.3975,
+                          -87.8756 93.5134 -21.965,
+                          -93.2676 74.4775 -27.1937,
+                          -82.9243 117.012 -21.6197,
+                          -87.1247 91.3435 -25.6992,
+                          -87.8078 93.3198 -22.3592,
+                          -93.2676 74.4775 -27.1937,
+                          -87.8078 93.3198 -22.3592,
+                          -87.1247 91.3435 -25.6992,
+                          -76.8414 104.939 -42.0756,
+                          -77.8448 92.6298 -42.9524,
+                          -87.1247 91.3435 -25.6992,
+                          -84.5168 83.2439 -33.4352,
+                          -87.1247 91.3435 -25.6992,
+                          -77.8448 92.6298 -42.9524,
+                          -74.1301 117.215 -39.8012,
+                          -76.8414 104.939 -42.0756,
+                          -87.1247 91.3435 -25.6992,
+                          -82.9243 117.012 -21.6197,
+                          -74.1301 117.215 -39.8012,
+                          -87.1247 91.3435 -25.6992,
+                          -93.2676 74.4775 -27.1937,
+                          -87.1247 91.3435 -25.6992,
+                          -84.5168 83.2439 -33.4352,
+                          -75.5932 91.0743 -41.0762,
+                          -77.8448 92.6298 -42.9524,
+                          -76.8414 104.939 -42.0756,
+                          -82.1787 74.6857 -37.5445,
+                          -84.5168 83.2439 -33.4352,
+                          -77.8448 92.6298 -42.9524,
+                          -79.7067 64.3772 -40.3764,
+                          -82.1787 74.6857 -37.5445,
+                          -77.8448 92.6298 -42.9524,
+                          -78.6217 64.2599 -41.6844,
+                          -79.7067 64.3772 -40.3764,
+                          -77.8448 92.6298 -42.9524,
+                          -77.9113 79.2485 -43.2008,
+                          -78.6217 64.2599 -41.6844,
+                          -77.8448 92.6298 -42.9524,
+                          -75.5932 91.0743 -41.0762,
+                          -77.9113 79.2485 -43.2008,
+                          -77.8448 92.6298 -42.9524,
+                          -74.1491 106.765 -39.9622,
+                          -76.8414 104.939 -42.0756,
+                          -74.1301 117.215 -39.8012,
+                          -75.5932 91.0743 -41.0762,
+                          -76.8414 104.939 -42.0756,
+                          -74.1491 106.765 -39.9622,
+                          -66.0142 134.047 -32.6816,
+                          -74.1301 117.215 -39.8012,
+                          -82.9243 117.012 -21.6197,
+                          -67.7314 126.189 -34.3953,
+                          -74.1301 117.215 -39.8012,
+                          -66.0142 134.047 -32.6816,
+                          -74.1491 106.765 -39.9622,
+                          -74.1301 117.215 -39.8012,
+                          -72.1338 115.401 -38.2936,
+                          -67.7314 126.189 -34.3953,
+                          -72.1338 115.401 -38.2936,
+                          -74.1301 117.215 -39.8012,
+                          -69.2751 142.038 -11.1812,
+                          -82.9243 117.012 -21.6197,
+                          -85.1155 116.189 -0.512584,
+                          -61.1485 140.689 -28.2737,
+                          -82.9243 117.012 -21.6197,
+                          -69.2751 142.038 -11.1812,
+                          -66.0142 134.047 -32.6816,
+                          -82.9243 117.012 -21.6197,
+                          -61.1485 140.689 -28.2737,
+                          -71.7654 142.623 7.65489,
+                          -85.1155 116.189 -0.512584,
+                          -83.5309 115.141 24.27,
+                          -69.2751 142.038 -11.1812,
+                          -85.1155 116.189 -0.512584,
+                          -71.7654 142.623 7.65489,
+                          -70.5001 143.238 28.4567,
+                          -83.5309 115.141 24.27,
+                          -80.5101 115.014 53.2499,
+                          -71.7654 142.623 7.65489,
+                          -83.5309 115.141 24.27,
+                          -70.5001 143.238 28.4567,
+                          -67.0391 144.824 51.0308,
+                          -80.5101 115.014 53.2499,
+                          -73.6507 115.059 80.8969,
+                          -70.5001 143.238 28.4567,
+                          -80.5101 115.014 53.2499,
+                          -67.0391 144.824 51.0308,
+                          -59.8782 145.719 71.561,
+                          -73.6507 115.059 80.8969,
+                          -59.8042 114.745 100.233,
+                          -67.0391 144.824 51.0308,
+                          -73.6507 115.059 80.8969,
+                          -59.8782 145.719 71.561,
+                          -47.8589 145.854 86.0346,
+                          -59.8042 114.745 100.233,
+                          -36.2729 114.244 109.354,
+                          -59.8782 145.719 71.561,
+                          -59.8042 114.745 100.233,
+                          -47.8589 145.854 86.0346,
+                          -47.8589 145.854 86.0346,
+                          -36.2729 114.244 109.354,
+                          -28.8059 146 93.3119,
+                          -17.501 0.996376 113.925,
+                          -17.0961 1.38508 114.06,
+                          -17.3223 2.24751 114.198,
+                          -16.5427 7.7048 134.41,
+                          -17.3223 2.24751 114.198,
+                          -17.0961 1.38508 114.06,
+                          -16.9222 1.01986 114.012,
+                          -16.3464 1.04248 114.095,
+                          -17.0961 1.38508 114.06,
+                          -16.306 6.93638 134.609,
+                          -17.0961 1.38508 114.06,
+                          -16.3464 1.04248 114.095,
+                          -17.501 0.996376 113.925,
+                          -16.9222 1.01986 114.012,
+                          -17.0961 1.38508 114.06,
+                          -16.306 6.93638 134.609,
+                          -16.5427 7.7048 134.41,
+                          -17.0961 1.38508 114.06,
+                          -16.306 6.93638 134.609,
+                          -16.3464 1.04248 114.095,
+                          -15.5527 6.59799 134.671,
+                          -13.7647 -15.4537 110.668,
+                          -8.79901 0.996376 114.887,
+                          -17.501 0.996376 113.925,
+                          -30.8632 -15.1111 106.952,
+                          -13.7647 -15.4537 110.668,
+                          -17.501 0.996376 113.925,
+                          -0.00101065 -17.577 110.421,
+                          -13.7647 -15.4537 110.668,
+                          -30.8632 -15.1111 106.952,
+                          -33.8591 -16.7893 104.531,
+                          -30.8632 -15.1111 106.952,
+                          -50.5068 -14.237 99.8411,
+                          -33.8591 -16.7893 104.531,
+                          -0.00101065 -17.577 110.421,
+                          -30.8632 -15.1111 106.952,
+                          -64.6038 -15.1758 89.4083,
+                          -50.5068 -14.237 99.8411,
+                          -65.7533 -13.4182 90.4173,
+                          -64.6038 -15.1758 89.4083,
+                          -33.8591 -16.7893 104.531,
+                          -50.5068 -14.237 99.8411,
+                          -64.6038 -15.1758 89.4083,
+                          -65.7533 -13.4182 90.4173,
+                          -81.5654 -8.90714 65.1743,
+                          -81.5949 -8.99321 60.1144,
+                          -81.5654 -8.90714 65.1743,
+                          -85.1129 -0.808685 50.5027,
+                          -81.5949 -8.99321 60.1144,
+                          -64.6038 -15.1758 89.4083,
+                          -81.5654 -8.90714 65.1743,
+                          -88.7462 28.4697 43.3876,
+                          -87.9057 13.3688 34.6449,
+                          -85.1129 -0.808685 50.5027,
+                          -81.5949 -8.99321 60.1144,
+                          -85.1129 -0.808685 50.5027,
+                          -87.9057 13.3688 34.6449,
+                          -89.5997 17.7905 30.297,
+                          -87.9057 13.3688 34.6449,
+                          -88.7462 28.4697 43.3876,
+                          -81.5949 -8.99321 60.1144,
+                          -87.9057 13.3688 34.6449,
+                          -86.9046 11.9664 33.1138,
+                          -79.7067 64.3772 -40.3764,
+                          -84.5168 83.2439 -33.4352,
+                          -82.1787 74.6857 -37.5445,
+                          -93.2676 74.4775 -27.1937,
+                          -84.5168 83.2439 -33.4352,
+                          -79.7067 64.3772 -40.3764,
+                          -76.5696 64.4671 -39.4751,
+                          -79.7067 64.3772 -40.3764,
+                          -78.6217 64.2599 -41.6844,
+                          -77.84 64.603 -37.9042,
+                          -79.7067 64.3772 -40.3764,
+                          -76.5696 64.4671 -39.4751,
+                          -80.9515 65.0305 -32.1047,
+                          -79.7067 64.3772 -40.3764,
+                          -77.84 64.603 -37.9042,
+                          -80.9515 65.0305 -32.1047,
+                          -90.2975 64.9173 -32.5566,
+                          -79.7067 64.3772 -40.3764,
+                          -93.2676 74.4775 -27.1937,
+                          -79.7067 64.3772 -40.3764,
+                          -90.2975 64.9173 -32.5566,
+                          -77.9113 79.2485 -43.2008,
+                          -77.4475 64.1357 -43.0072,
+                          -78.6217 64.2599 -41.6844,
+                          -76.5696 64.4671 -39.4751,
+                          -78.6217 64.2599 -41.6844,
+                          -77.4475 64.1357 -43.0072,
+                          -75.2328 64.3271 -40.9931,
+                          -77.4475 64.1357 -43.0072,
+                          -77.9113 79.2485 -43.2008,
+                          -76.5696 64.4671 -39.4751,
+                          -77.4475 64.1357 -43.0072,
+                          -75.2328 64.3271 -40.9931,
+                          -75.649 78.567 -41.2221,
+                          -77.9113 79.2485 -43.2008,
+                          -75.5932 91.0743 -41.0762,
+                          -75.2328 64.3271 -40.9931,
+                          -77.9113 79.2485 -43.2008,
+                          -75.649 78.567 -41.2221,
+                          -42.8528 162.991 6.88559,
+                          -3.6178 172.308 30.1029,
+                          -3.23625 172.326 29.2438,
+                          -3.1901 169.327 29.2068,
+                          -3.23625 172.326 29.2438,
+                          -3.6178 172.308 30.1029,
+                          -18.6835 170.058 12.9565,
+                          -42.8528 162.991 6.88559,
+                          -3.23625 172.326 29.2438,
+                          -16.4724 167.59 15.1264,
+                          -18.6835 170.058 12.9565,
+                          -3.23625 172.326 29.2438,
+                          -16.4724 167.59 15.1264,
+                          -3.23625 172.326 29.2438,
+                          -3.1901 169.327 29.2068,
+                          -42.8528 162.991 6.88559,
+                          -3.85477 172.287 31.1034,
+                          -3.6178 172.308 30.1029,
+                          -3.61036 169.305 30.2263,
+                          -3.6178 172.308 30.1029,
+                          -3.85477 172.287 31.1034,
+                          -3.1901 169.327 29.2068,
+                          -3.6178 172.308 30.1029,
+                          -3.61036 169.305 30.2263,
+                          -45.792 163.478 19.0623,
+                          -3.94318 172.262 32.2732,
+                          -3.85477 172.287 31.1034,
+                          -3.85007 169.281 31.3686,
+                          -3.85477 172.287 31.1034,
+                          -3.94318 172.262 32.2732,
+                          -42.8528 162.991 6.88559,
+                          -45.792 163.478 19.0623,
+                          -3.85477 172.287 31.1034,
+                          -3.61036 169.305 30.2263,
+                          -3.85477 172.287 31.1034,
+                          -3.85007 169.281 31.3686,
+                          -45.6758 164.015 31.9401,
+                          -3.85887 172.238 33.4559,
+                          -3.94318 172.262 32.2732,
+                          -3.92114 169.254 32.6716,
+                          -3.94318 172.262 32.2732,
+                          -3.85887 172.238 33.4559,
+                          -45.792 163.478 19.0623,
+                          -45.6758 164.015 31.9401,
+                          -3.94318 172.262 32.2732,
+                          -3.85007 169.281 31.3686,
+                          -3.94318 172.262 32.2732,
+                          -3.92114 169.254 32.6716,
+                          -43.1711 164.686 45.0235,
+                          -3.59667 172.217 34.5175,
+                          -3.85887 172.238 33.4559,
+                          -3.80775 169.231 33.7722,
+                          -3.85887 172.238 33.4559,
+                          -3.59667 172.217 34.5175,
+                          -45.6758 164.015 31.9401,
+                          -43.1711 164.686 45.0235,
+                          -3.85887 172.238 33.4559,
+                          -3.92114 169.254 32.6716,
+                          -3.85887 172.238 33.4559,
+                          -3.80775 169.231 33.7722,
+                          -28.8872 165.358 64.6061,
+                          -2.78507 172.189 35.9007,
+                          -3.59667 172.217 34.5175,
+                          -3.53438 169.212 34.7115,
+                          -3.59667 172.217 34.5175,
+                          -2.78507 172.189 35.9007,
+                          -37.6446 165.101 56.4764,
+                          -28.8872 165.358 64.6061,
+                          -3.59667 172.217 34.5175,
+                          -43.1711 164.686 45.0235,
+                          -37.6446 165.101 56.4764,
+                          -3.59667 172.217 34.5175,
+                          -3.80775 169.231 33.7722,
+                          -3.59667 172.217 34.5175,
+                          -3.53438 169.212 34.7115,
+                          -16.5665 165.654 68.9406,
+                          -1.59975 172.172 36.7106,
+                          -2.78507 172.189 35.9007,
+                          -2.71217 169.187 36.0093,
+                          -2.78507 172.189 35.9007,
+                          -1.59975 172.172 36.7106,
+                          -28.8872 165.358 64.6061,
+                          -16.5665 165.654 68.9406,
+                          -2.78507 172.189 35.9007,
+                          -3.53438 169.212 34.7115,
+                          -2.78507 172.189 35.9007,
+                          -2.71217 169.187 36.0093,
+                          -2.71217 169.187 36.0093,
+                          -1.59975 172.172 36.7106,
+                          -1.5397 169.172 36.7644,
+                          -28.8059 146 93.3119,
+                          -16.5665 165.654 68.9406,
+                          -28.8872 165.358 64.6061,
+                          -47.8589 145.854 86.0346,
+                          -28.8872 165.358 64.6061,
+                          -37.6446 165.101 56.4764,
+                          -47.8589 145.854 86.0346,
+                          -28.8059 146 93.3119,
+                          -28.8872 165.358 64.6061,
+                          -59.8782 145.719 71.561,
+                          -37.6446 165.101 56.4764,
+                          -43.1711 164.686 45.0235,
+                          -59.8782 145.719 71.561,
+                          -47.8589 145.854 86.0346,
+                          -37.6446 165.101 56.4764,
+                          -67.0391 144.824 51.0308,
+                          -43.1711 164.686 45.0235,
+                          -45.6758 164.015 31.9401,
+                          -67.0391 144.824 51.0308,
+                          -59.8782 145.719 71.561,
+                          -43.1711 164.686 45.0235,
+                          -70.5001 143.238 28.4567,
+                          -45.6758 164.015 31.9401,
+                          -45.792 163.478 19.0623,
+                          -70.5001 143.238 28.4567,
+                          -67.0391 144.824 51.0308,
+                          -45.6758 164.015 31.9401,
+                          -71.7654 142.623 7.65489,
+                          -45.792 163.478 19.0623,
+                          -42.8528 162.991 6.88559,
+                          -71.7654 142.623 7.65489,
+                          -70.5001 143.238 28.4567,
+                          -45.792 163.478 19.0623,
+                          -18.6835 170.058 12.9565,
+                          -35.4283 162.822 -3.87114,
+                          -42.8528 162.991 6.88559,
+                          -69.2751 142.038 -11.1812,
+                          -42.8528 162.991 6.88559,
+                          -35.4283 162.822 -3.87114,
+                          -69.2751 142.038 -11.1812,
+                          -71.7654 142.623 7.65489,
+                          -42.8528 162.991 6.88559,
+                          -32.9985 160.962 -1.47427,
+                          -35.4283 162.822 -3.87114,
+                          -18.6835 170.058 12.9565,
+                          -69.2751 142.038 -11.1812,
+                          -35.4283 162.822 -3.87114,
+                          -38.8535 160.728 -7.21946,
+                          -35.3138 159.641 -3.7465,
+                          -38.8535 160.728 -7.21946,
+                          -35.4283 162.822 -3.87114,
+                          -35.3138 159.641 -3.7465,
+                          -35.4283 162.822 -3.87114,
+                          -32.9985 160.962 -1.47427,
+                          -32.9985 160.962 -1.47427,
+                          -18.6835 170.058 12.9565,
+                          -16.4724 167.59 15.1264,
+                          -51.437 151.007 -19.2629,
+                          -69.2751 142.038 -11.1812,
+                          -38.8535 160.728 -7.21946,
+                          -49.0559 149.572 -17.0027,
+                          -51.437 151.007 -19.2629,
+                          -38.8535 160.728 -7.21946,
+                          -49.0559 149.572 -17.0027,
+                          -38.8535 160.728 -7.21946,
+                          -35.3138 159.641 -3.7465,
+                          -51.437 151.007 -19.2629,
+                          -61.1485 140.689 -28.2737,
+                          -69.2751 142.038 -11.1812,
+                          -60.0203 137.977 -27.3098,
+                          -61.1485 140.689 -28.2737,
+                          -51.437 151.007 -19.2629,
+                          -61.227 136.411 -28.4289,
+                          -66.0142 134.047 -32.6816,
+                          -61.1485 140.689 -28.2737,
+                          -61.227 136.411 -28.4289,
+                          -61.1485 140.689 -28.2737,
+                          -60.0203 137.977 -27.3098,
+                          -60.0203 137.977 -27.3098,
+                          -51.437 151.007 -19.2629,
+                          -49.0559 149.572 -17.0027,
+                          -67.7314 126.189 -34.3953,
+                          -66.0142 134.047 -32.6816,
+                          -61.227 136.411 -28.4289,
+                          76.4138 24.6822 85.7673,
+                          71.6058 42.0986 95.4497,
+                          73.999 52.9964 93.2042,
+                          80.3128 71.6348 77.5096,
+                          76.4138 24.6822 85.7673,
+                          73.999 52.9964 93.2042,
+                          70.4142 66.1694 97.6331,
+                          80.3128 71.6348 77.5096,
+                          73.999 52.9964 93.2042,
+                          55.6339 24.0528 104.384,
+                          63.9952 32.502 100.924,
+                          71.6058 42.0986 95.4497,
+                          76.4138 24.6822 85.7673,
+                          55.6339 24.0528 104.384,
+                          71.6058 42.0986 95.4497,
+                          55.6339 24.0528 104.384,
+                          56.5972 28.4599 104.687,
+                          63.9952 32.502 100.924,
+                          55.6339 24.0528 104.384,
+                          47.5034 27.0006 108.385,
+                          56.5972 28.4599 104.687,
+                          28.3155 23.5397 112.915,
+                          37.9625 29.013 111.595,
+                          47.5034 27.0006 108.385,
+                          55.6339 24.0528 104.384,
+                          28.3155 23.5397 112.915,
+                          47.5034 27.0006 108.385,
+                          28.3155 23.5397 112.915,
+                          29.7658 34.4561 113.947,
+                          37.9625 29.013 111.595,
+                          -0.00101543 23.9579 115.369,
+                          24.0457 42.8865 115.419,
+                          29.7658 34.4561 113.947,
+                          28.3155 23.5397 112.915,
+                          -0.00101543 23.9579 115.369,
+                          29.7658 34.4561 113.947,
+                          -0.00101543 23.9579 115.369,
+                          21.999 52.9964 115.994,
+                          24.0457 42.8865 115.419,
+                          -0.00101543 23.9579 115.369,
+                          23.3947 61.4103 115.852,
+                          21.999 52.9964 115.994,
+                          -0.00101543 23.9579 115.369,
+                          27.5627 69.071 115.176,
+                          23.3947 61.4103 115.852,
+                          -0.00101543 69.7933 116.416,
+                          28.3246 69.9917 115.044,
+                          27.5627 69.071 115.176,
+                          -0.00101543 34.3002 116.239,
+                          -0.00101543 69.7933 116.416,
+                          27.5627 69.071 115.176,
+                          -0.00101543 23.9579 115.369,
+                          -0.00101543 34.3002 116.239,
+                          27.5627 69.071 115.176,
+                          39.9237 111.885 106.216,
+                          28.3246 69.9917 115.044,
+                          -0.00101543 69.7933 116.416,
+                          33.8875 74.8351 114.009,
+                          28.3246 69.9917 115.044,
+                          39.9237 111.885 106.216,
+                          -28.3175 23.5397 112.915,
+                          -0.00101543 69.7933 116.416,
+                          -0.00101543 34.3002 116.239,
+                          -0.00101543 88.7877 114.402,
+                          39.9237 111.885 106.216,
+                          -0.00101543 69.7933 116.416,
+                          -28.3267 69.9917 115.044,
+                          -0.00101543 88.7877 114.402,
+                          -0.00101543 69.7933 116.416,
+                          -24.0477 42.8865 115.419,
+                          -0.00101543 69.7933 116.416,
+                          -28.3175 23.5397 112.915,
+                          -27.5647 69.071 115.176,
+                          -28.3267 69.9917 115.044,
+                          -0.00101543 69.7933 116.416,
+                          -23.3968 61.4103 115.852,
+                          -27.5647 69.071 115.176,
+                          -0.00101543 69.7933 116.416,
+                          -22.001 52.9964 115.994,
+                          -23.3968 61.4103 115.852,
+                          -0.00101543 69.7933 116.416,
+                          -24.0477 42.8865 115.419,
+                          -22.001 52.9964 115.994,
+                          -0.00101543 69.7933 116.416,
+                          -28.3175 23.5397 112.915,
+                          -0.00101543 34.3002 116.239,
+                          -0.00101543 23.9579 115.369,
+                          -0.00101543 -17.9272 108.143,
+                          -0.00101543 23.9579 115.369,
+                          28.3155 23.5397 112.915,
+                          -20.9642 -17.3841 105.566,
+                          -0.00101543 23.9579 115.369,
+                          -0.00101543 -17.9272 108.143,
+                          -20.9642 -17.3841 105.566,
+                          -28.3175 23.5397 112.915,
+                          -0.00101543 23.9579 115.369,
+                          41.0845 -16.6347 99.6227,
+                          28.3155 23.5397 112.915,
+                          55.6339 24.0528 104.384,
+                          16.4773 -17.5065 106.472,
+                          -0.00101543 -17.9272 108.143,
+                          28.3155 23.5397 112.915,
+                          41.0845 -16.6347 99.6227,
+                          16.4773 -17.5065 106.472,
+                          28.3155 23.5397 112.915,
+                          63.9656 -15.2976 86.9213,
+                          55.6339 24.0528 104.384,
+                          76.4138 24.6822 85.7673,
+                          63.9656 -15.2976 86.9213,
+                          41.0845 -16.6347 99.6227,
+                          55.6339 24.0528 104.384,
+                          84.7636 40.6455 58.9289,
+                          84.5831 30.4841 57.6103,
+                          76.4138 24.6822 85.7673,
+                          79.0837 -9.95758 60.7472,
+                          76.4138 24.6822 85.7673,
+                          84.5831 30.4841 57.6103,
+                          80.3128 71.6348 77.5096,
+                          84.7636 40.6455 58.9289,
+                          76.4138 24.6822 85.7673,
+                          79.0837 -9.95758 60.7472,
+                          63.9656 -15.2976 86.9213,
+                          76.4138 24.6822 85.7673,
+                          84.2947 19.7488 53.6572,
+                          79.0837 -9.95758 60.7472,
+                          84.5831 30.4841 57.6103,
+                          80.3128 71.6348 77.5096,
+                          84.9127 54.2367 57.4132,
+                          84.7636 40.6455 58.9289,
+                          84.4595 40.8107 52.295,
+                          84.7636 40.6455 58.9289,
+                          84.9127 54.2367 57.4132,
+                          80.3128 71.6348 77.5096,
+                          84.9577 67.098 52.3178,
+                          84.9127 54.2367 57.4132,
+                          80.3128 71.6348 77.5096,
+                          84.9286 77.3031 44.9498,
+                          84.9577 67.098 52.3178,
+                          74.9088 112.781 69.1367,
+                          84.9286 77.3031 44.9498,
+                          80.3128 71.6348 77.5096,
+                          79.937 112.915 36.0129,
+                          84.9056 87.7317 32.054,
+                          84.9286 77.3031 44.9498,
+                          74.9088 112.781 69.1367,
+                          79.937 112.915 36.0129,
+                          84.9286 77.3031 44.9498,
+                          70.4142 66.1694 97.6331,
+                          66.1733 71.5871 101.497,
+                          80.3128 71.6348 77.5096,
+                          62.9044 112.396 94.3275,
+                          80.3128 71.6348 77.5096,
+                          66.1733 71.5871 101.497,
+                          62.9044 112.396 94.3275,
+                          74.9088 112.781 69.1367,
+                          80.3128 71.6348 77.5096,
+                          62.9044 112.396 94.3275,
+                          66.1733 71.5871 101.497,
+                          57.2631 77.2886 106.979,
+                          48.6514 78.9881 110.354,
+                          62.9044 112.396 94.3275,
+                          57.2631 77.2886 106.979,
+                          82.3463 113.932 5.69428,
+                          85.2037 93.7307 18.016,
+                          84.9056 87.7317 32.054,
+                          79.937 112.915 36.0129,
+                          82.3463 113.932 5.69428,
+                          84.9056 87.7317 32.054,
+                          82.3463 113.932 5.69428,
+                          85.9406 95.5969 4.24845,
+                          85.2037 93.7307 18.016,
+                          82.3463 113.932 5.69428,
+                          85.6589 89.7553 -19.3134,
+                          85.9406 95.5969 4.24845,
+                          81.1075 114.943 -18.4956,
+                          85.3657 88.7782 -21.1588,
+                          85.6589 89.7553 -19.3134,
+                          82.3463 113.932 5.69428,
+                          81.1075 114.943 -18.4956,
+                          85.6589 89.7553 -19.3134,
+                          81.1075 114.943 -18.4956,
+                          81.7443 89.7248 -31.6975,
+                          85.3657 88.7782 -21.1588,
+                          80.5996 77.4356 -34.4485,
+                          85.3657 88.7782 -21.1588,
+                          81.7443 89.7248 -31.6975,
+                          74.1471 106.765 -39.9622,
+                          75.5912 91.0743 -41.0762,
+                          81.7443 89.7248 -31.6975,
+                          80.5996 77.4356 -34.4485,
+                          81.7443 89.7248 -31.6975,
+                          75.5912 91.0743 -41.0762,
+                          72.1318 115.401 -38.2936,
+                          74.1471 106.765 -39.9622,
+                          81.7443 89.7248 -31.6975,
+                          81.1075 114.943 -18.4956,
+                          72.1318 115.401 -38.2936,
+                          81.7443 89.7248 -31.6975,
+                          77.838 64.603 -37.9042,
+                          80.5996 77.4356 -34.4485,
+                          75.5912 91.0743 -41.0762,
+                          76.5676 64.4671 -39.4751,
+                          77.838 64.603 -37.9042,
+                          75.5912 91.0743 -41.0762,
+                          75.647 78.567 -41.2221,
+                          76.5676 64.4671 -39.4751,
+                          75.5912 91.0743 -41.0762,
+                          67.7293 126.189 -34.3953,
+                          72.1318 115.401 -38.2936,
+                          81.1075 114.943 -18.4956,
+                          68.3456 139.461 -8.39391,
+                          81.1075 114.943 -18.4956,
+                          82.3463 113.932 5.69428,
+                          60.0182 137.977 -27.3098,
+                          81.1075 114.943 -18.4956,
+                          68.3456 139.461 -8.39391,
+                          61.2249 136.411 -28.4289,
+                          81.1075 114.943 -18.4956,
+                          60.0182 137.977 -27.3098,
+                          61.2249 136.411 -28.4289,
+                          67.7293 126.189 -34.3953,
+                          81.1075 114.943 -18.4956,
+                          69.7657 140.305 13.0911,
+                          82.3463 113.932 5.69428,
+                          79.937 112.915 36.0129,
+                          68.3456 139.461 -8.39391,
+                          82.3463 113.932 5.69428,
+                          69.7657 140.305 13.0911,
+                          67.3465 141.452 37.8252,
+                          79.937 112.915 36.0129,
+                          74.9088 112.781 69.1367,
+                          69.7657 140.305 13.0911,
+                          79.937 112.915 36.0129,
+                          67.3465 141.452 37.8252,
+                          61.7127 143.007 62.7854,
+                          74.9088 112.781 69.1367,
+                          62.9044 112.396 94.3275,
+                          67.3465 141.452 37.8252,
+                          74.9088 112.781 69.1367,
+                          61.7127 143.007 62.7854,
+                          48.6514 78.9881 110.354,
+                          39.9237 111.885 106.216,
+                          62.9044 112.396 94.3275,
+                          50.7315 143.131 81.5448,
+                          62.9044 112.396 94.3275,
+                          39.9237 111.885 106.216,
+                          61.7127 143.007 62.7854,
+                          62.9044 112.396 94.3275,
+                          50.7315 143.131 81.5448,
+                          -0.00101543 88.7877 114.402,
+                          -0.00101543 111.27 109.392,
+                          39.9237 111.885 106.216,
+                          31.8544 143.356 90.9425,
+                          39.9237 111.885 106.216,
+                          -0.00101543 111.27 109.392,
+                          40.4805 77.8876 112.59,
+                          33.8875 74.8351 114.009,
+                          39.9237 111.885 106.216,
+                          48.6514 78.9881 110.354,
+                          40.4805 77.8876 112.59,
+                          39.9237 111.885 106.216,
+                          50.7315 143.131 81.5448,
+                          39.9237 111.885 106.216,
+                          31.8544 143.356 90.9425,
+                          -28.3267 69.9917 115.044,
+                          -0.00101543 111.27 109.392,
+                          -0.00101543 88.7877 114.402,
+                          -0.00101543 130.696 101.596,
+                          31.8544 143.356 90.9425,
+                          -0.00101543 111.27 109.392,
+                          -39.9257 111.885 106.216,
+                          -0.00101543 130.696 101.596,
+                          -0.00101543 111.27 109.392,
+                          -33.8895 74.8351 114.009,
+                          -0.00101543 111.27 109.392,
+                          -28.3267 69.9917 115.044,
+                          -33.8895 74.8351 114.009,
+                          -40.4825 77.8876 112.59,
+                          -0.00101543 111.27 109.392,
+                          -39.9257 111.885 106.216,
+                          -0.00101543 111.27 109.392,
+                          -40.4825 77.8876 112.59,
+                          1.53767 169.172 36.7644,
+                          -0.00101543 163.019 69.0276,
+                          -0.00101543 169.167 37.023,
+                          -18.4701 162.682 67.7629,
+                          -0.00101543 169.167 37.023,
+                          -0.00101543 163.019 69.0276,
+                          -18.4701 162.682 67.7629,
+                          -1.5397 169.172 36.7644,
+                          -0.00101543 169.167 37.023,
+                          1.53767 169.172 36.7644,
+                          18.4681 162.682 67.7629,
+                          -0.00101543 163.019 69.0276,
+                          -0.00101543 159.608 75.5436,
+                          -0.00101543 163.019 69.0276,
+                          18.4681 162.682 67.7629,
+                          -31.8564 143.356 90.9425,
+                          -0.00101543 163.019 69.0276,
+                          -0.00101543 159.608 75.5436,
+                          -31.8564 143.356 90.9425,
+                          -18.4701 162.682 67.7629,
+                          -0.00101543 163.019 69.0276,
+                          2.71013 169.187 36.0093,
+                          31.2927 162.316 62.1479,
+                          18.4681 162.682 67.7629,
+                          31.8544 143.356 90.9425,
+                          18.4681 162.682 67.7629,
+                          31.2927 162.316 62.1479,
+                          1.53767 169.172 36.7644,
+                          2.71013 169.187 36.0093,
+                          18.4681 162.682 67.7629,
+                          -0.00101543 142.93 93.893,
+                          -0.00101543 159.608 75.5436,
+                          18.4681 162.682 67.7629,
+                          31.8544 143.356 90.9425,
+                          -0.00101543 142.93 93.893,
+                          18.4681 162.682 67.7629,
+                          3.53235 169.212 34.7115,
+                          39.709 162.03 51.6219,
+                          31.2927 162.316 62.1479,
+                          50.7315 143.131 81.5448,
+                          31.2927 162.316 62.1479,
+                          39.709 162.03 51.6219,
+                          2.71013 169.187 36.0093,
+                          3.53235 169.212 34.7115,
+                          31.2927 162.316 62.1479,
+                          50.7315 143.131 81.5448,
+                          31.8544 143.356 90.9425,
+                          31.2927 162.316 62.1479,
+                          3.80572 169.231 33.7722,
+                          44.0501 161.388 37.5564,
+                          39.709 162.03 51.6219,
+                          61.7127 143.007 62.7854,
+                          39.709 162.03 51.6219,
+                          44.0501 161.388 37.5564,
+                          3.53235 169.212 34.7115,
+                          3.80572 169.231 33.7722,
+                          39.709 162.03 51.6219,
+                          61.7127 143.007 62.7854,
+                          50.7315 143.131 81.5448,
+                          39.709 162.03 51.6219,
+                          3.91911 169.254 32.6716,
+                          45.19 160.697 22.6931,
+                          44.0501 161.388 37.5564,
+                          67.3465 141.452 37.8252,
+                          44.0501 161.388 37.5564,
+                          45.19 160.697 22.6931,
+                          3.80572 169.231 33.7722,
+                          3.91911 169.254 32.6716,
+                          44.0501 161.388 37.5564,
+                          67.3465 141.452 37.8252,
+                          61.7127 143.007 62.7854,
+                          44.0501 161.388 37.5564,
+                          3.84804 169.281 31.3686,
+                          42.858 160.082 8.79737,
+                          45.19 160.697 22.6931,
+                          69.7657 140.305 13.0911,
+                          45.19 160.697 22.6931,
+                          42.858 160.082 8.79737,
+                          3.91911 169.254 32.6716,
+                          3.84804 169.281 31.3686,
+                          45.19 160.697 22.6931,
+                          69.7657 140.305 13.0911,
+                          67.3465 141.452 37.8252,
+                          45.19 160.697 22.6931,
+                          32.9964 160.962 -1.47427,
+                          35.3118 159.641 -3.7465,
+                          42.858 160.082 8.79737,
+                          68.3456 139.461 -8.39391,
+                          42.858 160.082 8.79737,
+                          35.3118 159.641 -3.7465,
+                          16.4703 167.59 15.1264,
+                          32.9964 160.962 -1.47427,
+                          42.858 160.082 8.79737,
+                          3.18807 169.327 29.2068,
+                          16.4703 167.59 15.1264,
+                          42.858 160.082 8.79737,
+                          3.60833 169.305 30.2263,
+                          3.18807 169.327 29.2068,
+                          42.858 160.082 8.79737,
+                          3.84804 169.281 31.3686,
+                          3.60833 169.305 30.2263,
+                          42.858 160.082 8.79737,
+                          68.3456 139.461 -8.39391,
+                          69.7657 140.305 13.0911,
+                          42.858 160.082 8.79737,
+                          49.0539 149.572 -17.0027,
+                          68.3456 139.461 -8.39391,
+                          35.3118 159.641 -3.7465,
+                          -31.8564 143.356 90.9425,
+                          -0.00101543 159.608 75.5436,
+                          -0.00101543 142.93 93.893,
+                          -0.00101543 130.696 101.596,
+                          -0.00101543 142.93 93.893,
+                          31.8544 143.356 90.9425,
+                          -39.9257 111.885 106.216,
+                          -0.00101543 142.93 93.893,
+                          -0.00101543 130.696 101.596,
+                          -31.8564 143.356 90.9425,
+                          -0.00101543 142.93 93.893,
+                          -39.9257 111.885 106.216,
+                          49.0539 149.572 -17.0027,
+                          60.0182 137.977 -27.3098,
+                          68.3456 139.461 -8.39391,
+                          -0.00101065 -17.577 110.421,
+                          -0.00101543 -17.9272 108.143,
+                          16.4773 -17.5065 106.472,
+                          -0.00101065 -17.577 110.421,
+                          -20.9642 -17.3841 105.566,
+                          -0.00101543 -17.9272 108.143,
+                          33.857 -16.7893 104.531,
+                          16.4773 -17.5065 106.472,
+                          41.0845 -16.6347 99.6227,
+                          33.857 -16.7893 104.531,
+                          -0.00101065 -17.577 110.421,
+                          16.4773 -17.5065 106.472,
+                          64.6017 -15.1758 89.4087,
+                          41.0845 -16.6347 99.6227,
+                          63.9656 -15.2976 86.9213,
+                          33.857 -16.7893 104.531,
+                          41.0845 -16.6347 99.6227,
+                          64.6017 -15.1758 89.4087,
+                          64.6017 -15.1758 89.4087,
+                          63.9656 -15.2976 86.9213,
+                          79.0837 -9.95758 60.7472,
+                          84.2947 19.7488 53.6572,
+                          83.3841 3.87717 40.5514,
+                          79.0837 -9.95758 60.7472,
+                          81.5929 -8.99319 60.1144,
+                          79.0837 -9.95758 60.7472,
+                          83.3841 3.87717 40.5514,
+                          64.6017 -15.1758 89.4087,
+                          79.0837 -9.95758 60.7472,
+                          81.5929 -8.99319 60.1144,
+                          81.5929 -8.99319 60.1144,
+                          83.3841 3.87717 40.5514,
+                          83.4146 4.03983 40.3717,
+                          80.9495 65.0305 -32.1047,
+                          80.5996 77.4356 -34.4485,
+                          77.838 64.603 -37.9042,
+                          90.2955 64.9173 -32.5566,
+                          80.9495 65.0305 -32.1047,
+                          77.838 64.603 -37.9042,
+                          75.647 78.567 -41.2221,
+                          75.2308 64.3271 -40.9931,
+                          76.5676 64.4671 -39.4751,
+                          81.5929 -8.99319 60.1144,
+                          84.0977 7.85853 36.2769,
+                          84.7154 11.599 32.4235,
+                          81.5929 -8.99319 60.1144,
+                          84.7154 11.599 32.4235,
+                          86.9024 11.9664 33.1138,
+                          84.0977 7.85853 36.2769,
+                          83.4369 4.23247 40.1613,
+                          83.358 7.76134 36.4586,
+                          81.5929 -8.99319 60.1144,
+                          83.4369 4.23247 40.1613,
+                          84.0977 7.85853 36.2769,
+                          81.5929 -8.99319 60.1144,
+                          83.4146 4.03983 40.3717,
+                          83.4369 4.23247 40.1613,
+                          -80.3148 71.6348 77.5096,
+                          -70.4163 66.1694 97.6331,
+                          -74.001 52.9964 93.2042,
+                          -76.4158 24.6822 85.7673,
+                          -80.3148 71.6348 77.5096,
+                          -74.001 52.9964 93.2042,
+                          -71.6078 42.0986 95.4497,
+                          -76.4158 24.6822 85.7673,
+                          -74.001 52.9964 93.2042,
+                          -80.3148 71.6348 77.5096,
+                          -66.1754 71.5871 101.497,
+                          -70.4163 66.1694 97.6331,
+                          -62.9064 112.396 94.3275,
+                          -66.1754 71.5871 101.497,
+                          -80.3148 71.6348 77.5096,
+                          -39.9257 111.885 106.216,
+                          -57.2651 77.2886 106.979,
+                          -66.1754 71.5871 101.497,
+                          -62.9064 112.396 94.3275,
+                          -39.9257 111.885 106.216,
+                          -66.1754 71.5871 101.497,
+                          -84.9597 67.098 52.3178,
+                          -84.9306 77.3031 44.9498,
+                          -80.3148 71.6348 77.5096,
+                          -74.9108 112.781 69.1367,
+                          -80.3148 71.6348 77.5096,
+                          -84.9306 77.3031 44.9498,
+                          -84.9147 54.2367 57.4132,
+                          -84.9597 67.098 52.3178,
+                          -80.3148 71.6348 77.5096,
+                          -84.7656 40.6455 58.9289,
+                          -84.9147 54.2367 57.4132,
+                          -80.3148 71.6348 77.5096,
+                          -84.5852 30.4841 57.6103,
+                          -84.7656 40.6455 58.9289,
+                          -80.3148 71.6348 77.5096,
+                          -76.4158 24.6822 85.7673,
+                          -84.5852 30.4841 57.6103,
+                          -80.3148 71.6348 77.5096,
+                          -74.9108 112.781 69.1367,
+                          -62.9064 112.396 94.3275,
+                          -80.3148 71.6348 77.5096,
+                          -79.939 112.915 36.0129,
+                          -74.9108 112.781 69.1367,
+                          -84.9306 77.3031 44.9498,
+                          -84.9077 87.7317 32.054,
+                          -79.939 112.915 36.0129,
+                          -84.9306 77.3031 44.9498,
+                          -84.4615 40.8107 52.295,
+                          -84.7656 40.6455 58.9289,
+                          -84.5852 30.4841 57.6103,
+                          -79.5916 -9.0764 58.8184,
+                          -84.5852 30.4841 57.6103,
+                          -76.4158 24.6822 85.7673,
+                          -79.5916 -9.0764 58.8184,
+                          -84.2967 19.7488 53.6572,
+                          -84.5852 30.4841 57.6103,
+                          -56.5993 28.4599 104.687,
+                          -55.6359 24.0528 104.384,
+                          -76.4158 24.6822 85.7673,
+                          -65.9496 -15.1986 85.0548,
+                          -76.4158 24.6822 85.7673,
+                          -55.6359 24.0528 104.384,
+                          -63.9973 32.502 100.924,
+                          -56.5993 28.4599 104.687,
+                          -76.4158 24.6822 85.7673,
+                          -71.6078 42.0986 95.4497,
+                          -63.9973 32.502 100.924,
+                          -76.4158 24.6822 85.7673,
+                          -65.9496 -15.1986 85.0548,
+                          -79.5916 -9.0764 58.8184,
+                          -76.4158 24.6822 85.7673,
+                          -37.9646 29.013 111.595,
+                          -28.3175 23.5397 112.915,
+                          -55.6359 24.0528 104.384,
+                          -45.6507 -16.3674 97.8023,
+                          -55.6359 24.0528 104.384,
+                          -28.3175 23.5397 112.915,
+                          -47.5055 27.0006 108.385,
+                          -37.9646 29.013 111.595,
+                          -55.6359 24.0528 104.384,
+                          -56.5993 28.4599 104.687,
+                          -47.5055 27.0006 108.385,
+                          -55.6359 24.0528 104.384,
+                          -45.6507 -16.3674 97.8023,
+                          -65.9496 -15.1986 85.0548,
+                          -55.6359 24.0528 104.384,
+                          -29.7679 34.4561 113.947,
+                          -24.0477 42.8865 115.419,
+                          -28.3175 23.5397 112.915,
+                          -37.9646 29.013 111.595,
+                          -29.7679 34.4561 113.947,
+                          -28.3175 23.5397 112.915,
+                          -20.9642 -17.3841 105.566,
+                          -45.6507 -16.3674 97.8023,
+                          -28.3175 23.5397 112.915,
+                          -39.9257 111.885 106.216,
+                          -48.6535 78.9881 110.354,
+                          -57.2651 77.2886 106.979,
+                          -39.9257 111.885 106.216,
+                          -40.4825 77.8876 112.59,
+                          -48.6535 78.9881 110.354,
+                          -31.8564 143.356 90.9425,
+                          -39.9257 111.885 106.216,
+                          -62.9064 112.396 94.3275,
+                          -50.7335 143.131 81.5448,
+                          -62.9064 112.396 94.3275,
+                          -74.9108 112.781 69.1367,
+                          -31.8564 143.356 90.9425,
+                          -62.9064 112.396 94.3275,
+                          -50.7335 143.131 81.5448,
+                          -61.7147 143.007 62.7854,
+                          -74.9108 112.781 69.1367,
+                          -79.939 112.915 36.0129,
+                          -50.7335 143.131 81.5448,
+                          -74.9108 112.781 69.1367,
+                          -61.7147 143.007 62.7854,
+                          -85.9426 95.5969 4.24845,
+                          -82.3483 113.932 5.69428,
+                          -79.939 112.915 36.0129,
+                          -67.3485 141.452 37.8252,
+                          -79.939 112.915 36.0129,
+                          -82.3483 113.932 5.69428,
+                          -85.2058 93.7307 18.016,
+                          -85.9426 95.5969 4.24845,
+                          -79.939 112.915 36.0129,
+                          -84.9077 87.7317 32.054,
+                          -85.2058 93.7307 18.016,
+                          -79.939 112.915 36.0129,
+                          -61.7147 143.007 62.7854,
+                          -79.939 112.915 36.0129,
+                          -67.3485 141.452 37.8252,
+                          -85.3677 88.7782 -21.1588,
+                          -81.1095 114.943 -18.4956,
+                          -82.3483 113.932 5.69428,
+                          -69.7678 140.305 13.0911,
+                          -82.3483 113.932 5.69428,
+                          -81.1095 114.943 -18.4956,
+                          -85.6609 89.7553 -19.3134,
+                          -85.3677 88.7782 -21.1588,
+                          -82.3483 113.932 5.69428,
+                          -85.9426 95.5969 4.24845,
+                          -85.6609 89.7553 -19.3134,
+                          -82.3483 113.932 5.69428,
+                          -67.3485 141.452 37.8252,
+                          -82.3483 113.932 5.69428,
+                          -69.7678 140.305 13.0911,
+                          -74.1491 106.765 -39.9622,
+                          -72.1338 115.401 -38.2936,
+                          -81.1095 114.943 -18.4956,
+                          -68.3476 139.461 -8.39391,
+                          -81.1095 114.943 -18.4956,
+                          -72.1338 115.401 -38.2936,
+                          -75.5932 91.0743 -41.0762,
+                          -74.1491 106.765 -39.9622,
+                          -81.1095 114.943 -18.4956,
+                          -81.7463 89.7248 -31.6975,
+                          -75.5932 91.0743 -41.0762,
+                          -81.1095 114.943 -18.4956,
+                          -85.3677 88.7782 -21.1588,
+                          -81.7463 89.7248 -31.6975,
+                          -81.1095 114.943 -18.4956,
+                          -69.7678 140.305 13.0911,
+                          -81.1095 114.943 -18.4956,
+                          -68.3476 139.461 -8.39391,
+                          -67.7314 126.189 -34.3953,
+                          -68.3476 139.461 -8.39391,
+                          -72.1338 115.401 -38.2936,
+                          -75.649 78.567 -41.2221,
+                          -75.5932 91.0743 -41.0762,
+                          -81.7463 89.7248 -31.6975,
+                          -80.6016 77.4356 -34.4485,
+                          -81.7463 89.7248 -31.6975,
+                          -85.3677 88.7782 -21.1588,
+                          -75.2328 64.3271 -40.9931,
+                          -75.649 78.567 -41.2221,
+                          -81.7463 89.7248 -31.6975,
+                          -76.5696 64.4671 -39.4751,
+                          -75.2328 64.3271 -40.9931,
+                          -81.7463 89.7248 -31.6975,
+                          -77.84 64.603 -37.9042,
+                          -76.5696 64.4671 -39.4751,
+                          -81.7463 89.7248 -31.6975,
+                          -80.6016 77.4356 -34.4485,
+                          -77.84 64.603 -37.9042,
+                          -81.7463 89.7248 -31.6975,
+                          -18.4701 162.682 67.7629,
+                          -2.71217 169.187 36.0093,
+                          -1.5397 169.172 36.7644,
+                          -31.2948 162.316 62.1479,
+                          -3.53438 169.212 34.7115,
+                          -2.71217 169.187 36.0093,
+                          -18.4701 162.682 67.7629,
+                          -31.2948 162.316 62.1479,
+                          -2.71217 169.187 36.0093,
+                          -39.7111 162.03 51.6219,
+                          -3.80775 169.231 33.7722,
+                          -3.53438 169.212 34.7115,
+                          -31.2948 162.316 62.1479,
+                          -39.7111 162.03 51.6219,
+                          -3.53438 169.212 34.7115,
+                          -44.0521 161.388 37.5564,
+                          -3.92114 169.254 32.6716,
+                          -3.80775 169.231 33.7722,
+                          -39.7111 162.03 51.6219,
+                          -44.0521 161.388 37.5564,
+                          -3.80775 169.231 33.7722,
+                          -45.192 160.697 22.6931,
+                          -3.85007 169.281 31.3686,
+                          -3.92114 169.254 32.6716,
+                          -44.0521 161.388 37.5564,
+                          -45.192 160.697 22.6931,
+                          -3.92114 169.254 32.6716,
+                          -42.86 160.082 8.79737,
+                          -3.61036 169.305 30.2263,
+                          -3.85007 169.281 31.3686,
+                          -45.192 160.697 22.6931,
+                          -42.86 160.082 8.79737,
+                          -3.85007 169.281 31.3686,
+                          -16.4724 167.59 15.1264,
+                          -3.1901 169.327 29.2068,
+                          -3.61036 169.305 30.2263,
+                          -32.9985 160.962 -1.47427,
+                          -16.4724 167.59 15.1264,
+                          -3.61036 169.305 30.2263,
+                          -35.3138 159.641 -3.7465,
+                          -32.9985 160.962 -1.47427,
+                          -3.61036 169.305 30.2263,
+                          -42.86 160.082 8.79737,
+                          -35.3138 159.641 -3.7465,
+                          -3.61036 169.305 30.2263,
+                          -49.0559 149.572 -17.0027,
+                          -35.3138 159.641 -3.7465,
+                          -42.86 160.082 8.79737,
+                          -68.3476 139.461 -8.39391,
+                          -42.86 160.082 8.79737,
+                          -45.192 160.697 22.6931,
+                          -60.0203 137.977 -27.3098,
+                          -49.0559 149.572 -17.0027,
+                          -42.86 160.082 8.79737,
+                          -68.3476 139.461 -8.39391,
+                          -60.0203 137.977 -27.3098,
+                          -42.86 160.082 8.79737,
+                          -69.7678 140.305 13.0911,
+                          -45.192 160.697 22.6931,
+                          -44.0521 161.388 37.5564,
+                          -69.7678 140.305 13.0911,
+                          -68.3476 139.461 -8.39391,
+                          -45.192 160.697 22.6931,
+                          -67.3485 141.452 37.8252,
+                          -44.0521 161.388 37.5564,
+                          -39.7111 162.03 51.6219,
+                          -67.3485 141.452 37.8252,
+                          -69.7678 140.305 13.0911,
+                          -44.0521 161.388 37.5564,
+                          -61.7147 143.007 62.7854,
+                          -39.7111 162.03 51.6219,
+                          -31.2948 162.316 62.1479,
+                          -61.7147 143.007 62.7854,
+                          -67.3485 141.452 37.8252,
+                          -39.7111 162.03 51.6219,
+                          -50.7335 143.131 81.5448,
+                          -31.2948 162.316 62.1479,
+                          -18.4701 162.682 67.7629,
+                          -50.7335 143.131 81.5448,
+                          -61.7147 143.007 62.7854,
+                          -31.2948 162.316 62.1479,
+                          -31.8564 143.356 90.9425,
+                          -50.7335 143.131 81.5448,
+                          -18.4701 162.682 67.7629,
+                          -61.227 136.411 -28.4289,
+                          -60.0203 137.977 -27.3098,
+                          -68.3476 139.461 -8.39391,
+                          -67.7314 126.189 -34.3953,
+                          -61.227 136.411 -28.4289,
+                          -68.3476 139.461 -8.39391,
+                          -79.5916 -9.0764 58.8184,
+                          -83.3861 3.87721 40.5514,
+                          -84.2967 19.7488 53.6572,
+                          -86.9046 11.9664 33.1138,
+                          -83.3861 3.87721 40.5514,
+                          -79.5916 -9.0764 58.8184,
+                          -86.9046 11.9664 33.1138,
+                          -83.4462 4.21515 40.1792,
+                          -83.3861 3.87721 40.5514,
+                          -81.5949 -8.99321 60.1144,
+                          -79.5916 -9.0764 58.8184,
+                          -65.9496 -15.1986 85.0548,
+                          -81.5949 -8.99321 60.1144,
+                          -86.9046 11.9664 33.1138,
+                          -79.5916 -9.0764 58.8184,
+                          -64.6038 -15.1758 89.4083,
+                          -65.9496 -15.1986 85.0548,
+                          -45.6507 -16.3674 97.8023,
+                          -81.5949 -8.99321 60.1144,
+                          -65.9496 -15.1986 85.0548,
+                          -64.6038 -15.1758 89.4083,
+                          -33.8591 -16.7893 104.531,
+                          -45.6507 -16.3674 97.8023,
+                          -20.9642 -17.3841 105.566,
+                          -64.6038 -15.1758 89.4083,
+                          -45.6507 -16.3674 97.8023,
+                          -33.8591 -16.7893 104.531,
+                          -33.8591 -16.7893 104.531,
+                          -20.9642 -17.3841 105.566,
+                          -0.00101065 -17.577 110.421,
+                          -80.9515 65.0305 -32.1047,
+                          -77.84 64.603 -37.9042,
+                          -80.6016 77.4356 -34.4485,
+                          -86.9046 11.9664 33.1138,
+                          -84.7175 11.599 32.4235,
+                          -84.1508 8.15085 35.9712,
+                          -83.3216 7.94414 36.2744,
+                          -83.494 4.55423 39.8092,
+                          -84.1508 8.15085 35.9712,
+                          -86.9046 11.9664 33.1138,
+                          -84.1508 8.15085 35.9712,
+                          -83.494 4.55423 39.8092,
+                          -86.9046 11.9664 33.1138,
+                          -83.494 4.55423 39.8092,
+                          -83.4462 4.21515 40.1792,
+                          -90.9182 45.7361 39.3341,
+                          -89.1536 45.7781 45.4317,
+                          -89.5722 69.2939 35.9017,
+                          11.1313 38.7451 124.468,
+                          6.67121 70.9964 119.33,
+                          6.49835 70.9964 119.345,
+                          11.1313 38.7451 124.468,
+                          6.49835 70.9964 119.345,
+                          -11.1333 38.7453 124.468,
+                          15.5507 7.14408 135.318,
+                          -15.5527 6.59799 134.671,
+                          15.5507 6.59799 134.671,
+                          16.3077 6.9406 134.608,
+                          15.5507 7.14408 135.318,
+                          15.5507 6.59799 134.671,
+                          15.5507 7.14408 135.318,
+                          -15.5527 7.13273 135.313,
+                          -15.5527 6.59799 134.671,
+                          -16.306 6.93638 134.609,
+                          -15.5527 6.59799 134.671,
+                          -15.5527 7.13273 135.313,
+                          11.1313 38.7451 124.468,
+                          -11.1333 38.7453 124.468,
+                          -15.5515 7.98014 135.319,
+                          -16.2364 7.94534 135.032,
+                          -15.5515 7.98014 135.319,
+                          -11.1333 38.7453 124.468,
+                          15.5494 7.98014 135.319,
+                          11.1313 38.7451 124.468,
+                          -15.5515 7.98014 135.319,
+                          -15.5527 7.13273 135.313,
+                          15.5494 7.98014 135.319,
+                          -15.5515 7.98014 135.319,
+                          -16.306 6.93638 134.609,
+                          -15.5527 7.13273 135.313,
+                          -15.5515 7.98014 135.319,
+                          -16.306 6.93638 134.609,
+                          -15.5515 7.98014 135.319,
+                          -16.2364 7.94534 135.032,
+                          -16.2364 7.94534 135.032,
+                          -11.1333 38.7453 124.468,
+                          -13.0515 32.1433 125.276,
+                          13.0494 32.1433 125.276,
+                          11.1313 38.7451 124.468,
+                          15.5494 7.98014 135.319,
+                          16.2308 7.94769 135.034,
+                          15.5494 7.98014 135.319,
+                          16.5406 7.7048 134.41,
+                          15.5507 7.14408 135.318,
+                          16.5406 7.7048 134.41,
+                          15.5494 7.98014 135.319,
+                          16.2308 7.94769 135.034,
+                          13.0494 32.1433 125.276,
+                          15.5494 7.98014 135.319,
+                          15.5507 7.14408 135.318,
+                          15.5494 7.98014 135.319,
+                          -15.5527 7.13273 135.313,
+                          16.2308 7.94769 135.034,
+                          16.5406 7.7048 134.41,
+                          13.0494 32.1433 125.276,
+                          16.3077 6.9406 134.608,
+                          16.5406 7.7048 134.41,
+                          15.5507 7.14408 135.318,
+                          -16.2364 7.94534 135.032,
+                          -13.0515 32.1433 125.276,
+                          -16.5427 7.7048 134.41,
+                          -16.306 6.93638 134.609,
+                          -16.2364 7.94534 135.032,
+                          -16.5427 7.7048 134.41,
+                          60.9342 85.9514 116.733,
+                          70.885 76.7819 106.327,
+                          70.7186 79.0868 107.594,
+                          61.5566 87.3666 117.918,
+                          60.9342 85.9514 116.733,
+                          70.7186 79.0868 107.594,
+                          60.9342 85.9514 116.733,
+                          71.0933 74.6307 105.389,
+                          70.885 76.7819 106.327,
+                          61.6102 83.7075 114.707,
+                          71.2898 71.7646 103.765,
+                          71.0933 74.6307 105.389,
+                          60.9342 85.9514 116.733,
+                          61.6102 83.7075 114.707,
+                          71.0933 74.6307 105.389,
+                          61.808 82.1146 110.677,
+                          70.9315 71.2814 101.682,
+                          71.2898 71.7646 103.765,
+                          62.0334 82.105 112.684,
+                          61.808 82.1146 110.677,
+                          71.2898 71.7646 103.765,
+                          61.6102 83.7075 114.707,
+                          62.0334 82.105 112.684,
+                          71.2898 71.7646 103.765,
+                          61.5143 82.2577 110.852,
+                          61.808 82.1146 110.677,
+                          62.0334 82.105 112.684,
+                          46.9241 83.4564 118.189,
+                          62.0334 82.105 112.684,
+                          61.6102 83.7075 114.707,
+                          46.5698 83.4575 116.351,
+                          61.5143 82.2577 110.852,
+                          62.0334 82.105 112.684,
+                          46.9241 83.4564 118.189,
+                          46.5698 83.4575 116.351,
+                          62.0334 82.105 112.684,
+                          46.9061 84.8731 120.105,
+                          61.6102 83.7075 114.707,
+                          60.9342 85.9514 116.733,
+                          46.9061 84.8731 120.105,
+                          46.9241 83.4564 118.189,
+                          61.6102 83.7075 114.707,
+                          61.5566 87.3666 117.918,
+                          60.5151 87.8226 118.668,
+                          60.9342 85.9514 116.733,
+                          46.7477 86.8585 122.049,
+                          60.9342 85.9514 116.733,
+                          60.5151 87.8226 118.668,
+                          46.7477 86.8585 122.049,
+                          46.9061 84.8731 120.105,
+                          60.9342 85.9514 116.733,
+                          48.2296 88.864 123.717,
+                          46.7477 86.8585 122.049,
+                          60.5151 87.8226 118.668,
+                          46.1734 83.382 116.437,
+                          46.5698 83.4575 116.351,
+                          46.9241 83.4564 118.189,
+                          26.2971 75.673 120.474,
+                          46.9241 83.4564 118.189,
+                          46.9061 84.8731 120.105,
+                          25.2838 75.3574 118.708,
+                          46.1734 83.382 116.437,
+                          46.9241 83.4564 118.189,
+                          26.2971 75.673 120.474,
+                          25.2838 75.3574 118.708,
+                          46.9241 83.4564 118.189,
+                          27.7145 77.963 121.717,
+                          46.9061 84.8731 120.105,
+                          46.7477 86.8585 122.049,
+                          27.7145 77.963 121.717,
+                          26.2971 75.673 120.474,
+                          46.9061 84.8731 120.105,
+                          48.2296 88.864 123.717,
+                          46.7851 88.5868 123.961,
+                          46.7477 86.8585 122.049,
+                          28.5995 79.5649 122.379,
+                          46.7477 86.8585 122.049,
+                          46.7851 88.5868 123.961,
+                          28.5995 79.5649 122.379,
+                          27.7145 77.963 121.717,
+                          46.7477 86.8585 122.049,
+                          29.5893 81.152 123.255,
+                          28.5995 79.5649 122.379,
+                          46.7851 88.5868 123.961,
+                          -70.887 76.7819 106.327,
+                          -61.5586 87.3666 117.918,
+                          -70.7206 79.0868 107.594,
+                          -70.887 76.7819 106.327,
+                          -60.5171 87.8226 118.668,
+                          -61.5586 87.3666 117.918,
+                          -70.887 76.7819 106.327,
+                          -60.9362 85.9514 116.733,
+                          -60.5171 87.8226 118.668,
+                          -48.2316 88.864 123.717,
+                          -60.5171 87.8226 118.668,
+                          -60.9362 85.9514 116.733,
+                          -71.0953 74.6307 105.389,
+                          -61.6122 83.7075 114.707,
+                          -60.9362 85.9514 116.733,
+                          -46.7497 86.8585 122.049,
+                          -60.9362 85.9514 116.733,
+                          -61.6122 83.7075 114.707,
+                          -70.887 76.7819 106.327,
+                          -71.0953 74.6307 105.389,
+                          -60.9362 85.9514 116.733,
+                          -46.7871 88.5868 123.961,
+                          -60.9362 85.9514 116.733,
+                          -46.7497 86.8585 122.049,
+                          -48.2316 88.864 123.717,
+                          -60.9362 85.9514 116.733,
+                          -46.7871 88.5868 123.961,
+                          -71.2919 71.7646 103.765,
+                          -62.0354 82.105 112.684,
+                          -61.6122 83.7075 114.707,
+                          -46.9081 84.8731 120.105,
+                          -61.6122 83.7075 114.707,
+                          -62.0354 82.105 112.684,
+                          -71.0953 74.6307 105.389,
+                          -71.2919 71.7646 103.765,
+                          -61.6122 83.7075 114.707,
+                          -46.7497 86.8585 122.049,
+                          -61.6122 83.7075 114.707,
+                          -46.9081 84.8731 120.105,
+                          -70.9335 71.2814 101.682,
+                          -61.8101 82.1146 110.677,
+                          -62.0354 82.105 112.684,
+                          -46.9261 83.4564 118.189,
+                          -62.0354 82.105 112.684,
+                          -61.8101 82.1146 110.677,
+                          -71.2919 71.7646 103.765,
+                          -70.9335 71.2814 101.682,
+                          -62.0354 82.105 112.684,
+                          -46.9081 84.8731 120.105,
+                          -62.0354 82.105 112.684,
+                          -46.9261 83.4564 118.189,
+                          -61.5164 82.2577 110.852,
+                          -46.9261 83.4564 118.189,
+                          -61.8101 82.1146 110.677,
+                          -46.7497 86.8585 122.049,
+                          -28.6015 79.5649 122.379,
+                          -29.5914 81.152 123.255,
+                          -46.7871 88.5868 123.961,
+                          -46.7497 86.8585 122.049,
+                          -29.5914 81.152 123.255,
+                          -46.7497 86.8585 122.049,
+                          -27.7166 77.963 121.717,
+                          -28.6015 79.5649 122.379,
+                          -46.9081 84.8731 120.105,
+                          -26.2991 75.673 120.474,
+                          -27.7166 77.963 121.717,
+                          -46.7497 86.8585 122.049,
+                          -46.9081 84.8731 120.105,
+                          -27.7166 77.963 121.717,
+                          -46.1754 83.382 116.437,
+                          -25.2858 75.3574 118.708,
+                          -26.2991 75.673 120.474,
+                          -46.5718 83.4575 116.351,
+                          -46.1754 83.382 116.437,
+                          -26.2991 75.673 120.474,
+                          -46.9261 83.4564 118.189,
+                          -46.5718 83.4575 116.351,
+                          -26.2991 75.673 120.474,
+                          -46.9081 84.8731 120.105,
+                          -46.9261 83.4564 118.189,
+                          -26.2991 75.673 120.474,
+                          -61.5164 82.2577 110.852,
+                          -46.5718 83.4575 116.351,
+                          -46.9261 83.4564 118.189 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.51 0.397 0.107
+    }
+    Separator {
+        Normal {
+            vector      [ -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.5 0.866025,
+                          0 0.5 0.866025,
+                          0 0.5 0.866025,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          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 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.866025 -0.5,
+                          0 0.866025 -0.5,
+                          0 0.866025 -0.5,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.866025 -0.5,
+                          0 0.866025 -0.5,
+                          0 0.866025 -0.5,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 0.866025 0.5,
+                          0 0.866025 0.5,
+                          0 0.866025 0.5,
+                          0 0.866025 0.5,
+                          0 0.866025 0.5,
+                          0 0.866025 0.5,
+                          0 0.5 0.866025,
+                          0 0.5 0.866025,
+                          0 0.5 0.866025,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -44.5 -16 -16,
+                          -44.5 -16 16,
+                          -44.5 4.28719 16,
+                          -17 -16 16,
+                          -44.5 4.28719 16,
+                          -44.5 -16 16,
+                          -44.5 4.28719 -16,
+                          -44.5 -16 -16,
+                          -44.5 4.28719 16,
+                          -44.5 11.7128 11.7128,
+                          -44.5 4.28719 -16,
+                          -44.5 4.28719 16,
+                          -17 4.28719 16,
+                          -44.5 11.7128 11.7128,
+                          -44.5 4.28719 16,
+                          -17 4.28719 16,
+                          -44.5 4.28719 16,
+                          -17 -16 16,
+                          -17 -16 16,
+                          -44.5 -16 16,
+                          -44.5 -16 -16,
+                          -17 4.28719 -16,
+                          -44.5 -16 -16,
+                          -44.5 4.28719 -16,
+                          -17 -16 -16,
+                          -44.5 -16 -16,
+                          -17 4.28719 -16,
+                          -17 -16 16,
+                          -44.5 -16 -16,
+                          -17 -16 -16,
+                          -44.5 11.7128 11.7128,
+                          -44.5 11.7128 -11.7128,
+                          -44.5 4.28719 -16,
+                          -17 11.7128 -11.7128,
+                          -44.5 4.28719 -16,
+                          -44.5 11.7128 -11.7128,
+                          -17 11.7128 -11.7128,
+                          -17 4.28719 -16,
+                          -44.5 4.28719 -16,
+                          -44.5 16 4.28719,
+                          -44.5 16 -4.28719,
+                          -44.5 11.7128 -11.7128,
+                          -17 16 -4.28719,
+                          -44.5 11.7128 -11.7128,
+                          -44.5 16 -4.28719,
+                          -44.5 11.7128 11.7128,
+                          -44.5 16 4.28719,
+                          -44.5 11.7128 -11.7128,
+                          -17 11.7128 -11.7128,
+                          -44.5 11.7128 -11.7128,
+                          -17 16 -4.28719,
+                          -17 16 4.28719,
+                          -44.5 16 -4.28719,
+                          -44.5 16 4.28719,
+                          -17 16 -4.28719,
+                          -44.5 16 -4.28719,
+                          -17 16 4.28719,
+                          -17 11.7128 11.7128,
+                          -44.5 16 4.28719,
+                          -44.5 11.7128 11.7128,
+                          -17 16 4.28719,
+                          -44.5 16 4.28719,
+                          -17 11.7128 11.7128,
+                          -17 11.7128 11.7128,
+                          -44.5 11.7128 11.7128,
+                          -17 4.28719 16,
+                          -17 -16 16,
+                          -17 -16 -16,
+                          -17 4.28719 -16,
+                          -17 4.28719 16,
+                          -17 -16 16,
+                          -17 4.28719 -16,
+                          -17 11.7128 -11.7128,
+                          -17 4.28719 16,
+                          -17 4.28719 -16,
+                          -17 11.7128 -11.7128,
+                          -17 11.7128 11.7128,
+                          -17 4.28719 16,
+                          -17 16 -4.28719,
+                          -17 16 4.28719,
+                          -17 11.7128 11.7128,
+                          -17 11.7128 -11.7128,
+                          -17 16 -4.28719,
+                          -17 11.7128 11.7128 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    1 0.03 0.03
+    }
+    Separator {
+        Normal {
+            vector      [ -1 0 -1.22461e-16,
+                          -1 0 -1.22461e-16,
+                          -1 0 -1.22461e-16,
+                          -1.22461e-16 1.22461e-16 1,
+                          -1.22461e-16 1.22461e-16 1,
+                          -8.65927e-17 -0.707107 0.707107,
+                          -1 0 -1.22461e-16,
+                          -1 0 -1.22461e-16,
+                          -1 0 -1.22461e-16,
+                          -1 0 -1.22461e-16,
+                          -1 0 -1.22461e-16,
+                          -1 0 -1.22461e-16,
+                          -8.65927e-17 0.707107 0.707107,
+                          -8.65927e-17 0.707107 0.707107,
+                          -1.22461e-16 1.22461e-16 1,
+                          -1.22461e-16 1.22461e-16 1,
+                          -8.65927e-17 0.707107 0.707107,
+                          -1.22461e-16 1.22461e-16 1,
+                          -1 0 -1.22461e-16,
+                          -1 0 -1.22461e-16,
+                          -1 0 -1.22461e-16,
+                          -8.65927e-17 -0.707107 0.707107,
+                          -8.65927e-17 -0.707107 0.707107,
+                          0 -1 1.83691e-16,
+                          -8.65927e-17 -0.707107 0.707107,
+                          -1.22461e-16 1.22461e-16 1,
+                          -8.65927e-17 -0.707107 0.707107,
+                          0 -1 1.83691e-16,
+                          0 -1 1.83691e-16,
+                          8.65927e-17 -0.707107 -0.707107,
+                          -8.65927e-17 -0.707107 0.707107,
+                          0 -1 1.83691e-16,
+                          0 -1 1.83691e-16,
+                          8.65927e-17 -0.707107 -0.707107,
+                          8.65927e-17 -0.707107 -0.707107,
+                          1.22461e-16 -2.44921e-16 -1,
+                          0 -1 1.83691e-16,
+                          8.65927e-17 -0.707107 -0.707107,
+                          8.65927e-17 -0.707107 -0.707107,
+                          -1 0 -1.22461e-16,
+                          -1 0 -1.22461e-16,
+                          -1 0 -1.22461e-16,
+                          1.22461e-16 0 -1,
+                          1.22461e-16 0 -1,
+                          8.65927e-17 0.707107 -0.707107,
+                          8.65927e-17 -0.707107 -0.707107,
+                          1.22461e-16 -2.44921e-16 -1,
+                          1.22461e-16 -2.44921e-16 -1,
+                          -1 0 -1.22461e-16,
+                          -1 0 -1.22461e-16,
+                          -1 0 -1.22461e-16,
+                          8.65927e-17 0.707107 -0.707107,
+                          8.65927e-17 0.707107 -0.707107,
+                          0 1 -6.12303e-17,
+                          8.65927e-17 0.707107 -0.707107,
+                          1.22461e-16 0 -1,
+                          8.65927e-17 0.707107 -0.707107,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          -8.65927e-17 0.707107 0.707107,
+                          0 1 -6.12303e-17,
+                          8.65927e-17 0.707107 -0.707107,
+                          0 1 -6.12303e-17,
+                          -8.65927e-17 0.707107 0.707107,
+                          0 1 -6.12303e-17,
+                          -8.65927e-17 0.707107 0.707107,
+                          1 0 1.22461e-16,
+                          1 0 1.22461e-16,
+                          1 0 1.22461e-16,
+                          1 0 1.22461e-16,
+                          1 0 1.22461e-16,
+                          1 0 1.22461e-16,
+                          1 0 1.22461e-16,
+                          1 0 1.22461e-16,
+                          1 0 1.22461e-16,
+                          1 0 1.22461e-16,
+                          1 0 1.22461e-16,
+                          1 0 1.22461e-16,
+                          1 0 1.22461e-16,
+                          1 0 1.22461e-16,
+                          1 0 1.22461e-16,
+                          1 0 1.22461e-16,
+                          1 0 1.22461e-16,
+                          1 0 1.22461e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -71.779 -8.13173 -8.13173,
+                          -71.779 -8.13173 8.13173,
+                          -71.779 -6.39488e-14 11.5,
+                          42.7 -6.39488e-14 11.5,
+                          -71.779 -6.39488e-14 11.5,
+                          -71.779 -8.13173 8.13173,
+                          -71.779 -6.39488e-14 -11.5,
+                          -71.779 -8.13173 -8.13173,
+                          -71.779 -6.39488e-14 11.5,
+                          -71.779 8.13173 8.13173,
+                          -71.779 -6.39488e-14 -11.5,
+                          -71.779 -6.39488e-14 11.5,
+                          42.7 8.13173 8.13173,
+                          -71.779 8.13173 8.13173,
+                          -71.779 -6.39488e-14 11.5,
+                          42.7 -6.39488e-14 11.5,
+                          42.7 8.13173 8.13173,
+                          -71.779 -6.39488e-14 11.5,
+                          -71.779 -8.13173 -8.13173,
+                          -71.779 -11.5 -1.52876e-14,
+                          -71.779 -8.13173 8.13173,
+                          42.7 -8.13173 8.13173,
+                          -71.779 -8.13173 8.13173,
+                          -71.779 -11.5 -1.52876e-14,
+                          42.7 -8.13173 8.13173,
+                          42.7 -6.39488e-14 11.5,
+                          -71.779 -8.13173 8.13173,
+                          42.7 -11.5 -1.26843e-15,
+                          -71.779 -11.5 -1.52876e-14,
+                          -71.779 -8.13173 -8.13173,
+                          42.7 -8.13173 8.13173,
+                          -71.779 -11.5 -1.52876e-14,
+                          42.7 -11.5 -1.26843e-15,
+                          42.7 -8.13173 -8.13173,
+                          -71.779 -8.13173 -8.13173,
+                          -71.779 -6.39488e-14 -11.5,
+                          42.7 -11.5 -1.26843e-15,
+                          -71.779 -8.13173 -8.13173,
+                          42.7 -8.13173 -8.13173,
+                          -71.779 8.13173 8.13173,
+                          -71.779 8.13173 -8.13173,
+                          -71.779 -6.39488e-14 -11.5,
+                          42.7 -6.39488e-14 -11.5,
+                          -71.779 -6.39488e-14 -11.5,
+                          -71.779 8.13173 -8.13173,
+                          42.7 -8.13173 -8.13173,
+                          -71.779 -6.39488e-14 -11.5,
+                          42.7 -6.39488e-14 -11.5,
+                          -71.779 8.13173 8.13173,
+                          -71.779 11.5 -1.52876e-14,
+                          -71.779 8.13173 -8.13173,
+                          42.7 8.13173 -8.13173,
+                          -71.779 8.13173 -8.13173,
+                          -71.779 11.5 -1.52876e-14,
+                          42.7 8.13173 -8.13173,
+                          42.7 -6.39488e-14 -11.5,
+                          -71.779 8.13173 -8.13173,
+                          42.7 11.5 -1.26843e-15,
+                          -71.779 11.5 -1.52876e-14,
+                          -71.779 8.13173 8.13173,
+                          42.7 11.5 -1.26843e-15,
+                          42.7 8.13173 -8.13173,
+                          -71.779 11.5 -1.52876e-14,
+                          42.7 8.13173 8.13173,
+                          42.7 11.5 -1.26843e-15,
+                          -71.779 8.13173 8.13173,
+                          42.7 -6.39488e-14 11.5,
+                          42.7 -6.39488e-14 -11.5,
+                          42.7 8.13173 -8.13173,
+                          42.7 -8.13173 8.13173,
+                          42.7 -6.39488e-14 -11.5,
+                          42.7 -6.39488e-14 11.5,
+                          42.7 -8.13173 8.13173,
+                          42.7 -8.13173 -8.13173,
+                          42.7 -6.39488e-14 -11.5,
+                          42.7 8.13173 8.13173,
+                          42.7 8.13173 -8.13173,
+                          42.7 11.5 -1.26843e-15,
+                          42.7 -6.39488e-14 11.5,
+                          42.7 8.13173 -8.13173,
+                          42.7 8.13173 8.13173,
+                          42.7 -8.13173 8.13173,
+                          42.7 -11.5 -1.26843e-15,
+                          42.7 -8.13173 -8.13173 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.55 0.393802 0.197146
+    }
+    Separator {
+        Normal {
+            vector      [ -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          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,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -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 -0.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          -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,
+                          -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,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.707107 -0.707107,
+                          0 -0.707107 -0.707107,
+                          0 -0.707107 -0.707107,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 -0.707107 -0.707107,
+                          0 -0.707107 -0.707107,
+                          0 -0.707107 -0.707107,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -51 17.5 -16,
+                          -51 6.5 16,
+                          -51 17.5 16,
+                          -45 17.5 16,
+                          -51 17.5 16,
+                          -51 6.5 16,
+                          -45 17.5 -16,
+                          -51 17.5 -16,
+                          -51 17.5 16,
+                          -45 17.5 -16,
+                          -51 17.5 16,
+                          -45 17.5 16,
+                          -51 17.5 -16,
+                          -51 -1.5 8,
+                          -51 6.5 16,
+                          -45 6.5 16,
+                          -51 6.5 16,
+                          -51 -1.5 8,
+                          -45 6.5 16,
+                          -45 17.5 16,
+                          -51 6.5 16,
+                          -51 17.5 -16,
+                          -51 -1.5 2.59808,
+                          -51 -1.5 8,
+                          -45 -1.5 2.59808,
+                          -51 -1.5 8,
+                          -51 -1.5 2.59808,
+                          -45 -1.5 8,
+                          -51 -1.5 8,
+                          -45 -1.5 2.59808,
+                          -45 6.5 16,
+                          -51 -1.5 8,
+                          -45 -1.5 8,
+                          -51 17.5 -16,
+                          -51 -1.5 -2.59808,
+                          -51 -1.5 2.59808,
+                          -45 -1.5 -2.59808,
+                          -51 -1.5 2.59808,
+                          -51 -1.5 -2.59808,
+                          -45 -1.5 2.59808,
+                          -51 -1.5 2.59808,
+                          -45 -1.5 -2.59808,
+                          -51 17.5 -16,
+                          -51 -1.5 -8,
+                          -51 -1.5 -2.59808,
+                          -45 -1.5 -8,
+                          -51 -1.5 -2.59808,
+                          -51 -1.5 -8,
+                          -45 -1.5 -2.59808,
+                          -51 -1.5 -2.59808,
+                          -45 -1.5 -8,
+                          -51 17.5 -16,
+                          -51 6.5 -16,
+                          -51 -1.5 -8,
+                          -45 -1.5 -8,
+                          -51 -1.5 -8,
+                          -51 6.5 -16,
+                          -45 6.5 -16,
+                          -51 6.5 -16,
+                          -51 17.5 -16,
+                          -45 -1.5 -8,
+                          -51 6.5 -16,
+                          -45 6.5 -16,
+                          -45 6.5 -16,
+                          -51 17.5 -16,
+                          -45 17.5 -16,
+                          -45 6.5 -16,
+                          -45 17.5 -16,
+                          -45 17.5 16,
+                          -45 -1.5 -8,
+                          -45 6.5 -16,
+                          -45 17.5 16,
+                          -45 -1.5 -2.59808,
+                          -45 -1.5 -8,
+                          -45 17.5 16,
+                          -45 -1.5 2.59808,
+                          -45 -1.5 -2.59808,
+                          -45 17.5 16,
+                          -45 -1.5 8,
+                          -45 -1.5 2.59808,
+                          -45 17.5 16,
+                          -45 6.5 16,
+                          -45 -1.5 8,
+                          -45 17.5 16 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.324 0.577 0.81
+    }
+    Separator {
+        Normal {
+            vector      [ 1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -1 1.22461e-16,
+                          0 -1 1.22461e-16,
+                          0 6.12303e-17 1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -1.83691e-16 -1,
+                          0 -1.83691e-16 -1,
+                          0 -1 1.22461e-16,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -1.83691e-16 -1,
+                          0 -1 1.22461e-16,
+                          0 -1 1.22461e-16,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 1 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 6.12303e-17 1,
+                          0 -1 1.22461e-16,
+                          0 6.12303e-17 1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 1 -2.44921e-16,
+                          0 1 -2.44921e-16,
+                          0 -1.83691e-16 -1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 6.12303e-17 1,
+                          0 1 0,
+                          0 1 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 1 -2.44921e-16,
+                          0 -1.83691e-16 -1,
+                          0 -1.83691e-16 -1,
+                          0.965926 -3.28039e-12 0.258819,
+                          1 6.98623e-09 -5.4897e-19,
+                          1 -1.52136e-18 1.20033e-07,
+                          0.98078 0.195119 1.25116e-10,
+                          1 1.52137e-18 -1.20033e-07,
+                          1 8.34122e-09 6.73597e-19,
+                          0.965926 -3.28039e-12 0.258819,
+                          0.98078 0.195119 1.09329e-10,
+                          1 6.98623e-09 -5.4897e-19,
+                          0.98078 -0.195119 -1.25116e-10,
+                          1 -1.52136e-18 1.20033e-07,
+                          1 -8.34122e-09 -6.73598e-19,
+                          0.965926 -3.28039e-12 0.258819,
+                          1 -1.52136e-18 1.20033e-07,
+                          0.98078 -0.195119 -1.25116e-10,
+                          0.965926 3.28041e-12 -0.258819,
+                          1 -6.98622e-09 5.48965e-19,
+                          1 1.52137e-18 -1.20033e-07,
+                          0.98078 -0.195119 -1.09329e-10,
+                          1 -6.98622e-09 5.48965e-19,
+                          0.965926 3.28041e-12 -0.258819,
+                          0.965926 3.28041e-12 -0.258819,
+                          1 1.52137e-18 -1.20033e-07,
+                          0.98078 0.195119 1.25116e-10,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0.707107 -0.707107 8.65927e-17,
+                          0.707107 -0.707107 8.65927e-17,
+                          0.707107 4.32964e-17 0.707107,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0.707107 -1.29889e-16 -0.707107,
+                          0.707107 -1.29889e-16 -0.707107,
+                          0.707107 -0.707107 8.65927e-17,
+                          0.707107 -1.29889e-16 -0.707107,
+                          0.707107 -0.707107 8.65927e-17,
+                          0.707107 -0.707107 8.65927e-17,
+                          0.707107 4.32964e-17 0.707107,
+                          0.707107 4.32964e-17 0.707107,
+                          0.707107 0.707107 0,
+                          0.707107 4.32964e-17 0.707107,
+                          0.707107 -0.707107 8.65927e-17,
+                          0.707107 4.32964e-17 0.707107,
+                          0.707107 0.707107 -1.73185e-16,
+                          0.707107 0.707107 -1.73185e-16,
+                          0.707107 -1.29889e-16 -0.707107,
+                          0.707107 4.32964e-17 0.707107,
+                          0.707107 0.707107 0,
+                          0.707107 0.707107 0,
+                          0.707107 0.707107 -1.73185e-16,
+                          0.707107 -1.29889e-16 -0.707107,
+                          0.707107 -1.29889e-16 -0.707107,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -1.83691e-16 -1,
+                          0 1.48617e-11 -1,
+                          0 1 -2.44921e-16,
+                          0.258819 1.22427e-11 -0.965926,
+                          3.78688e-16 1 4.56456e-09,
+                          1.02604e-16 1.26746e-11 -1,
+                          0 1 -2.44921e-16,
+                          0 -1.83691e-16 -1,
+                          0 1 -2.44921e-16,
+                          0 -1.48614e-11 1,
+                          0 1 -4.17479e-18,
+                          0 1 -1.22461e-16,
+                          0.258819 1.22427e-11 -0.965926,
+                          0.258791 0.965933 3.68722e-09,
+                          3.78688e-16 1 4.56456e-09,
+                          1.02604e-16 -1.26745e-11 1,
+                          -1.33767e-16 1 -4.53921e-09,
+                          0.258791 0.965933 3.89604e-10,
+                          0 -1 1.22461e-16,
+                          0 -1 1.22461e-16,
+                          0 1.48617e-11 -1,
+                          0.258791 -0.965933 -3.89604e-10,
+                          1.02604e-16 1.26746e-11 -1,
+                          -1.33767e-16 -1 4.53921e-09,
+                          0 -1.83691e-16 -1,
+                          0 -1 1.22461e-16,
+                          0 1.48617e-11 -1,
+                          0.258791 -0.965933 -3.89604e-10,
+                          0.258819 1.22427e-11 -0.965926,
+                          1.02604e-16 1.26746e-11 -1,
+                          0 6.12303e-17 1,
+                          0 -1 1.22461e-16,
+                          0 -1 -3.21629e-16,
+                          0.258819 -1.22426e-11 0.965926,
+                          0.258791 -0.965933 -3.68722e-09,
+                          3.78688e-16 -1 -4.56456e-09,
+                          0 6.12303e-17 1,
+                          0 -1.48614e-11 1,
+                          0 -1 1.22461e-16,
+                          0.258819 -1.22426e-11 0.965926,
+                          3.78688e-16 -1 -4.56456e-09,
+                          1.02604e-16 -1.26745e-11 1,
+                          0 6.12303e-17 1,
+                          0 1 -4.17479e-18,
+                          0 -1.48614e-11 1,
+                          0.258819 1.22427e-11 -0.965926,
+                          0.499958 0.86605 2.65874e-09,
+                          0.258791 0.965933 3.68722e-09,
+                          0.258819 -1.22426e-11 0.965926,
+                          0.258791 0.965933 3.89604e-10,
+                          0.499958 0.86605 2.65874e-09,
+                          0.258819 -1.22426e-11 0.965926,
+                          1.02604e-16 -1.26745e-11 1,
+                          0.258791 0.965933 3.89604e-10,
+                          0.5 1.09765e-11 -0.866025,
+                          0.707065 0.707149 1.64246e-09,
+                          0.499958 0.86605 2.65874e-09,
+                          0.5 -1.09764e-11 0.866025,
+                          0.499958 0.86605 2.65874e-09,
+                          0.707065 0.707149 2.05186e-09,
+                          0.258819 1.22427e-11 -0.965926,
+                          0.5 1.09765e-11 -0.866025,
+                          0.499958 0.86605 2.65874e-09,
+                          0.258819 -1.22426e-11 0.965926,
+                          0.499958 0.86605 2.65874e-09,
+                          0.5 -1.09764e-11 0.866025,
+                          0.707107 8.96226e-12 -0.707107,
+                          0.831437 0.55562 9.79103e-10,
+                          0.707065 0.707149 1.64246e-09,
+                          0.707107 -8.96221e-12 0.707107,
+                          0.707065 0.707149 2.05186e-09,
+                          0.831437 0.55562 1.01792e-09,
+                          0.5 1.09765e-11 -0.866025,
+                          0.707107 8.96226e-12 -0.707107,
+                          0.707065 0.707149 1.64246e-09,
+                          0.5 -1.09764e-11 0.866025,
+                          0.707065 0.707149 2.05186e-09,
+                          0.707107 -8.96221e-12 0.707107,
+                          0.866025 6.33728e-12 -0.5,
+                          0.923861 0.382729 4.59927e-10,
+                          0.831437 0.55562 9.79103e-10,
+                          0.866025 -6.33724e-12 0.5,
+                          0.831437 0.55562 1.01792e-09,
+                          0.923861 0.382729 4.50399e-10,
+                          0.707107 8.96226e-12 -0.707107,
+                          0.866025 6.33728e-12 -0.5,
+                          0.831437 0.55562 9.79103e-10,
+                          0.707107 -8.96221e-12 0.707107,
+                          0.831437 0.55562 1.01792e-09,
+                          0.866025 -6.33724e-12 0.5,
+                          0.965926 3.28041e-12 -0.258819,
+                          0.98078 0.195119 1.25116e-10,
+                          0.923861 0.382729 4.59927e-10,
+                          0.965926 -3.28039e-12 0.258819,
+                          0.923861 0.382729 4.50399e-10,
+                          0.98078 0.195119 1.09329e-10,
+                          0.866025 6.33728e-12 -0.5,
+                          0.965926 3.28041e-12 -0.258819,
+                          0.923861 0.382729 4.59927e-10,
+                          0.866025 -6.33724e-12 0.5,
+                          0.923861 0.382729 4.50399e-10,
+                          0.965926 -3.28039e-12 0.258819,
+                          0.923861 -0.382729 -4.50399e-10,
+                          0.965926 3.28041e-12 -0.258819,
+                          0.866025 6.33728e-12 -0.5,
+                          0.923861 -0.382729 -4.50399e-10,
+                          0.98078 -0.195119 -1.09329e-10,
+                          0.965926 3.28041e-12 -0.258819,
+                          0.831437 -0.55562 -1.01792e-09,
+                          0.866025 6.33728e-12 -0.5,
+                          0.707107 8.96226e-12 -0.707107,
+                          0.831437 -0.55562 -1.01792e-09,
+                          0.923861 -0.382729 -4.50399e-10,
+                          0.866025 6.33728e-12 -0.5,
+                          0.707065 -0.707149 -2.05186e-09,
+                          0.707107 8.96226e-12 -0.707107,
+                          0.5 1.09765e-11 -0.866025,
+                          0.707065 -0.707149 -2.05186e-09,
+                          0.831437 -0.55562 -1.01792e-09,
+                          0.707107 8.96226e-12 -0.707107,
+                          0.499958 -0.86605 -2.65874e-09,
+                          0.5 1.09765e-11 -0.866025,
+                          0.258819 1.22427e-11 -0.965926,
+                          0.499958 -0.86605 -2.65874e-09,
+                          0.707065 -0.707149 -2.05186e-09,
+                          0.5 1.09765e-11 -0.866025,
+                          0.258791 -0.965933 -3.89604e-10,
+                          0.499958 -0.86605 -2.65874e-09,
+                          0.258819 1.22427e-11 -0.965926,
+                          0.965926 -3.28039e-12 0.258819,
+                          0.98078 -0.195119 -1.25116e-10,
+                          0.923861 -0.382729 -4.59927e-10,
+                          0.866025 -6.33724e-12 0.5,
+                          0.923861 -0.382729 -4.59927e-10,
+                          0.831437 -0.55562 -9.79103e-10,
+                          0.866025 -6.33724e-12 0.5,
+                          0.965926 -3.28039e-12 0.258819,
+                          0.923861 -0.382729 -4.59927e-10,
+                          0.707107 -8.96221e-12 0.707107,
+                          0.831437 -0.55562 -9.79103e-10,
+                          0.707065 -0.707149 -1.64246e-09,
+                          0.707107 -8.96221e-12 0.707107,
+                          0.866025 -6.33724e-12 0.5,
+                          0.831437 -0.55562 -9.79103e-10,
+                          0.5 -1.09764e-11 0.866025,
+                          0.707065 -0.707149 -1.64246e-09,
+                          0.499958 -0.86605 -2.65874e-09,
+                          0.5 -1.09764e-11 0.866025,
+                          0.707107 -8.96221e-12 0.707107,
+                          0.707065 -0.707149 -1.64246e-09,
+                          0.258819 -1.22426e-11 0.965926,
+                          0.499958 -0.86605 -2.65874e-09,
+                          0.258791 -0.965933 -3.68722e-09,
+                          0.258819 -1.22426e-11 0.965926,
+                          0.5 -1.09764e-11 0.866025,
+                          0.499958 -0.86605 -2.65874e-09 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 52.5 -0.0001146 2.7,
+                          52.5 -5.70577e-14 3.5,
+                          52.5 -3.5 3.78196e-30,
+                          -47.5 -3.5 3.78196e-30,
+                          52.5 -3.5 3.78196e-30,
+                          52.5 -5.70577e-14 3.5,
+                          52.5 -2.7 3.30644e-16,
+                          52.5 -3.5 3.78196e-30,
+                          52.5 -5.70577e-14 -3.5,
+                          -47.5 -5.70577e-14 -3.5,
+                          52.5 -5.70577e-14 -3.5,
+                          52.5 -3.5 3.78196e-30,
+                          52.5 -2.7 3.30644e-16,
+                          52.5 -0.0001146 2.7,
+                          52.5 -3.5 3.78196e-30,
+                          -47.5 -5.70577e-14 -3.5,
+                          52.5 -3.5 3.78196e-30,
+                          -47.5 -3.5 3.78196e-30,
+                          52.5 2.7 -6.61287e-16,
+                          52.5 3.5 4.0092e-30,
+                          52.5 -5.70577e-14 3.5,
+                          -47.5 -5.70577e-14 3.5,
+                          52.5 -5.70577e-14 3.5,
+                          52.5 3.5 4.0092e-30,
+                          52.5 -0.0001146 2.7,
+                          52.5 2.7 -6.61287e-16,
+                          52.5 -5.70577e-14 3.5,
+                          -47.5 -5.70577e-14 3.5,
+                          -47.5 -3.5 3.78196e-30,
+                          52.5 -5.70577e-14 3.5,
+                          52.5 0.0001146 -2.7,
+                          52.5 -5.70577e-14 -3.5,
+                          52.5 3.5 4.0092e-30,
+                          -47.5 3.5 4.0092e-30,
+                          52.5 3.5 4.0092e-30,
+                          52.5 -5.70577e-14 -3.5,
+                          52.5 0.0001146 -2.7,
+                          52.5 3.5 4.0092e-30,
+                          52.5 2.7 -6.61287e-16,
+                          -47.5 -5.70577e-14 3.5,
+                          52.5 3.5 4.0092e-30,
+                          -47.5 3.5 4.0092e-30,
+                          52.5 0.0001146 -2.7,
+                          52.5 -2.7 3.30644e-16,
+                          52.5 -5.70577e-14 -3.5,
+                          -47.5 3.5 4.0092e-30,
+                          52.5 -5.70577e-14 -3.5,
+                          -47.5 -5.70577e-14 -3.5,
+                          52.5068 -3.36218e-11 2.64824,
+                          52.5 2.7 -6.61287e-16,
+                          52.5 -0.0001146 2.7,
+                          52.5038 2.66098 1.7063e-09,
+                          52.5 0.0001146 -2.7,
+                          52.5 2.7 -6.61287e-16,
+                          52.5068 -3.36218e-11 2.64824,
+                          52.5038 2.66098 1.7063e-09,
+                          52.5 2.7 -6.61287e-16,
+                          52.5038 -2.66098 -1.7063e-09,
+                          52.5 -0.0001146 2.7,
+                          52.5 -2.7 3.30644e-16,
+                          52.5068 -3.36218e-11 2.64824,
+                          52.5 -0.0001146 2.7,
+                          52.5038 -2.66098 -1.7063e-09,
+                          52.5068 3.35084e-11 -2.64824,
+                          52.5 -2.7 3.30644e-16,
+                          52.5 0.0001146 -2.7,
+                          52.5038 -2.66098 -1.7063e-09,
+                          52.5 -2.7 3.30644e-16,
+                          52.5068 3.35084e-11 -2.64824,
+                          52.5068 3.35084e-11 -2.64824,
+                          52.5 0.0001146 -2.7,
+                          52.5038 2.66098 1.7063e-09,
+                          61.5 2.2 -2.69413e-16,
+                          61.5 -5.67087e-14 2.2,
+                          61.5 -2.2 2.69413e-16,
+                          61.2 -2.5 -8.04071e-16,
+                          61.5 -2.2 2.69413e-16,
+                          61.5 -5.67087e-14 2.2,
+                          61.5 -5.72475e-14 -2.2,
+                          61.5 2.2 -2.69413e-16,
+                          61.5 -2.2 2.69413e-16,
+                          61.2 -5.73026e-14 -2.5,
+                          61.5 -5.72475e-14 -2.2,
+                          61.5 -2.2 2.69413e-16,
+                          61.2 -5.73026e-14 -2.5,
+                          61.5 -2.2 2.69413e-16,
+                          61.2 -2.5 -8.04071e-16,
+                          61.2 -5.66903e-14 2.5,
+                          61.5 -5.67087e-14 2.2,
+                          61.5 2.2 -2.69413e-16,
+                          61.2 -5.66903e-14 2.5,
+                          61.2 -2.5 -8.04071e-16,
+                          61.5 -5.67087e-14 2.2,
+                          61.2 2.5 -1.0437e-17,
+                          61.5 2.2 -2.69413e-16,
+                          61.5 -5.72475e-14 -2.2,
+                          61.2 -5.66903e-14 2.5,
+                          61.5 2.2 -2.69413e-16,
+                          61.2 2.5 -1.0437e-17,
+                          61.2 2.5 -1.0437e-17,
+                          61.5 -5.72475e-14 -2.2,
+                          61.2 -5.73026e-14 -2.5,
+                          -47.5 3.5 4.0092e-30,
+                          -47.5 -5.70577e-14 -3.5,
+                          -47.5 -3.5 3.78196e-30,
+                          -47.5 -5.70577e-14 3.5,
+                          -47.5 3.5 4.0092e-30,
+                          -47.5 -3.5 3.78196e-30,
+                          61.2 -5.73026e-14 -2.5,
+                          52.7 9.28785e-05 -2.5,
+                          52.7 2.5 -3.06152e-16,
+                          52.6482 3.17159e-11 -2.50681,
+                          52.7 2.5 -3.06152e-16,
+                          52.7 9.28785e-05 -2.5,
+                          61.2 2.5 -1.0437e-17,
+                          61.2 -5.73026e-14 -2.5,
+                          52.7 2.5 -3.06152e-16,
+                          52.7 -9.28785e-05 2.5,
+                          61.2 2.5 -1.0437e-17,
+                          52.7 2.5 -3.06152e-16,
+                          52.6482 3.17159e-11 -2.50681,
+                          52.6482 2.50681 9.56915e-09,
+                          52.7 2.5 -3.06152e-16,
+                          52.7 -9.28785e-05 2.5,
+                          52.7 2.5 -3.06152e-16,
+                          52.6482 2.50681 9.56915e-09,
+                          61.2 -2.5 -8.04071e-16,
+                          52.7 -2.5 3.06152e-16,
+                          52.7 9.28785e-05 -2.5,
+                          52.6482 -2.50681 -9.56915e-09,
+                          52.7 9.28785e-05 -2.5,
+                          52.7 -2.5 3.06152e-16,
+                          61.2 -5.73026e-14 -2.5,
+                          61.2 -2.5 -8.04071e-16,
+                          52.7 9.28785e-05 -2.5,
+                          52.6482 -2.50681 -9.56915e-09,
+                          52.6482 3.17159e-11 -2.50681,
+                          52.7 9.28785e-05 -2.5,
+                          61.2 -5.66903e-14 2.5,
+                          52.7 -2.5 3.06152e-16,
+                          61.2 -2.5 -8.04071e-16,
+                          52.6482 -3.18294e-11 2.50681,
+                          52.6482 -2.50681 -9.56915e-09,
+                          52.7 -2.5 3.06152e-16,
+                          61.2 -5.66903e-14 2.5,
+                          52.7 -9.28785e-05 2.5,
+                          52.7 -2.5 3.06152e-16,
+                          52.6482 -3.18294e-11 2.50681,
+                          52.7 -2.5 3.06152e-16,
+                          52.7 -9.28785e-05 2.5,
+                          61.2 -5.66903e-14 2.5,
+                          61.2 2.5 -1.0437e-17,
+                          52.7 -9.28785e-05 2.5,
+                          52.6482 3.17159e-11 -2.50681,
+                          52.6 2.52679 7.75714e-09,
+                          52.6482 2.50681 9.56915e-09,
+                          52.6482 -3.18294e-11 2.50681,
+                          52.6482 2.50681 9.56915e-09,
+                          52.6 2.52679 7.75714e-09,
+                          52.6482 -3.18294e-11 2.50681,
+                          52.7 -9.28785e-05 2.5,
+                          52.6482 2.50681 9.56915e-09,
+                          52.6 3.19692e-11 -2.52679,
+                          52.5586 2.55857 5.94268e-09,
+                          52.6 2.52679 7.75714e-09,
+                          52.6 -3.20827e-11 2.52679,
+                          52.6 2.52679 7.75714e-09,
+                          52.5586 2.55857 5.94268e-09,
+                          52.6482 3.17159e-11 -2.50681,
+                          52.6 3.19692e-11 -2.52679,
+                          52.6 2.52679 7.75714e-09,
+                          52.6482 -3.18294e-11 2.50681,
+                          52.6 2.52679 7.75714e-09,
+                          52.6 -3.20827e-11 2.52679,
+                          52.5586 3.2372e-11 -2.55858,
+                          52.5337 2.58888 4.56207e-09,
+                          52.5586 2.55857 5.94268e-09,
+                          52.5586 -3.24855e-11 2.55858,
+                          52.5586 2.55857 5.94268e-09,
+                          52.5337 2.58888 4.56207e-09,
+                          52.6 3.19692e-11 -2.52679,
+                          52.5586 3.2372e-11 -2.55858,
+                          52.5586 2.55857 5.94268e-09,
+                          52.6 -3.20827e-11 2.52679,
+                          52.5586 2.55857 5.94268e-09,
+                          52.5586 -3.24855e-11 2.55858,
+                          52.5268 3.2897e-11 -2.6,
+                          52.5152 2.62345 3.15262e-09,
+                          52.5337 2.58888 4.56207e-09,
+                          52.5268 -3.30105e-11 2.6,
+                          52.5337 2.58888 4.56207e-09,
+                          52.5152 2.62345 3.15262e-09,
+                          52.5586 3.2372e-11 -2.55858,
+                          52.5268 3.2897e-11 -2.6,
+                          52.5337 2.58888 4.56207e-09,
+                          52.5586 -3.24855e-11 2.55858,
+                          52.5337 2.58888 4.56207e-09,
+                          52.5268 -3.30105e-11 2.6,
+                          52.5068 3.35084e-11 -2.64824,
+                          52.5038 2.66098 1.7063e-09,
+                          52.5152 2.62345 3.15262e-09,
+                          52.5068 -3.36218e-11 2.64824,
+                          52.5152 2.62345 3.15262e-09,
+                          52.5038 2.66098 1.7063e-09,
+                          52.5268 3.2897e-11 -2.6,
+                          52.5068 3.35084e-11 -2.64824,
+                          52.5152 2.62345 3.15262e-09,
+                          52.5268 -3.30105e-11 2.6,
+                          52.5152 2.62345 3.15262e-09,
+                          52.5068 -3.36218e-11 2.64824,
+                          52.5152 -2.62345 -3.15262e-09,
+                          52.5068 3.35084e-11 -2.64824,
+                          52.5268 3.2897e-11 -2.6,
+                          52.5152 -2.62345 -3.15262e-09,
+                          52.5038 -2.66098 -1.7063e-09,
+                          52.5068 3.35084e-11 -2.64824,
+                          52.5337 -2.58888 -4.56207e-09,
+                          52.5268 3.2897e-11 -2.6,
+                          52.5586 3.2372e-11 -2.55858,
+                          52.5337 -2.58888 -4.56207e-09,
+                          52.5152 -2.62345 -3.15262e-09,
+                          52.5268 3.2897e-11 -2.6,
+                          52.5586 -2.55857 -5.94268e-09,
+                          52.5586 3.2372e-11 -2.55858,
+                          52.6 3.19692e-11 -2.52679,
+                          52.5586 -2.55857 -5.94268e-09,
+                          52.5337 -2.58888 -4.56207e-09,
+                          52.5586 3.2372e-11 -2.55858,
+                          52.6 -2.52679 -7.75714e-09,
+                          52.6 3.19692e-11 -2.52679,
+                          52.6482 3.17159e-11 -2.50681,
+                          52.6 -2.52679 -7.75714e-09,
+                          52.5586 -2.55857 -5.94268e-09,
+                          52.6 3.19692e-11 -2.52679,
+                          52.6482 -2.50681 -9.56915e-09,
+                          52.6 -2.52679 -7.75714e-09,
+                          52.6482 3.17159e-11 -2.50681,
+                          52.5068 -3.36218e-11 2.64824,
+                          52.5038 -2.66098 -1.7063e-09,
+                          52.5152 -2.62345 -3.15262e-09,
+                          52.5268 -3.30105e-11 2.6,
+                          52.5152 -2.62345 -3.15262e-09,
+                          52.5337 -2.58888 -4.56207e-09,
+                          52.5268 -3.30105e-11 2.6,
+                          52.5068 -3.36218e-11 2.64824,
+                          52.5152 -2.62345 -3.15262e-09,
+                          52.5586 -3.24855e-11 2.55858,
+                          52.5337 -2.58888 -4.56207e-09,
+                          52.5586 -2.55857 -5.94268e-09,
+                          52.5586 -3.24855e-11 2.55858,
+                          52.5268 -3.30105e-11 2.6,
+                          52.5337 -2.58888 -4.56207e-09,
+                          52.6 -3.20827e-11 2.52679,
+                          52.5586 -2.55857 -5.94268e-09,
+                          52.6 -2.52679 -7.75714e-09,
+                          52.6 -3.20827e-11 2.52679,
+                          52.5586 -3.24855e-11 2.55858,
+                          52.5586 -2.55857 -5.94268e-09,
+                          52.6482 -3.18294e-11 2.50681,
+                          52.6 -2.52679 -7.75714e-09,
+                          52.6482 -2.50681 -9.56915e-09,
+                          52.6482 -3.18294e-11 2.50681,
+                          52.6 -3.20827e-11 2.52679,
+                          52.6 -2.52679 -7.75714e-09 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.6 0.179235 0.260819
+    }
+    Separator {
+        Normal {
+            vector      [ 0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          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,
+                          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,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 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 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -45 19.5 -16,
+                          -51 17.5 -16,
+                          -51 19.5 -16,
+                          -51 17.5 16,
+                          -51 19.5 -16,
+                          -51 17.5 -16,
+                          -51 19.5 16,
+                          -45 19.5 -16,
+                          -51 19.5 -16,
+                          -51 19.5 16,
+                          -51 19.5 -16,
+                          -51 17.5 16,
+                          51 19.5 -16,
+                          51 17.5 -16,
+                          -51 17.5 -16,
+                          -51 17.5 16,
+                          -51 17.5 -16,
+                          51 17.5 -16,
+                          45 19.5 -16,
+                          51 19.5 -16,
+                          -51 17.5 -16,
+                          45 21.5 -16,
+                          45 19.5 -16,
+                          -51 17.5 -16,
+                          -45 19.5 -16,
+                          45 21.5 -16,
+                          -51 17.5 -16,
+                          51 19.5 16,
+                          51 17.5 -16,
+                          51 19.5 -16,
+                          51 17.5 16,
+                          51 17.5 -16,
+                          51 19.5 16,
+                          -51 17.5 16,
+                          51 17.5 -16,
+                          51 17.5 16,
+                          45 19.5 16,
+                          51 19.5 -16,
+                          45 19.5 -16,
+                          45 19.5 16,
+                          51 19.5 16,
+                          51 19.5 -16,
+                          45 21.5 16,
+                          45 19.5 -16,
+                          45 21.5 -16,
+                          45 19.5 16,
+                          45 19.5 -16,
+                          45 21.5 16,
+                          -45 19.5 -16,
+                          -45 21.5 -16,
+                          45 21.5 -16,
+                          45 21.5 16,
+                          45 21.5 -16,
+                          -45 21.5 -16,
+                          -45 19.5 16,
+                          -45 21.5 -16,
+                          -45 19.5 -16,
+                          45 21.5 16,
+                          -45 21.5 -16,
+                          -45 21.5 16,
+                          -45 19.5 16,
+                          -45 21.5 16,
+                          -45 21.5 -16,
+                          -45 19.5 16,
+                          -45 19.5 -16,
+                          -51 19.5 16,
+                          45 19.5 16,
+                          51 17.5 16,
+                          51 19.5 16,
+                          -51 19.5 16,
+                          -51 17.5 16,
+                          51 17.5 16,
+                          -45 19.5 16,
+                          -51 19.5 16,
+                          51 17.5 16,
+                          -45 19.5 16,
+                          51 17.5 16,
+                          -45 21.5 16,
+                          45 19.5 16,
+                          -45 21.5 16,
+                          51 17.5 16,
+                          45 19.5 16,
+                          45 21.5 16,
+                          -45 21.5 16 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/head/head_base.wrl b/data/RobotAPI/robots/Armar3/fullmodel/armar/head/head_base.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..daca4f93ccf607093e7a66d990d5effc23b37e1c
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/head/head_base.wrl
@@ -0,0 +1,145 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            -47 -36.5 583.5, -40.0097 -36.5 596.989, -34 -36.5 594.5, -34 -37.5 594.5, 
+            4.26326e-014 -36.5 548, -27.9903 -36.5 596.989, -27.9896 -37.5 596.99, -42.4998 -36.5 603, 
+            -40.0104 -37.5 596.99, -47 -36.5 616, -40.0097 -36.5 609.011, -42.5 -37.5 603, 
+            -34 -36.5 611.5, -40.0104 -37.5 609.01, -22 -36.5 611, -27.9903 -36.5 609.011, 
+            -34 -37.5 611.5, -25.5002 -36.5 603, -27.9896 -37.5 609.01, -25.5 -37.5 603, 
+            -27 -36.5 616, -27 -42.5 616, -22 -42.5 611, -47 -42.5 616, 
+            -56 -36.5 583.5, -47 -42.5 583.5, -47 -36.5 577.5, -56 -36.5 577.5, 
+            -56 -42.5 577.5, -56 -42.5 583.5, -47 -36.5 548, -47 -42.5 577.5, 
+            -47 -42.5 548, 7.10543e-014 -36.5 611, 4.9738e-014 -42.5 548, 7.81597e-014 -42.5 611, 
+            -27.2833 -42.5 596.282, -34 -42.5 593.5, -34 -37.5 593.5, -40.7167 -42.5 596.282, 
+            -40.7175 -37.5 596.282, -24.5003 -42.5 603, -27.2825 -37.5 596.282, -27.2833 -42.5 609.718, 
+            -24.5 -37.5 603, -34 -42.5 612.5, -27.2825 -37.5 609.718, -40.7167 -42.5 609.718, 
+            -34 -37.5 612.5, -43.4997 -42.5 603, -40.7175 -37.5 609.718, -43.5 -37.5 603, 
+            -47 36.5 610, -40.0097 36.5 609.011, -34 36.5 611.5, -34 37.5 611.5, 
+            -22 36.5 611, -27.9903 36.5 609.011, -27.9896 37.5 609.01, -27 36.5 616, 
+            -47 36.5 596, -42.4998 36.5 603, -40.0104 37.5 609.01, -40.0097 36.5 596.989, 
+            -42.5 37.5 603, -34 36.5 594.5, -40.0104 37.5 596.99, -30 36.5 579, 
+            -27.9903 36.5 596.989, -34 37.5 594.5, 4.9738e-014 36.5 611, -25.5002 36.5 603, 
+            -27.9896 37.5 596.99, -25.5 37.5 603, -30 36.5 548, 2.13163e-014 36.5 548, 
+            1.42109e-014 42.5 548, 4.26326e-014 42.5 611, -30 42.5 548, -30 42.5 579, 
+            -47 42.5 596, -41 36.5 616, -47 42.5 610, -41 42.5 616, 
+            -27 42.5 616, -22 42.5 611, -27.2826 42.5 609.717, -34 42.5 612.5, 
+            -34 37.5 612.5, -40.7174 42.5 609.717, -40.7167 37.5 609.718, -24.5 42.5 603, 
+            -27.2833 37.5 609.718, -27.2826 42.5 596.283, -24.5003 37.5 603, -34 42.5 593.5, 
+            -27.2833 37.5 596.282, -40.7174 42.5 596.283, -34 37.5 593.5, -43.5 42.5 603, 
+            -40.7167 37.5 596.282, -43.4997 37.5 603, 26 -20 548, 26 20 548, 
+            1.42109e-014 42.2 548, 1.42109e-014 42.2 540, 4.26326e-014 -42.2 548, -30 42.2 548, 
+            -30 42.2 540, 26 20 540, 26 -20 540, -47 -42.2 548, 
+            4.26326e-014 -42.2 540, -94 20 548, -94 -20 548, -47 -42.2 540, 
+            -94 -20 540, -94 20 540
+          ]
+        }
+        color Color
+        {
+          color
+          [
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1
+          ]
+        }
+        coordIndex
+        [ 0,1,2,-1, 3,2,1,-1, 4,2,5,-1, 6,5,2,-1, 
+          4,0,2,-1, 3,6,2,-1, 0,7,1,-1, 8,1,7,-1, 8,3,1,-1, 9,10,7,-1, 
+          11,7,10,-1, 0,9,7,-1, 8,7,11,-1, 9,12,10,-1, 13,10,12,-1, 11,10,13,-1, 
+          14,15,12,-1, 16,12,15,-1, 14,12,9,-1, 13,12,16,-1, 4,17,15,-1, 18,15,17,-1, 
+          14,4,15,-1, 18,16,15,-1, 4,5,17,-1, 19,17,5,-1, 19,18,17,-1, 6,19,5,-1, 
+          14,9,20,-1, 21,20,9,-1, 22,14,20,-1, 22,20,21,-1, 23,9,0,-1, 23,21,9,-1, 
+          4,24,0,-1, 25,0,24,-1, 23,0,25,-1, 26,27,24,-1, 28,24,27,-1, 4,26,24,-1, 
+          29,24,28,-1, 25,24,29,-1, 28,27,26,-1, 4,30,26,-1, 31,26,30,-1, 28,26,31,-1, 
+          32,30,4,-1, 31,30,32,-1, 14,33,4,-1, 34,4,33,-1, 32,4,34,-1, 35,33,14,-1, 
+          34,33,35,-1, 35,14,22,-1, 25,36,37,-1, 38,37,36,-1, 25,37,39,-1, 40,39,37,-1, 
+          40,37,38,-1, 35,41,36,-1, 42,36,41,-1, 25,35,36,-1, 42,38,36,-1, 35,43,41,-1, 
+          44,41,43,-1, 42,41,44,-1, 22,45,43,-1, 46,43,45,-1, 35,22,43,-1, 44,43,46,-1, 
+          21,47,45,-1, 48,45,47,-1, 22,21,45,-1, 46,45,48,-1, 23,49,47,-1, 50,47,49,-1, 
+          23,47,21,-1, 48,47,50,-1, 25,39,49,-1, 51,49,39,-1, 23,25,49,-1, 50,49,51,-1, 
+          51,39,40,-1, 32,34,35,-1, 31,32,35,-1, 28,31,35,-1, 25,28,35,-1, 25,29,28,-1, 
+          48,16,18,-1, 50,13,16,-1, 48,50,16,-1, 46,18,19,-1, 46,48,18,-1, 42,19,6,-1, 
+          44,46,19,-1, 42,44,19,-1, 42,6,3,-1, 38,3,8,-1, 42,3,38,-1, 50,11,13,-1, 
+          40,8,11,-1, 51,40,11,-1, 50,51,11,-1, 40,38,8,-1, 52,53,54,-1, 55,54,53,-1, 
+          56,54,57,-1, 58,57,54,-1, 59,52,54,-1, 56,59,54,-1, 58,54,55,-1, 60,61,53,-1, 
+          62,53,61,-1, 52,60,53,-1, 62,55,53,-1, 60,63,61,-1, 64,61,63,-1, 62,61,64,-1, 
+          60,65,63,-1, 66,63,65,-1, 64,63,66,-1, 67,68,65,-1, 69,65,68,-1, 60,67,65,-1, 
+          66,65,69,-1, 70,71,68,-1, 72,68,71,-1, 70,68,67,-1, 69,68,72,-1, 70,57,71,-1, 
+          73,71,57,-1, 72,71,73,-1, 70,56,57,-1, 73,57,58,-1, 70,74,75,-1, 76,75,74,-1, 
+          77,70,75,-1, 76,77,75,-1, 70,67,74,-1, 78,74,67,-1, 76,74,78,-1, 79,67,60,-1, 
+          78,67,79,-1, 80,60,52,-1, 79,60,80,-1, 59,81,52,-1, 82,52,81,-1, 80,52,82,-1, 
+          83,81,59,-1, 82,81,83,-1, 84,59,56,-1, 83,59,84,-1, 85,56,70,-1, 84,56,85,-1, 
+          85,70,77,-1, 85,86,87,-1, 88,87,86,-1, 82,87,89,-1, 90,89,87,-1, 83,85,87,-1, 
+          82,83,87,-1, 90,87,88,-1, 76,91,86,-1, 92,86,91,-1, 76,86,85,-1, 92,88,86,-1, 
+          76,93,91,-1, 94,91,93,-1, 92,91,94,-1, 76,95,93,-1, 96,93,95,-1, 94,93,96,-1, 
+          80,97,95,-1, 98,95,97,-1, 79,80,95,-1, 76,79,95,-1, 96,95,98,-1, 82,99,97,-1, 
+          100,97,99,-1, 80,82,97,-1, 98,97,100,-1, 82,89,99,-1, 101,99,89,-1, 100,99,101,-1, 
+          101,89,90,-1, 76,85,77,-1, 83,84,85,-1, 76,78,79,-1, 92,58,55,-1, 88,55,62,-1, 
+          92,55,88,-1, 92,73,58,-1, 96,72,73,-1, 94,96,73,-1, 92,94,73,-1, 98,69,72,-1, 
+          96,98,72,-1, 100,66,69,-1, 98,100,69,-1, 100,64,66,-1, 90,62,64,-1, 101,90,64,-1, 
+          100,101,64,-1, 90,88,62,-1, 102,103,104,-1, 105,104,103,-1, 106,102,104,-1, 107,106,104,-1, 
+          108,107,104,-1, 108,104,105,-1, 109,103,102,-1, 109,105,103,-1, 110,102,106,-1, 109,102,110,-1, 
+          107,111,106,-1, 112,106,111,-1, 110,106,112,-1, 113,114,111,-1, 115,111,114,-1, 107,113,111,-1, 
+          112,111,115,-1, 116,114,113,-1, 115,114,116,-1, 117,113,107,-1, 116,113,117,-1, 117,107,108,-1, 
+          115,108,105,-1, 112,115,105,-1, 109,112,105,-1, 116,117,108,-1, 115,116,108,-1, 109,110,112,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/head/jaw.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/head/jaw.iv
new file mode 100644
index 0000000000000000000000000000000000000000..d99e61356b41855205f7ac03b2c9ddf9f3216b90
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/head/jaw.iv
@@ -0,0 +1,6541 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.6235294117647059 0.7137254901960784 0.803921568627451
+    }
+    Separator {
+        Normal {
+            vector      [ 0.999897 -0.000324471 0.0143593,
+                          0.999095 -0.0415496 -0.0091486,
+                          0.998963 -0.041913 -0.0177683,
+                          -8.4969e-17 -0.931357 0.364107,
+                          -9.23929e-17 -0.930969 0.365098,
+                          -6.00278e-16 -0.885557 0.46453,
+                          0.999852 0.00942684 -0.0143956,
+                          0.999897 -0.000324471 0.0143593,
+                          0.998963 -0.041913 -0.0177683,
+                          0.99776 -0.0359644 -0.0563971,
+                          0.999852 0.00942684 -0.0143956,
+                          0.998963 -0.041913 -0.0177683,
+                          0.70684 -0.68542 -0.174864,
+                          0.998011 -0.0289897 -0.0559784,
+                          0.999281 -0.0346893 -0.0153008,
+                          0 -0.974562 0.224117,
+                          -9.23929e-17 -0.930969 0.365098,
+                          -8.4969e-17 -0.931357 0.364107,
+                          0.70684 -0.68542 -0.174864,
+                          0.999281 -0.0346893 -0.0153008,
+                          0.797337 -0.581017 -0.163318,
+                          0.999897 -0.000324471 0.0143593,
+                          0.999195 -0.0400936 -0.00124969,
+                          0.999095 -0.0415496 -0.0091486,
+                          -8.4969e-17 -0.931357 0.364107,
+                          -6.00278e-16 -0.885557 0.46453,
+                          -9.54003e-16 -0.829854 0.557981,
+                          2.4521e-16 -0.885074 0.46545,
+                          -3.06513e-16 -0.885074 0.46545,
+                          -5.36097e-15 -0.408015 0.912975,
+                          -8.4969e-17 -0.931357 0.364107,
+                          -9.54003e-16 -0.829854 0.557981,
+                          -5.69448e-16 -0.829854 0.557981,
+                          0.992465 0.122522 0.00157007,
+                          0.999897 -0.000324471 0.0143593,
+                          0.999852 0.00942684 -0.0143956,
+                          0.992465 0.122522 0.00157007,
+                          0.999722 0.0173921 0.0159466,
+                          0.999897 -0.000324471 0.0143593,
+                          2.25432e-15 -0.40689 0.913477,
+                          -5.36097e-15 -0.408015 0.912975,
+                          -1.96067e-15 -0.241134 0.970492,
+                          2.4521e-16 -0.885074 0.46545,
+                          -5.36097e-15 -0.408015 0.912975,
+                          2.25432e-15 -0.40689 0.913477,
+                          0.99776 -0.0359644 -0.0563971,
+                          0.998308 0.019633 -0.0547321,
+                          0.999852 0.00942684 -0.0143956,
+                          0.943678 0.318924 -0.088088,
+                          0.999852 0.00942684 -0.0143956,
+                          0.998308 0.019633 -0.0547321,
+                          0.954524 0.295499 -0.0395538,
+                          0.999852 0.00942684 -0.0143956,
+                          0.943678 0.318924 -0.088088,
+                          0.959228 0.28051 -0.0345866,
+                          0.999852 0.00942684 -0.0143956,
+                          0.954524 0.295499 -0.0395538,
+                          0.992465 0.122522 0.00157007,
+                          0.999852 0.00942684 -0.0143956,
+                          0.959228 0.28051 -0.0345866,
+                          0.995273 -0.0236635 -0.0941877,
+                          0.994107 0.0343605 -0.102815,
+                          0.998308 0.019633 -0.0547321,
+                          0.927189 0.344338 -0.147486,
+                          0.998308 0.019633 -0.0547321,
+                          0.994107 0.0343605 -0.102815,
+                          0.996208 -0.033095 -0.0804624,
+                          0.995273 -0.0236635 -0.0941877,
+                          0.998308 0.019633 -0.0547321,
+                          0.99776 -0.0359644 -0.0563971,
+                          0.996208 -0.033095 -0.0804624,
+                          0.998308 0.019633 -0.0547321,
+                          0.943678 0.318924 -0.088088,
+                          0.998308 0.019633 -0.0547321,
+                          0.927189 0.344338 -0.147486,
+                          0.989173 0.0305905 -0.143528,
+                          0.98478 0.063397 -0.161828,
+                          0.994107 0.0343605 -0.102815,
+                          0.899972 0.375461 -0.221538,
+                          0.994107 0.0343605 -0.102815,
+                          0.98478 0.063397 -0.161828,
+                          0.995798 -0.0114863 -0.0908575,
+                          0.989173 0.0305905 -0.143528,
+                          0.994107 0.0343605 -0.102815,
+                          0.995273 -0.0236635 -0.0941877,
+                          0.995798 -0.0114863 -0.0908575,
+                          0.994107 0.0343605 -0.102815,
+                          0.927189 0.344338 -0.147486,
+                          0.994107 0.0343605 -0.102815,
+                          0.899972 0.375461 -0.221538,
+                          0.953475 0.100451 -0.284244,
+                          0.966152 0.108226 -0.234175,
+                          0.98478 0.063397 -0.161828,
+                          0.862143 0.413263 -0.293125,
+                          0.98478 0.063397 -0.161828,
+                          0.966152 0.108226 -0.234175,
+                          0.989173 0.0305905 -0.143528,
+                          0.953475 0.100451 -0.284244,
+                          0.98478 0.063397 -0.161828,
+                          0.899972 0.375461 -0.221538,
+                          0.98478 0.063397 -0.161828,
+                          0.862143 0.413263 -0.293125,
+                          0.953475 0.100451 -0.284244,
+                          0.925815 0.151449 -0.346308,
+                          0.966152 0.108226 -0.234175,
+                          0.829328 0.4432 -0.340279,
+                          0.966152 0.108226 -0.234175,
+                          0.925815 0.151449 -0.346308,
+                          0.862143 0.413263 -0.293125,
+                          0.966152 0.108226 -0.234175,
+                          0.829328 0.4432 -0.340279,
+                          0.85299 0.203334 -0.48069,
+                          0.844968 0.169741 -0.507166,
+                          0.925815 0.151449 -0.346308,
+                          0.813021 0.43997 -0.381344,
+                          0.925815 0.151449 -0.346308,
+                          0.844968 0.169741 -0.507166,
+                          0.953475 0.100451 -0.284244,
+                          0.85299 0.203334 -0.48069,
+                          0.925815 0.151449 -0.346308,
+                          0.829328 0.4432 -0.340279,
+                          0.925815 0.151449 -0.346308,
+                          0.813021 0.43997 -0.381344,
+                          0.678229 0.325113 -0.65902,
+                          0.682416 0.160118 -0.713211,
+                          0.844968 0.169741 -0.507166,
+                          0.794015 0.381232 -0.473501,
+                          0.844968 0.169741 -0.507166,
+                          0.682416 0.160118 -0.713211,
+                          0.85299 0.203334 -0.48069,
+                          0.678229 0.325113 -0.65902,
+                          0.844968 0.169741 -0.507166,
+                          0.813021 0.43997 -0.381344,
+                          0.844968 0.169741 -0.507166,
+                          0.794015 0.381232 -0.473501,
+                          0.414684 0.445615 -0.793388,
+                          0.410724 0.128524 -0.902656,
+                          0.682416 0.160118 -0.713211,
+                          0.615519 0.141496 -0.775316,
+                          0.682416 0.160118 -0.713211,
+                          0.410724 0.128524 -0.902656,
+                          0.678229 0.325113 -0.65902,
+                          0.414684 0.445615 -0.793388,
+                          0.682416 0.160118 -0.713211,
+                          0.793107 0.370103 -0.483741,
+                          0.794015 0.381232 -0.473501,
+                          0.682416 0.160118 -0.713211,
+                          0.615519 0.141496 -0.775316,
+                          0.793107 0.370103 -0.483741,
+                          0.682416 0.160118 -0.713211,
+                          0.133465 0.490411 -0.861211,
+                          0.438087 0.00214235 -0.89893,
+                          0.410724 0.128524 -0.902656,
+                          0.415011 0.0170192 -0.909657,
+                          0.410724 0.128524 -0.902656,
+                          0.438087 0.00214235 -0.89893,
+                          0.414684 0.445615 -0.793388,
+                          0.133465 0.490411 -0.861211,
+                          0.410724 0.128524 -0.902656,
+                          0.415011 0.0170192 -0.909657,
+                          0.615519 0.141496 -0.775316,
+                          0.410724 0.128524 -0.902656,
+                          0.243829 0.331203 -0.911511,
+                          0.77728 -0.118769 -0.617843,
+                          0.438087 0.00214235 -0.89893,
+                          -1.01604e-17 0.504872 -0.863194,
+                          -3.9793e-16 0.53953 -0.841966,
+                          -2.24018e-16 0.473745 -0.880662,
+                          0.133465 0.490411 -0.861211,
+                          0.243829 0.331203 -0.911511,
+                          0.438087 0.00214235 -0.89893,
+                          -3.54196e-17 0.552662 -0.833405,
+                          -4.15069e-16 0.556875 -0.830596,
+                          -3.9793e-16 0.53953 -0.841966,
+                          -1.01604e-17 0.504872 -0.863194,
+                          -3.54196e-17 0.552662 -0.833405,
+                          -3.9793e-16 0.53953 -0.841966,
+                          0.243829 0.331203 -0.911511,
+                          0.928505 -0.170292 -0.329969,
+                          0.77728 -0.118769 -0.617843,
+                          3.81855e-18 0.42372 -0.905793,
+                          -2.24018e-16 0.473745 -0.880662,
+                          0 0.405863 -0.913934,
+                          3.81855e-18 0.42372 -0.905793,
+                          -1.01604e-17 0.504872 -0.863194,
+                          -2.24018e-16 0.473745 -0.880662,
+                          -0.164263 0.261851 -0.951027,
+                          0.928505 -0.170292 -0.329969,
+                          0.243829 0.331203 -0.911511,
+                          0.802097 -0.23478 -0.549108,
+                          0.963622 -0.25104 -0.0917151,
+                          0.928505 -0.170292 -0.329969,
+                          -2.8809e-18 0.359513 -0.93314,
+                          0 0.405863 -0.913934,
+                          0 0.350932 -0.936401,
+                          -0.164263 0.261851 -0.951027,
+                          0.802097 -0.23478 -0.549108,
+                          0.928505 -0.170292 -0.329969,
+                          -1.4077e-17 0.415586 -0.909554,
+                          0 0.405863 -0.913934,
+                          -2.8809e-18 0.359513 -0.93314,
+                          3.81855e-18 0.42372 -0.905793,
+                          0 0.405863 -0.913934,
+                          -1.4077e-17 0.415586 -0.909554,
+                          -0.259114 0.324392 -0.909742,
+                          0.243829 0.331203 -0.911511,
+                          0.133465 0.490411 -0.861211,
+                          -0.259114 0.324392 -0.909742,
+                          -0.164263 0.261851 -0.951027,
+                          0.243829 0.331203 -0.911511,
+                          -0.0904405 0.280724 -0.955518,
+                          0.133465 0.490411 -0.861211,
+                          0.414684 0.445615 -0.793388,
+                          -0.0904405 0.280724 -0.955518,
+                          -0.259114 0.324392 -0.909742,
+                          0.133465 0.490411 -0.861211,
+                          0.235352 0.158201 -0.958948,
+                          0.414684 0.445615 -0.793388,
+                          0.678229 0.325113 -0.65902,
+                          0.235352 0.158201 -0.958948,
+                          -0.0904405 0.280724 -0.955518,
+                          0.414684 0.445615 -0.793388,
+                          0.542994 0.0153088 -0.839597,
+                          0.678229 0.325113 -0.65902,
+                          0.85299 0.203334 -0.48069,
+                          0.542994 0.0153088 -0.839597,
+                          0.235352 0.158201 -0.958948,
+                          0.678229 0.325113 -0.65902,
+                          0.737614 -0.09765 -0.668124,
+                          0.85299 0.203334 -0.48069,
+                          0.953475 0.100451 -0.284244,
+                          0.737614 -0.09765 -0.668124,
+                          0.542994 0.0153088 -0.839597,
+                          0.85299 0.203334 -0.48069,
+                          0.830358 -0.151738 -0.536173,
+                          0.953475 0.100451 -0.284244,
+                          0.989173 0.0305905 -0.143528,
+                          0.830358 -0.151738 -0.536173,
+                          0.737614 -0.09765 -0.668124,
+                          0.953475 0.100451 -0.284244,
+                          0.995934 -0.00907015 -0.0896268,
+                          0.989173 0.0305905 -0.143528,
+                          0.995798 -0.0114863 -0.0908575,
+                          0.99617 -0.00940862 -0.0869327,
+                          0.989173 0.0305905 -0.143528,
+                          0.995934 -0.00907015 -0.0896268,
+                          0.902211 -0.176577 -0.393491,
+                          0.830358 -0.151738 -0.536173,
+                          0.989173 0.0305905 -0.143528,
+                          0.96128 -0.189715 -0.199873,
+                          0.902211 -0.176577 -0.393491,
+                          0.989173 0.0305905 -0.143528,
+                          0.988045 -0.0742196 -0.135122,
+                          0.96128 -0.189715 -0.199873,
+                          0.989173 0.0305905 -0.143528,
+                          0.994391 -0.0319203 -0.100837,
+                          0.988045 -0.0742196 -0.135122,
+                          0.989173 0.0305905 -0.143528,
+                          0.99617 -0.00940862 -0.0869327,
+                          0.994391 -0.0319203 -0.100837,
+                          0.989173 0.0305905 -0.143528,
+                          0.761193 -0.485493 0.429978,
+                          0.994987 -0.00396645 -0.0999237,
+                          0.994757 -0.0163976 -0.100942,
+                          0.762557 -0.461113 0.453742,
+                          0.995197 -0.00271149 -0.0978546,
+                          0.994987 -0.00396645 -0.0999237,
+                          0.762557 -0.461113 0.453742,
+                          0.994987 -0.00396645 -0.0999237,
+                          0.761193 -0.485493 0.429978,
+                          0.738706 -0.599682 0.307725,
+                          0.994757 -0.0163976 -0.100942,
+                          0.996101 -0.0260024 -0.0842998,
+                          0.761193 -0.485493 0.429978,
+                          0.994757 -0.0163976 -0.100942,
+                          0.738706 -0.599682 0.307725,
+                          0.738706 -0.599682 0.307725,
+                          0.996101 -0.0260024 -0.0842998,
+                          0.998011 -0.0289897 -0.0559784,
+                          0.738706 -0.599682 0.307725,
+                          0.998011 -0.0289897 -0.0559784,
+                          0.70684 -0.68542 -0.174864,
+                          0.762557 -0.461113 0.453742,
+                          0.995708 -0.00446879 -0.0924437,
+                          0.995197 -0.00271149 -0.0978546,
+                          -0.0844325 -0.0109864 -0.996369,
+                          -0.0622414 0.0416609 -0.997191,
+                          -0.513829 0.229627 -0.82659,
+                          -4.95196e-19 0.354975 -0.934876,
+                          -2.8809e-18 0.359513 -0.93314,
+                          0 0.350932 -0.936401,
+                          0.251922 0.0551414 -0.966175,
+                          0.802097 -0.23478 -0.549108,
+                          -0.164263 0.261851 -0.951027,
+                          0.251922 0.0551414 -0.966175,
+                          0.315878 -0.0205262 -0.948578,
+                          0.802097 -0.23478 -0.549108,
+                          -0.924945 0.186941 -0.330952,
+                          -0.513829 0.229627 -0.82659,
+                          -0.848602 0.468297 -0.246116,
+                          -0.618402 -0.215215 -0.755819,
+                          -0.107244 -0.0708239 -0.991707,
+                          -0.513829 0.229627 -0.82659,
+                          -0.0844325 -0.0109864 -0.996369,
+                          -0.513829 0.229627 -0.82659,
+                          -0.107244 -0.0708239 -0.991707,
+                          -0.924945 0.186941 -0.330952,
+                          -0.618402 -0.215215 -0.755819,
+                          -0.513829 0.229627 -0.82659,
+                          -0.109526 0.261919 -0.958855,
+                          -0.164263 0.261851 -0.951027,
+                          -0.259114 0.324392 -0.909742,
+                          -0.109526 0.261919 -0.958855,
+                          0.251922 0.0551414 -0.966175,
+                          -0.164263 0.261851 -0.951027,
+                          -0.175702 0.239853 -0.954777,
+                          -0.259114 0.324392 -0.909742,
+                          -0.0904405 0.280724 -0.955518,
+                          -0.175702 0.239853 -0.954777,
+                          -0.109526 0.261919 -0.958855,
+                          -0.259114 0.324392 -0.909742,
+                          -0.0677766 0.0933318 -0.993325,
+                          -0.0904405 0.280724 -0.955518,
+                          0.235352 0.158201 -0.958948,
+                          -0.0677766 0.0933318 -0.993325,
+                          -0.175702 0.239853 -0.954777,
+                          -0.0904405 0.280724 -0.955518,
+                          0.139746 -0.172428 -0.975059,
+                          0.235352 0.158201 -0.958948,
+                          0.542994 0.0153088 -0.839597,
+                          0.139746 -0.172428 -0.975059,
+                          -0.0677766 0.0933318 -0.993325,
+                          0.235352 0.158201 -0.958948,
+                          0.34302 -0.472339 -0.811932,
+                          0.542994 0.0153088 -0.839597,
+                          0.737614 -0.09765 -0.668124,
+                          0.34302 -0.472339 -0.811932,
+                          0.139746 -0.172428 -0.975059,
+                          0.542994 0.0153088 -0.839597,
+                          0.440311 -0.642765 -0.62688,
+                          0.737614 -0.09765 -0.668124,
+                          0.830358 -0.151738 -0.536173,
+                          0.440311 -0.642765 -0.62688,
+                          0.34302 -0.472339 -0.811932,
+                          0.737614 -0.09765 -0.668124,
+                          0.480754 -0.723146 -0.495919,
+                          0.830358 -0.151738 -0.536173,
+                          0.902211 -0.176577 -0.393491,
+                          0.480754 -0.723146 -0.495919,
+                          0.440311 -0.642765 -0.62688,
+                          0.830358 -0.151738 -0.536173,
+                          0.918342 -0.307486 -0.249201,
+                          0.902211 -0.176577 -0.393491,
+                          0.96128 -0.189715 -0.199873,
+                          0.759575 -0.563434 -0.324945,
+                          0.902211 -0.176577 -0.393491,
+                          0.918342 -0.307486 -0.249201,
+                          0.519343 -0.777408 -0.354852,
+                          0.480754 -0.723146 -0.495919,
+                          0.902211 -0.176577 -0.393491,
+                          0.759575 -0.563434 -0.324945,
+                          0.519343 -0.777408 -0.354852,
+                          0.902211 -0.176577 -0.393491,
+                          0.754112 -0.377624 0.537322,
+                          0.961949 -0.176629 -0.208462,
+                          0.986876 -0.0692081 -0.1459,
+                          0.736148 -0.431272 0.521622,
+                          0.91545 -0.305186 -0.262322,
+                          0.961949 -0.176629 -0.208462,
+                          0.736148 -0.431272 0.521622,
+                          0.961949 -0.176629 -0.208462,
+                          0.754112 -0.377624 0.537322,
+                          0.754112 -0.377624 0.537322,
+                          0.986876 -0.0692081 -0.1459,
+                          0.9938 -0.0261933 -0.108053,
+                          0.755683 -0.424929 0.498376,
+                          0.9938 -0.0261933 -0.108053,
+                          0.995708 -0.00446879 -0.0924437,
+                          0.754112 -0.377624 0.537322,
+                          0.9938 -0.0261933 -0.108053,
+                          0.755683 -0.424929 0.498376,
+                          0.755683 -0.424929 0.498376,
+                          0.995708 -0.00446879 -0.0924437,
+                          0.762557 -0.461113 0.453742,
+                          0.736148 -0.431272 0.521622,
+                          0.757145 -0.560538 -0.335454,
+                          0.91545 -0.305186 -0.262322,
+                          -0.924945 0.186941 -0.330952,
+                          -0.848602 0.468297 -0.246116,
+                          -0.785987 0.600891 -0.145446,
+                          0.295638 0.0287268 -0.954868,
+                          0.251922 0.0551414 -0.966175,
+                          -0.109526 0.261919 -0.958855,
+                          -0.769735 0.624657 -0.131572,
+                          -0.785987 0.600891 -0.145446,
+                          -0.638497 0.749398 -0.175284,
+                          -0.769735 0.624657 -0.131572,
+                          -0.924945 0.186941 -0.330952,
+                          -0.785987 0.600891 -0.145446,
+                          0.0350112 0.0903834 -0.995291,
+                          -0.109526 0.261919 -0.958855,
+                          -0.175702 0.239853 -0.954777,
+                          0.255998 -0.0401468 -0.965843,
+                          0.295638 0.0287268 -0.954868,
+                          -0.109526 0.261919 -0.958855,
+                          0.166393 -0.00046943 -0.986059,
+                          0.255998 -0.0401468 -0.965843,
+                          -0.109526 0.261919 -0.958855,
+                          0.0350112 0.0903834 -0.995291,
+                          0.166393 -0.00046943 -0.986059,
+                          -0.109526 0.261919 -0.958855,
+                          0.0233991 0.06071 -0.997881,
+                          -0.175702 0.239853 -0.954777,
+                          -0.0677766 0.0933318 -0.993325,
+                          0.0233991 0.06071 -0.997881,
+                          0.0350112 0.0903834 -0.995291,
+                          -0.175702 0.239853 -0.954777,
+                          0.183514 -0.270936 -0.944942,
+                          -0.0677766 0.0933318 -0.993325,
+                          0.139746 -0.172428 -0.975059,
+                          0.183514 -0.270936 -0.944942,
+                          0.0233991 0.06071 -0.997881,
+                          -0.0677766 0.0933318 -0.993325,
+                          0.294611 -0.634632 -0.714455,
+                          0.139746 -0.172428 -0.975059,
+                          0.34302 -0.472339 -0.811932,
+                          0.294611 -0.634632 -0.714455,
+                          0.183514 -0.270936 -0.944942,
+                          0.139746 -0.172428 -0.975059,
+                          0.294605 -0.79708 -0.527135,
+                          0.34302 -0.472339 -0.811932,
+                          0.440311 -0.642765 -0.62688,
+                          0.294605 -0.79708 -0.527135,
+                          0.294611 -0.634632 -0.714455,
+                          0.34302 -0.472339 -0.811932,
+                          0.268607 -0.8717 -0.409866,
+                          0.440311 -0.642765 -0.62688,
+                          0.480754 -0.723146 -0.495919,
+                          0.268607 -0.8717 -0.409866,
+                          0.294605 -0.79708 -0.527135,
+                          0.440311 -0.642765 -0.62688,
+                          0.321178 -0.88336 -0.341349,
+                          0.480754 -0.723146 -0.495919,
+                          0.519343 -0.777408 -0.354852,
+                          0.245547 -0.916152 -0.316816,
+                          0.268607 -0.8717 -0.409866,
+                          0.480754 -0.723146 -0.495919,
+                          0.252345 -0.913411 -0.319379,
+                          0.245547 -0.916152 -0.316816,
+                          0.480754 -0.723146 -0.495919,
+                          0.321178 -0.88336 -0.341349,
+                          0.252345 -0.913411 -0.319379,
+                          0.480754 -0.723146 -0.495919,
+                          0.759575 -0.563434 -0.324945,
+                          0.542178 -0.762186 -0.353717,
+                          0.519343 -0.777408 -0.354852,
+                          0.428541 -0.787286 0.44332,
+                          0.518311 -0.771975 -0.36798,
+                          0.540524 -0.756708 -0.367733,
+                          0.321178 -0.88336 -0.341349,
+                          0.519343 -0.777408 -0.354852,
+                          0.410688 -0.84026 -0.353974,
+                          0.428541 -0.787286 0.44332,
+                          0.407701 -0.837615 -0.363566,
+                          0.518311 -0.771975 -0.36798,
+                          0.631835 -0.614309 0.472662,
+                          0.540524 -0.756708 -0.367733,
+                          0.757145 -0.560538 -0.335454,
+                          0.428541 -0.787286 0.44332,
+                          0.540524 -0.756708 -0.367733,
+                          0.631835 -0.614309 0.472662,
+                          0.631835 -0.614309 0.472662,
+                          0.757145 -0.560538 -0.335454,
+                          0.736148 -0.431272 0.521622,
+                          0.300401 -0.846631 0.43929,
+                          0.322488 -0.879125 -0.350915,
+                          0.407701 -0.837615 -0.363566,
+                          0.300401 -0.846631 0.43929,
+                          0.407701 -0.837615 -0.363566,
+                          0.428541 -0.787286 0.44332,
+                          -0.553157 0.817369 -0.161014,
+                          -0.638497 0.749398 -0.175284,
+                          -0.390184 0.904984 -0.169588,
+                          -0.553157 0.817369 -0.161014,
+                          -0.769735 0.624657 -0.131572,
+                          -0.638497 0.749398 -0.175284,
+                          7.22427e-05 -0.0832198 -0.996531,
+                          0.255998 -0.0401468 -0.965843,
+                          0.166393 -0.00046943 -0.986059,
+                          0.000168569 -0.0684147 -0.997657,
+                          0.14073 -0.0652651 -0.987894,
+                          0.255998 -0.0401468 -0.965843,
+                          -0.386522 0.907492 -0.164499,
+                          -0.390184 0.904984 -0.169588,
+                          -0.182963 0.975113 -0.125216,
+                          7.22427e-05 -0.0832198 -0.996531,
+                          0.000168569 -0.0684147 -0.997657,
+                          0.255998 -0.0401468 -0.965843,
+                          -0.553157 0.817369 -0.161014,
+                          -0.390184 0.904984 -0.169588,
+                          -0.386522 0.907492 -0.164499,
+                          7.45087e-05 -0.0423384 -0.999103,
+                          0.166393 -0.00046943 -0.986059,
+                          0.0350112 0.0903834 -0.995291,
+                          7.45087e-05 -0.0423384 -0.999103,
+                          7.22427e-05 -0.0832198 -0.996531,
+                          0.166393 -0.00046943 -0.986059,
+                          0.000519117 0.0502122 -0.998738,
+                          0.0350112 0.0903834 -0.995291,
+                          0.0233991 0.06071 -0.997881,
+                          0.000519117 0.0502122 -0.998738,
+                          7.45087e-05 -0.0423384 -0.999103,
+                          0.0350112 0.0903834 -0.995291,
+                          -0.00228338 -0.247163 -0.968971,
+                          0.0233991 0.06071 -0.997881,
+                          0.183514 -0.270936 -0.944942,
+                          0.000544684 0.0352486 -0.999378,
+                          0.000519117 0.0502122 -0.998738,
+                          0.0233991 0.06071 -0.997881,
+                          -0.00228338 -0.247163 -0.968971,
+                          0.000544684 0.0352486 -0.999378,
+                          0.0233991 0.06071 -0.997881,
+                          -0.0070473 -0.600503 -0.799591,
+                          0.183514 -0.270936 -0.944942,
+                          0.294611 -0.634632 -0.714455,
+                          -0.0070473 -0.600503 -0.799591,
+                          -0.00228338 -0.247163 -0.968971,
+                          0.183514 -0.270936 -0.944942,
+                          -0.0111804 -0.835882 -0.548795,
+                          0.294611 -0.634632 -0.714455,
+                          0.294605 -0.79708 -0.527135,
+                          -0.0111804 -0.835882 -0.548795,
+                          -0.0070473 -0.600503 -0.799591,
+                          0.294611 -0.634632 -0.714455,
+                          -0.0122489 -0.908025 -0.418736,
+                          0.294605 -0.79708 -0.527135,
+                          0.268607 -0.8717 -0.409866,
+                          -0.0122489 -0.908025 -0.418736,
+                          -0.0111804 -0.835882 -0.548795,
+                          0.294605 -0.79708 -0.527135,
+                          -0.0117122 -0.942974 -0.33266,
+                          0.268607 -0.8717 -0.409866,
+                          0.245547 -0.916152 -0.316816,
+                          -0.0117122 -0.942974 -0.33266,
+                          -0.0122489 -0.908025 -0.418736,
+                          0.268607 -0.8717 -0.409866,
+                          0.132202 -0.865447 0.483244,
+                          0.245711 -0.912582 -0.326833,
+                          0.251187 -0.910315 -0.328986,
+                          -0.0117122 -0.942974 -0.33266,
+                          0.245547 -0.916152 -0.316816,
+                          0.147412 -0.94786 -0.282543,
+                          0.132202 -0.865447 0.483244,
+                          0.14332 -0.945608 -0.292036,
+                          0.245711 -0.912582 -0.326833,
+                          0.221671 -0.86175 0.456343,
+                          0.251187 -0.910315 -0.328986,
+                          0.322488 -0.879125 -0.350915,
+                          0.132202 -0.865447 0.483244,
+                          0.251187 -0.910315 -0.328986,
+                          0.221671 -0.86175 0.456343,
+                          0.221671 -0.86175 0.456343,
+                          0.322488 -0.879125 -0.350915,
+                          0.300401 -0.846631 0.43929,
+                          -0.0101402 -0.964362 -0.264392,
+                          -0.0117122 -0.942974 -0.33266,
+                          0.147412 -0.94786 -0.282543,
+                          -0.00463999 -0.864686 0.502291,
+                          0.015838 -0.961852 -0.273112,
+                          0.14332 -0.945608 -0.292036,
+                          0.132202 -0.865447 0.483244,
+                          -0.00463999 -0.864686 0.502291,
+                          0.14332 -0.945608 -0.292036,
+                          -0.187719 0.974345 -0.124148,
+                          -0.182963 0.975113 -0.125216,
+                          -0.000809532 0.994636 -0.103431,
+                          -0.386522 0.907492 -0.164499,
+                          -0.182963 0.975113 -0.125216,
+                          -0.187719 0.974345 -0.124148,
+                          -0.14073 -0.0652651 -0.987894,
+                          -0.000168569 -0.0684147 -0.997657,
+                          -7.22427e-05 -0.0832198 -0.996531,
+                          -0.00148747 0.994631 -0.103471,
+                          -0.187719 0.974345 -0.124148,
+                          -0.000809532 0.994636 -0.103431,
+                          0.182963 0.975113 -0.125216,
+                          0.00148747 0.994631 -0.103471,
+                          0.000809532 0.994636 -0.103431,
+                          -0.166394 -0.00047035 -0.986059,
+                          -7.22427e-05 -0.0832198 -0.996531,
+                          -7.45087e-05 -0.0423384 -0.999103,
+                          -0.255998 -0.0401468 -0.965843,
+                          -0.14073 -0.0652651 -0.987894,
+                          -7.22427e-05 -0.0832198 -0.996531,
+                          -0.166394 -0.00047035 -0.986059,
+                          -0.255998 -0.0401468 -0.965843,
+                          -7.22427e-05 -0.0832198 -0.996531,
+                          -0.0350142 0.090381 -0.995292,
+                          -7.45087e-05 -0.0423384 -0.999103,
+                          -0.000519117 0.0502122 -0.998738,
+                          -0.0350142 0.090381 -0.995292,
+                          -0.166394 -0.00047035 -0.986059,
+                          -7.45087e-05 -0.0423384 -0.999103,
+                          -0.0350142 0.090381 -0.995292,
+                          -0.000519117 0.0502122 -0.998738,
+                          -0.000544684 0.0352486 -0.999378,
+                          -0.0233953 0.0607173 -0.997881,
+                          -0.000544684 0.0352486 -0.999378,
+                          0.00228338 -0.247163 -0.968971,
+                          -0.0233953 0.0607173 -0.997881,
+                          -0.0350142 0.090381 -0.995292,
+                          -0.000544684 0.0352486 -0.999378,
+                          -0.183505 -0.270914 -0.944951,
+                          0.00228338 -0.247163 -0.968971,
+                          0.0070473 -0.600503 -0.799591,
+                          -0.183505 -0.270914 -0.944951,
+                          -0.0233953 0.0607173 -0.997881,
+                          0.00228338 -0.247163 -0.968971,
+                          -0.294609 -0.634616 -0.714471,
+                          0.0070473 -0.600503 -0.799591,
+                          0.0111804 -0.835882 -0.548795,
+                          -0.294609 -0.634616 -0.714471,
+                          -0.183505 -0.270914 -0.944951,
+                          0.0070473 -0.600503 -0.799591,
+                          -0.294607 -0.797072 -0.527147,
+                          0.0111804 -0.835882 -0.548795,
+                          0.0122489 -0.908025 -0.418736,
+                          -0.294607 -0.797072 -0.527147,
+                          -0.294609 -0.634616 -0.714471,
+                          0.0111804 -0.835882 -0.548795,
+                          -0.268609 -0.871695 -0.409875,
+                          0.0122489 -0.908025 -0.418736,
+                          0.0117122 -0.942974 -0.33266,
+                          -0.268609 -0.871695 -0.409875,
+                          -0.294607 -0.797072 -0.527147,
+                          0.0122489 -0.908025 -0.418736,
+                          -0.268609 -0.871695 -0.409875,
+                          0.0117122 -0.942974 -0.33266,
+                          0.0101402 -0.964362 -0.264392,
+                          -0.147504 -0.947839 -0.282568,
+                          -0.268609 -0.871695 -0.409875,
+                          0.0101402 -0.964362 -0.264392,
+                          0.00466106 -0.864682 0.502298,
+                          -0.143415 -0.945587 -0.292058,
+                          -0.0158773 -0.961851 -0.273114,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.927189 0.344338 -0.147486,
+                          0.770544 0.612044 -0.177943,
+                          0.833927 0.528771 -0.158012,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.943678 0.318924 -0.088088,
+                          0.927189 0.344338 -0.147486,
+                          0.833927 0.528771 -0.158012,
+                          0.891521 0.442728 -0.0958249,
+                          0.943678 0.318924 -0.088088,
+                          0.833927 0.528771 -0.158012,
+                          -1.61124e-15 0.959119 0.283002,
+                          1.34682e-15 0.903852 0.427846,
+                          0 0.999983 -0.00589021,
+                          -1.61124e-15 0.959119 0.283002,
+                          0 0.999983 -0.00589021,
+                          0 0.999983 -0.00589021,
+                          0.927189 0.344338 -0.147486,
+                          0.699015 0.687936 -0.195251,
+                          0.770544 0.612044 -0.177943,
+                          0.927189 0.344338 -0.147486,
+                          0.659559 0.698517 -0.277588,
+                          0.699015 0.687936 -0.195251,
+                          -0.707344 0.704194 -0.0614443,
+                          -0.705378 0.706618 -0.05597,
+                          -0.724824 0.688931 0.0019936,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.899972 0.375461 -0.221538,
+                          0.632546 0.704152 -0.322576,
+                          0.659559 0.698517 -0.277588,
+                          -0.73143 0.681887 -0.00637074,
+                          -0.724824 0.688931 0.0019936,
+                          -0.728747 0.682554 0.055208,
+                          0.927189 0.344338 -0.147486,
+                          0.899972 0.375461 -0.221538,
+                          0.659559 0.698517 -0.277588,
+                          -0.721124 0.691307 -0.0455562,
+                          -0.724824 0.688931 0.0019936,
+                          -0.73143 0.681887 -0.00637074,
+                          -0.709389 0.701605 -0.0672173,
+                          -0.724824 0.688931 0.0019936,
+                          -0.721124 0.691307 -0.0455562,
+                          -0.707344 0.704194 -0.0614443,
+                          -0.724824 0.688931 0.0019936,
+                          -0.709389 0.701605 -0.0672173,
+                          0.862143 0.413263 -0.293125,
+                          0.603589 0.713421 -0.355964,
+                          0.632546 0.704152 -0.322576,
+                          -0.736717 0.67406 0.0537594,
+                          -0.728747 0.682554 0.055208,
+                          -0.729667 0.674472 0.112577,
+                          0.899972 0.375461 -0.221538,
+                          0.862143 0.413263 -0.293125,
+                          0.632546 0.704152 -0.322576,
+                          -0.73143 0.681887 -0.00637074,
+                          -0.728747 0.682554 0.055208,
+                          -0.736717 0.67406 0.0537594,
+                          0.862143 0.413263 -0.293125,
+                          0.646643 0.675172 -0.35496,
+                          0.603589 0.713421 -0.355964,
+                          -3.28528e-17 0.878603 -0.477554,
+                          -6.87921e-16 0.905204 -0.424976,
+                          6.89368e-16 0.860811 -0.508925,
+                          -0.736717 0.67406 0.0537594,
+                          -0.729667 0.674472 0.112577,
+                          -0.739818 0.663394 0.112153,
+                          -0.741656 0.655585 0.141967,
+                          -0.739818 0.663394 0.112153,
+                          -0.729667 0.674472 0.112577,
+                          0.829328 0.4432 -0.340279,
+                          0.718105 0.604752 -0.344383,
+                          0.646643 0.675172 -0.35496,
+                          -3.8878e-17 0.849781 -0.527136,
+                          6.89368e-16 0.860811 -0.508925,
+                          -3.61925e-17 0.811318 -0.584606,
+                          0.862143 0.413263 -0.293125,
+                          0.829328 0.4432 -0.340279,
+                          0.646643 0.675172 -0.35496,
+                          -3.28528e-17 0.878603 -0.477554,
+                          6.89368e-16 0.860811 -0.508925,
+                          -3.8878e-17 0.849781 -0.527136,
+                          0.813021 0.43997 -0.381344,
+                          0.776227 0.499455 -0.38473,
+                          0.718105 0.604752 -0.344383,
+                          0 0.804531 -0.593911,
+                          -3.61925e-17 0.811318 -0.584606,
+                          -3.2367e-16 0.759479 -0.650532,
+                          0.829328 0.4432 -0.340279,
+                          0.813021 0.43997 -0.381344,
+                          0.718105 0.604752 -0.344383,
+                          0 0.804531 -0.593911,
+                          -3.8878e-17 0.849781 -0.527136,
+                          -3.61925e-17 0.811318 -0.584606,
+                          0.813021 0.43997 -0.381344,
+                          0.794015 0.381232 -0.473501,
+                          0.776227 0.499455 -0.38473,
+                          -2.62251e-17 0.758935 -0.651166,
+                          -3.2367e-16 0.759479 -0.650532,
+                          -1.65832e-16 0.712488 -0.701684,
+                          0 0.804531 -0.593911,
+                          -3.2367e-16 0.759479 -0.650532,
+                          -2.62251e-17 0.758935 -0.651166,
+                          -7.9449e-18 0.715268 -0.698851,
+                          -1.65832e-16 0.712488 -0.701684,
+                          -1.43886e-16 0.708153 -0.706059,
+                          -2.62251e-17 0.758935 -0.651166,
+                          -1.65832e-16 0.712488 -0.701684,
+                          -7.9449e-18 0.715268 -0.698851,
+                          0.891521 0.442728 -0.0958249,
+                          0.954524 0.295499 -0.0395538,
+                          0.943678 0.318924 -0.088088,
+                          5.73092e-17 0.822371 0.568952,
+                          2.4377e-16 0.64515 0.764056,
+                          1.34682e-15 0.903852 0.427846,
+                          -8.52113e-16 0.604413 0.796671,
+                          3.00742e-16 0.610511 0.792008,
+                          2.4377e-16 0.64515 0.764056,
+                          -8.52113e-16 0.604413 0.796671,
+                          2.4377e-16 0.64515 0.764056,
+                          5.73092e-17 0.822371 0.568952,
+                          5.73092e-17 0.822371 0.568952,
+                          1.34682e-15 0.903852 0.427846,
+                          -1.61124e-15 0.959119 0.283002,
+                          -4.74162e-16 0.563585 0.826058,
+                          -4.23974e-15 0.201696 0.979448,
+                          3.00742e-16 0.610511 0.792008,
+                          -4.74162e-16 0.563585 0.826058,
+                          3.00742e-16 0.610511 0.792008,
+                          -8.52113e-16 0.604413 0.796671,
+                          0 0.688935 -0.724823,
+                          -1.43886e-16 0.708153 -0.706059,
+                          1.90914e-16 0.622314 -0.782768,
+                          -7.9449e-18 0.715268 -0.698851,
+                          -1.43886e-16 0.708153 -0.706059,
+                          0 0.688935 -0.724823,
+                          -2.82599e-16 0.617336 -0.786699,
+                          1.90914e-16 0.622314 -0.782768,
+                          -4.15069e-16 0.556875 -0.830596,
+                          0 0.677252 -0.735751,
+                          0 0.688935 -0.724823,
+                          1.90914e-16 0.622314 -0.782768,
+                          -7.09598e-17 0.647104 -0.762402,
+                          0 0.677252 -0.735751,
+                          1.90914e-16 0.622314 -0.782768,
+                          -7.09598e-17 0.647104 -0.762402,
+                          1.90914e-16 0.622314 -0.782768,
+                          -2.82599e-16 0.617336 -0.786699,
+                          -3.98506e-16 0.56066 -0.828046,
+                          -4.15069e-16 0.556875 -0.830596,
+                          -3.54196e-17 0.552662 -0.833405,
+                          -2.82599e-16 0.617336 -0.786699,
+                          -4.15069e-16 0.556875 -0.830596,
+                          -3.98506e-16 0.56066 -0.828046,
+                          8.51351e-16 -0.251258 0.96792,
+                          -1.96067e-15 -0.241134 0.970492,
+                          -4.23974e-15 0.201696 0.979448,
+                          2.25432e-15 -0.40689 0.913477,
+                          -1.96067e-15 -0.241134 0.970492,
+                          8.51351e-16 -0.251258 0.96792,
+                          8.51351e-16 -0.251258 0.96792,
+                          -4.23974e-15 0.201696 0.979448,
+                          -4.74162e-16 0.563585 0.826058,
+                          -0.255495 0.899242 0.355085,
+                          0.0169062 0.954993 0.296146,
+                          0.0129563 0.968689 0.24794,
+                          0.255495 0.899242 0.355085,
+                          -0.0129563 0.968689 0.24794,
+                          -0.0169062 0.954993 0.296146,
+                          -0.213351 0.93399 0.286607,
+                          -0.255495 0.899242 0.355085,
+                          0.0129563 0.968689 0.24794,
+                          0.0180077 -0.268888 0.963003,
+                          0.0286089 -0.28318 0.95864,
+                          -0.0279309 -0.24344 0.969514,
+                          -0.0271695 -0.243695 0.969471,
+                          0.0180077 -0.268888 0.963003,
+                          -0.0279309 -0.24344 0.969514,
+                          -0.0286089 -0.28318 0.95864,
+                          0.0271695 -0.243695 0.969471,
+                          0.0279309 -0.24344 0.969514,
+                          0.255495 0.899242 0.355085,
+                          0.213351 0.93399 0.286607,
+                          -0.0129563 0.968689 0.24794,
+                          -0.272414 0.864531 0.422346,
+                          0.02128 0.937663 0.346893,
+                          0.0169062 0.954993 0.296146,
+                          0.255495 0.899242 0.355085,
+                          -0.0169062 0.954993 0.296146,
+                          -0.02128 0.937663 0.346893,
+                          -0.255495 0.899242 0.355085,
+                          -0.272414 0.864531 0.422346,
+                          0.0169062 0.954993 0.296146,
+                          -0.272414 0.864531 0.422346,
+                          0.0257165 0.914976 0.402689,
+                          0.02128 0.937663 0.346893,
+                          0.272414 0.864531 0.422346,
+                          -0.02128 0.937663 0.346893,
+                          -0.0257165 0.914976 0.402689,
+                          0.272414 0.864531 0.422346,
+                          0.255495 0.899242 0.355085,
+                          -0.02128 0.937663 0.346893,
+                          -0.290234 0.81442 0.502478,
+                          0.0295402 0.881854 0.470596,
+                          0.0257165 0.914976 0.402689,
+                          0.290234 0.81442 0.502478,
+                          -0.0257165 0.914976 0.402689,
+                          -0.0295402 0.881854 0.470596,
+                          -0.272414 0.864531 0.422346,
+                          -0.290234 0.81442 0.502478,
+                          0.0257165 0.914976 0.402689,
+                          0.290234 0.81442 0.502478,
+                          0.272414 0.864531 0.422346,
+                          -0.0257165 0.914976 0.402689,
+                          -0.300554 0.73156 0.611954,
+                          0.0325222 0.826121 0.562554,
+                          0.0295402 0.881854 0.470596,
+                          0.300554 0.73156 0.611954,
+                          -0.0295402 0.881854 0.470596,
+                          -0.0325222 0.826121 0.562554,
+                          -0.290234 0.81442 0.502478,
+                          -0.300554 0.73156 0.611954,
+                          0.0295402 0.881854 0.470596,
+                          0.300554 0.73156 0.611954,
+                          0.290234 0.81442 0.502478,
+                          -0.0295402 0.881854 0.470596,
+                          -0.285443 0.585657 0.758636,
+                          0.029158 0.701911 0.711667,
+                          0.0325222 0.826121 0.562554,
+                          0.285443 0.585657 0.758636,
+                          -0.0325222 0.826121 0.562554,
+                          -0.029158 0.701911 0.711667,
+                          -0.300554 0.73156 0.611954,
+                          -0.285443 0.585657 0.758636,
+                          0.0325222 0.826121 0.562554,
+                          0.285443 0.585657 0.758636,
+                          0.300554 0.73156 0.611954,
+                          -0.0325222 0.826121 0.562554,
+                          -0.207026 0.331087 0.920609,
+                          0.0145537 0.438783 0.898475,
+                          0.029158 0.701911 0.711667,
+                          0.207026 0.331087 0.920609,
+                          -0.029158 0.701911 0.711667,
+                          -0.0145537 0.438783 0.898475,
+                          -0.285443 0.585657 0.758636,
+                          -0.207026 0.331087 0.920609,
+                          0.029158 0.701911 0.711667,
+                          0.207026 0.331087 0.920609,
+                          0.285443 0.585657 0.758636,
+                          -0.029158 0.701911 0.711667,
+                          -0.0806768 0.0505452 0.995458,
+                          0.0015571 0.0544332 0.998516,
+                          0.0145537 0.438783 0.898475,
+                          0.0806768 0.0505452 0.995458,
+                          -0.0145537 0.438783 0.898475,
+                          -0.0015571 0.0544332 0.998516,
+                          -0.207026 0.331087 0.920609,
+                          -0.0806768 0.0505452 0.995458,
+                          0.0145537 0.438783 0.898475,
+                          0.0806768 0.0505452 0.995458,
+                          0.207026 0.331087 0.920609,
+                          -0.0145537 0.438783 0.898475,
+                          -0.00636165 -0.0948697 0.995469,
+                          1.91095e-07 -0.0464812 0.998919,
+                          0.0015571 0.0544332 0.998516,
+                          0.0806768 0.0505452 0.995458,
+                          -0.0015571 0.0544332 0.998516,
+                          -1.91095e-07 -0.0464812 0.998919,
+                          -0.0806768 0.0505452 0.995458,
+                          -0.00636165 -0.0948697 0.995469,
+                          0.0015571 0.0544332 0.998516,
+                          -0.00636165 -0.0948697 0.995469,
+                          -7.1791e-05 -0.0703683 0.997521,
+                          1.91095e-07 -0.0464812 0.998919,
+                          0.00636165 -0.0948697 0.995469,
+                          -1.91095e-07 -0.0464812 0.998919,
+                          7.1791e-05 -0.0703683 0.997521,
+                          0.00636165 -0.0948697 0.995469,
+                          0.0806768 0.0505452 0.995458,
+                          -1.91095e-07 -0.0464812 0.998919,
+                          -0.0253113 -0.0994692 0.994719,
+                          0.000806647 -0.0273726 0.999625,
+                          -7.1791e-05 -0.0703683 0.997521,
+                          0.0253113 -0.0994692 0.994719,
+                          7.1791e-05 -0.0703683 0.997521,
+                          -0.000806647 -0.0273726 0.999625,
+                          -0.00636165 -0.0948697 0.995469,
+                          -0.0253113 -0.0994692 0.994719,
+                          -7.1791e-05 -0.0703683 0.997521,
+                          0.0253113 -0.0994692 0.994719,
+                          0.00636165 -0.0948697 0.995469,
+                          7.1791e-05 -0.0703683 0.997521,
+                          -0.117242 -0.0290739 0.992678,
+                          0.000207797 0.0498483 0.998757,
+                          0.000806647 -0.0273726 0.999625,
+                          0.0253113 -0.0994692 0.994719,
+                          -0.000806647 -0.0273726 0.999625,
+                          -0.000207797 0.0498483 0.998757,
+                          -0.0253113 -0.0994692 0.994719,
+                          -0.117242 -0.0290739 0.992678,
+                          0.000806647 -0.0273726 0.999625,
+                          -0.117242 -0.0290739 0.992678,
+                          -0.00106788 0.0756468 0.997134,
+                          0.000207797 0.0498483 0.998757,
+                          0.117242 -0.0290739 0.992678,
+                          -0.000207797 0.0498483 0.998757,
+                          0.00106788 0.0756468 0.997134,
+                          0.117242 -0.0290739 0.992678,
+                          0.0253113 -0.0994692 0.994719,
+                          -0.000207797 0.0498483 0.998757,
+                          -0.200806 0.0176098 0.979473,
+                          -0.00145976 0.0813091 0.996688,
+                          -0.00106788 0.0756468 0.997134,
+                          0.200806 0.0176098 0.979473,
+                          0.00106788 0.0756468 0.997134,
+                          0.00145976 0.0813091 0.996688,
+                          -0.117242 -0.0290739 0.992678,
+                          -0.200806 0.0176098 0.979473,
+                          -0.00106788 0.0756468 0.997134,
+                          0.200806 0.0176098 0.979473,
+                          0.117242 -0.0290739 0.992678,
+                          0.00106788 0.0756468 0.997134,
+                          -0.141165 0.0873124 0.986128,
+                          -0.00148532 0.0906163 0.995885,
+                          -0.00145976 0.0813091 0.996688,
+                          0.262863 0.0601202 0.962958,
+                          0.00145976 0.0813091 0.996688,
+                          0.00148532 0.0906163 0.995885,
+                          -0.262863 0.0601202 0.962958,
+                          -0.141165 0.0873124 0.986128,
+                          -0.00145976 0.0813091 0.996688,
+                          -0.200806 0.0176098 0.979473,
+                          -0.262863 0.0601202 0.962958,
+                          -0.00145976 0.0813091 0.996688,
+                          0.262863 0.0601202 0.962958,
+                          0.200806 0.0176098 0.979473,
+                          0.00145976 0.0813091 0.996688,
+                          -0.00148747 0.994631 -0.103471,
+                          -0.00221593 0.994626 -0.103511,
+                          -0.187719 0.974345 -0.124148,
+                          0.182963 0.975113 -0.125216,
+                          0.00221593 0.994626 -0.103511,
+                          0.00148747 0.994631 -0.103471,
+                          0.187719 0.974345 -0.124148,
+                          0.00221593 0.994626 -0.103511,
+                          0.182963 0.975113 -0.125216,
+                          0.141165 0.0873124 0.986128,
+                          0.262863 0.0601202 0.962958,
+                          0.00148532 0.0906163 0.995885,
+                          -0.307526 -0.00199125 0.951538,
+                          -0.262863 0.0601202 0.962958,
+                          -0.200806 0.0176098 0.979473,
+                          0.0335298 -0.23329 0.971829,
+                          -0.200806 0.0176098 0.979473,
+                          -0.117242 -0.0290739 0.992678,
+                          -0.249847 -0.0553123 0.966704,
+                          -0.200806 0.0176098 0.979473,
+                          0.0335298 -0.23329 0.971829,
+                          -0.307526 -0.00199125 0.951538,
+                          -0.200806 0.0176098 0.979473,
+                          -0.249847 -0.0553123 0.966704,
+                          0.160322 -0.271125 0.949099,
+                          -0.117242 -0.0290739 0.992678,
+                          -0.0253113 -0.0994692 0.994719,
+                          0.0335298 -0.23329 0.971829,
+                          -0.117242 -0.0290739 0.992678,
+                          0.160322 -0.271125 0.949099,
+                          0.173303 -0.23585 0.956212,
+                          -0.0253113 -0.0994692 0.994719,
+                          -0.00636165 -0.0948697 0.995469,
+                          0.160322 -0.271125 0.949099,
+                          -0.0253113 -0.0994692 0.994719,
+                          0.173303 -0.23585 0.956212,
+                          0.107548 -0.143016 0.98386,
+                          -0.00636165 -0.0948697 0.995469,
+                          -0.0806768 0.0505452 0.995458,
+                          0.173303 -0.23585 0.956212,
+                          -0.00636165 -0.0948697 0.995469,
+                          0.107548 -0.143016 0.98386,
+                          -0.0151815 0.00954459 0.999839,
+                          -0.0806768 0.0505452 0.995458,
+                          -0.207026 0.331087 0.920609,
+                          0.107548 -0.143016 0.98386,
+                          -0.0806768 0.0505452 0.995458,
+                          -0.0151815 0.00954459 0.999839,
+                          -0.165251 0.208397 0.963983,
+                          -0.207026 0.331087 0.920609,
+                          -0.285443 0.585657 0.758636,
+                          -0.0151815 0.00954459 0.999839,
+                          -0.207026 0.331087 0.920609,
+                          -0.165251 0.208397 0.963983,
+                          -0.30895 0.419535 0.853546,
+                          -0.285443 0.585657 0.758636,
+                          -0.300554 0.73156 0.611954,
+                          -0.165251 0.208397 0.963983,
+                          -0.285443 0.585657 0.758636,
+                          -0.30895 0.419535 0.853546,
+                          -0.401512 0.571712 0.715495,
+                          -0.300554 0.73156 0.611954,
+                          -0.290234 0.81442 0.502478,
+                          -0.30895 0.419535 0.853546,
+                          -0.300554 0.73156 0.611954,
+                          -0.401512 0.571712 0.715495,
+                          -0.449388 0.659924 0.602122,
+                          -0.290234 0.81442 0.502478,
+                          -0.272414 0.864531 0.422346,
+                          -0.401512 0.571712 0.715495,
+                          -0.290234 0.81442 0.502478,
+                          -0.449388 0.659924 0.602122,
+                          -0.478944 0.716167 0.507658,
+                          -0.272414 0.864531 0.422346,
+                          -0.255495 0.899242 0.355085,
+                          -0.449388 0.659924 0.602122,
+                          -0.272414 0.864531 0.422346,
+                          -0.478944 0.716167 0.507658,
+                          -0.213351 0.93399 0.286607,
+                          -0.242724 0.923939 0.295672,
+                          -0.255495 0.899242 0.355085,
+                          -0.505425 0.757504 0.413199,
+                          -0.255495 0.899242 0.355085,
+                          -0.242724 0.923939 0.295672,
+                          -0.478944 0.716167 0.507658,
+                          -0.255495 0.899242 0.355085,
+                          -0.505425 0.757504 0.413199,
+                          0.0446728 -0.293816 0.954817,
+                          0.0407642 -0.294818 0.954684,
+                          0.0286089 -0.28318 0.95864,
+                          -0.365389 0.873722 0.321093,
+                          -0.505425 0.757504 0.413199,
+                          -0.242724 0.923939 0.295672,
+                          0.0624972 -0.309185 0.948946,
+                          0.0663166 -0.316575 0.946247,
+                          0.0407642 -0.294818 0.954684,
+                          0.0446728 -0.293816 0.954817,
+                          0.0624972 -0.309185 0.948946,
+                          0.0407642 -0.294818 0.954684,
+                          0.0180077 -0.268888 0.963003,
+                          0.0446728 -0.293816 0.954817,
+                          0.0286089 -0.28318 0.95864,
+                          0.0165788 -0.196141 0.980435,
+                          -0.951044 0.199036 0.236431,
+                          -0.960484 0.250939 0.120413,
+                          -0.778902 0.221473 0.586738,
+                          0.0165788 -0.196141 0.980435,
+                          -0.960484 0.250939 0.120413,
+                          0.0165788 -0.196141 0.980435,
+                          -0.482545 -0.175989 0.858008,
+                          -0.951044 0.199036 0.236431,
+                          -0.946359 0.192631 0.25942,
+                          -0.951044 0.199036 0.236431,
+                          -0.482545 -0.175989 0.858008,
+                          0.255018 -0.307073 0.916882,
+                          -0.137327 -0.414572 0.899595,
+                          -0.482545 -0.175989 0.858008,
+                          -0.421691 -0.0157304 0.906603,
+                          -0.482545 -0.175989 0.858008,
+                          -0.137327 -0.414572 0.899595,
+                          0.0165788 -0.196141 0.980435,
+                          0.255018 -0.307073 0.916882,
+                          -0.482545 -0.175989 0.858008,
+                          -0.728599 0.159484 0.666115,
+                          -0.482545 -0.175989 0.858008,
+                          -0.421691 -0.0157304 0.906603,
+                          -0.852457 0.190459 0.486871,
+                          -0.482545 -0.175989 0.858008,
+                          -0.728599 0.159484 0.666115,
+                          -0.946359 0.192631 0.25942,
+                          -0.482545 -0.175989 0.858008,
+                          -0.852457 0.190459 0.486871,
+                          0.247035 -0.323202 0.913518,
+                          -0.137312 -0.492055 0.859667,
+                          -0.137327 -0.414572 0.899595,
+                          -0.373601 -0.113321 0.920641,
+                          -0.137327 -0.414572 0.899595,
+                          -0.137312 -0.492055 0.859667,
+                          0.255018 -0.307073 0.916882,
+                          0.247035 -0.323202 0.913518,
+                          -0.137327 -0.414572 0.899595,
+                          -0.421691 -0.0157304 0.906603,
+                          -0.137327 -0.414572 0.899595,
+                          -0.373601 -0.113321 0.920641,
+                          0.126872 -0.291549 0.948105,
+                          -0.335034 -0.469696 0.816785,
+                          -0.137312 -0.492055 0.859667,
+                          -0.555027 -0.148919 0.818394,
+                          -0.137312 -0.492055 0.859667,
+                          -0.335034 -0.469696 0.816785,
+                          0.247035 -0.323202 0.913518,
+                          0.126872 -0.291549 0.948105,
+                          -0.137312 -0.492055 0.859667,
+                          -0.373601 -0.113321 0.920641,
+                          -0.137312 -0.492055 0.859667,
+                          -0.555027 -0.148919 0.818394,
+                          -0.090887 -0.213489 0.972709,
+                          -0.546312 -0.397497 0.737252,
+                          -0.335034 -0.469696 0.816785,
+                          -0.727389 -0.164286 0.66627,
+                          -0.335034 -0.469696 0.816785,
+                          -0.546312 -0.397497 0.737252,
+                          0.126872 -0.291549 0.948105,
+                          -0.090887 -0.213489 0.972709,
+                          -0.335034 -0.469696 0.816785,
+                          -0.555027 -0.148919 0.818394,
+                          -0.335034 -0.469696 0.816785,
+                          -0.727389 -0.164286 0.66627,
+                          -0.329525 -0.114292 0.937204,
+                          -0.716697 -0.307717 0.625824,
+                          -0.546312 -0.397497 0.737252,
+                          -0.837541 -0.167833 0.519959,
+                          -0.546312 -0.397497 0.737252,
+                          -0.716697 -0.307717 0.625824,
+                          -0.090887 -0.213489 0.972709,
+                          -0.329525 -0.114292 0.937204,
+                          -0.546312 -0.397497 0.737252,
+                          -0.727389 -0.164286 0.66627,
+                          -0.546312 -0.397497 0.737252,
+                          -0.837541 -0.167833 0.519959,
+                          -0.5376 -0.0151858 0.843063,
+                          -0.842885 -0.216925 0.492431,
+                          -0.716697 -0.307717 0.625824,
+                          -0.903023 -0.158325 0.399354,
+                          -0.716697 -0.307717 0.625824,
+                          -0.842885 -0.216925 0.492431,
+                          -0.329525 -0.114292 0.937204,
+                          -0.5376 -0.0151858 0.843063,
+                          -0.716697 -0.307717 0.625824,
+                          -0.837541 -0.167833 0.519959,
+                          -0.716697 -0.307717 0.625824,
+                          -0.903023 -0.158325 0.399354,
+                          -0.787508 0.126598 0.603161,
+                          -0.925441 -0.136228 0.353554,
+                          -0.842885 -0.216925 0.492431,
+                          -0.942738 -0.134963 0.305009,
+                          -0.842885 -0.216925 0.492431,
+                          -0.925441 -0.136228 0.353554,
+                          -0.693621 0.0711805 0.716815,
+                          -0.787508 0.126598 0.603161,
+                          -0.842885 -0.216925 0.492431,
+                          -0.5376 -0.0151858 0.843063,
+                          -0.693621 0.0711805 0.716815,
+                          -0.842885 -0.216925 0.492431,
+                          -0.903023 -0.158325 0.399354,
+                          -0.842885 -0.216925 0.492431,
+                          -0.942738 -0.134963 0.305009,
+                          -0.847576 0.156578 0.507048,
+                          -0.969242 -0.0750954 0.234371,
+                          -0.925441 -0.136228 0.353554,
+                          -0.966586 -0.103606 0.234474,
+                          -0.925441 -0.136228 0.353554,
+                          -0.969242 -0.0750954 0.234371,
+                          -0.787508 0.126598 0.603161,
+                          -0.847576 0.156578 0.507048,
+                          -0.925441 -0.136228 0.353554,
+                          -0.942738 -0.134963 0.305009,
+                          -0.925441 -0.136228 0.353554,
+                          -0.966586 -0.103606 0.234474,
+                          -0.901234 0.175731 0.396101,
+                          -0.988429 -0.0282985 0.149018,
+                          -0.969242 -0.0750954 0.234371,
+                          -0.98087 -0.0717658 0.180953,
+                          -0.969242 -0.0750954 0.234371,
+                          -0.988429 -0.0282985 0.149018,
+                          -0.847576 0.156578 0.507048,
+                          -0.901234 0.175731 0.396101,
+                          -0.969242 -0.0750954 0.234371,
+                          -0.966586 -0.103606 0.234474,
+                          -0.969242 -0.0750954 0.234371,
+                          -0.98087 -0.0717658 0.180953,
+                          -0.945989 0.184908 0.266298,
+                          -0.994285 0.00251376 0.106732,
+                          -0.988429 -0.0282985 0.149018,
+                          -0.989718 -0.0472321 0.135006,
+                          -0.988429 -0.0282985 0.149018,
+                          -0.994285 0.00251376 0.106732,
+                          -0.901234 0.175731 0.396101,
+                          -0.945989 0.184908 0.266298,
+                          -0.988429 -0.0282985 0.149018,
+                          -0.98087 -0.0717658 0.180953,
+                          -0.988429 -0.0282985 0.149018,
+                          -0.989718 -0.0472321 0.135006,
+                          -0.995993 0.0194826 0.0872826,
+                          -0.995764 0.0215583 0.0893857,
+                          -0.994285 0.00251376 0.106732,
+                          -0.994987 -0.0311637 0.0950298,
+                          -0.994285 0.00251376 0.106732,
+                          -0.995764 0.0215583 0.0893857,
+                          -0.995101 0.0505346 0.0849726,
+                          -0.995993 0.0194826 0.0872826,
+                          -0.994285 0.00251376 0.106732,
+                          -0.970285 0.190321 0.149412,
+                          -0.995101 0.0505346 0.0849726,
+                          -0.994285 0.00251376 0.106732,
+                          -0.945989 0.184908 0.266298,
+                          -0.970285 0.190321 0.149412,
+                          -0.994285 0.00251376 0.106732,
+                          -0.989718 -0.0472321 0.135006,
+                          -0.994285 0.00251376 0.106732,
+                          -0.994987 -0.0311637 0.0950298,
+                          0.0712965 -0.672853 0.736333,
+                          0.0659443 -0.675302 0.734588,
+                          0.0749824 -0.666713 0.741533,
+                          -0.99585 0.0264665 0.0870774,
+                          -0.994987 -0.0311637 0.0950298,
+                          -0.995764 0.0215583 0.0893857,
+                          0.058581 -0.68417 0.726966,
+                          0.0506791 -0.693135 0.719024,
+                          0.0659443 -0.675302 0.734588,
+                          0.0712965 -0.672853 0.736333,
+                          0.058581 -0.68417 0.726966,
+                          0.0659443 -0.675302 0.734588,
+                          0.0822112 -0.651088 0.754537,
+                          0.0749824 -0.666713 0.741533,
+                          0.0957278 -0.578003 0.8104,
+                          0.0822112 -0.651088 0.754537,
+                          0.0712965 -0.672853 0.736333,
+                          0.0749824 -0.666713 0.741533,
+                          0.110112 -0.465757 0.878035,
+                          0.0957278 -0.578003 0.8104,
+                          0.127223 -0.360406 0.924079,
+                          0.0927903 -0.599036 0.795328,
+                          0.0822112 -0.651088 0.754537,
+                          0.0957278 -0.578003 0.8104,
+                          0.110112 -0.465757 0.878035,
+                          0.0927903 -0.599036 0.795328,
+                          0.0957278 -0.578003 0.8104,
+                          -0.912857 0.350296 0.209723,
+                          -0.970285 0.190321 0.149412,
+                          -0.945989 0.184908 0.266298,
+                          0.143734 -0.299298 0.943272,
+                          0.127223 -0.360406 0.924079,
+                          0.160059 -0.260343 0.952157,
+                          0.143734 -0.299298 0.943272,
+                          0.110112 -0.465757 0.878035,
+                          0.127223 -0.360406 0.924079,
+                          -0.505425 0.757504 0.413199,
+                          -0.945989 0.184908 0.266298,
+                          -0.901234 0.175731 0.396101,
+                          -0.738187 0.611802 0.284216,
+                          -0.912857 0.350296 0.209723,
+                          -0.945989 0.184908 0.266298,
+                          -0.560571 0.76623 0.31409,
+                          -0.738187 0.611802 0.284216,
+                          -0.945989 0.184908 0.266298,
+                          -0.533536 0.784067 0.317141,
+                          -0.560571 0.76623 0.31409,
+                          -0.945989 0.184908 0.266298,
+                          -0.505425 0.757504 0.413199,
+                          -0.533536 0.784067 0.317141,
+                          -0.945989 0.184908 0.266298,
+                          -0.478944 0.716167 0.507658,
+                          -0.901234 0.175731 0.396101,
+                          -0.847576 0.156578 0.507048,
+                          -0.478944 0.716167 0.507658,
+                          -0.505425 0.757504 0.413199,
+                          -0.901234 0.175731 0.396101,
+                          -0.449388 0.659924 0.602122,
+                          -0.847576 0.156578 0.507048,
+                          -0.787508 0.126598 0.603161,
+                          -0.449388 0.659924 0.602122,
+                          -0.478944 0.716167 0.507658,
+                          -0.847576 0.156578 0.507048,
+                          -0.401512 0.571712 0.715495,
+                          -0.787508 0.126598 0.603161,
+                          -0.693621 0.0711805 0.716815,
+                          -0.401512 0.571712 0.715495,
+                          -0.449388 0.659924 0.602122,
+                          -0.787508 0.126598 0.603161,
+                          -0.30895 0.419535 0.853546,
+                          -0.693621 0.0711805 0.716815,
+                          -0.5376 -0.0151858 0.843063,
+                          -0.30895 0.419535 0.853546,
+                          -0.401512 0.571712 0.715495,
+                          -0.693621 0.0711805 0.716815,
+                          -0.165251 0.208397 0.963983,
+                          -0.5376 -0.0151858 0.843063,
+                          -0.329525 -0.114292 0.937204,
+                          -0.165251 0.208397 0.963983,
+                          -0.30895 0.419535 0.853546,
+                          -0.5376 -0.0151858 0.843063,
+                          -0.0151815 0.00954459 0.999839,
+                          -0.329525 -0.114292 0.937204,
+                          -0.090887 -0.213489 0.972709,
+                          -0.0151815 0.00954459 0.999839,
+                          -0.165251 0.208397 0.963983,
+                          -0.329525 -0.114292 0.937204,
+                          0.107548 -0.143016 0.98386,
+                          -0.090887 -0.213489 0.972709,
+                          0.126872 -0.291549 0.948105,
+                          0.107548 -0.143016 0.98386,
+                          -0.0151815 0.00954459 0.999839,
+                          -0.090887 -0.213489 0.972709,
+                          0.173303 -0.23585 0.956212,
+                          0.126872 -0.291549 0.948105,
+                          0.247035 -0.323202 0.913518,
+                          0.173303 -0.23585 0.956212,
+                          0.107548 -0.143016 0.98386,
+                          0.126872 -0.291549 0.948105,
+                          0.160322 -0.271125 0.949099,
+                          0.247035 -0.323202 0.913518,
+                          0.255018 -0.307073 0.916882,
+                          0.160322 -0.271125 0.949099,
+                          0.173303 -0.23585 0.956212,
+                          0.247035 -0.323202 0.913518,
+                          0.0335298 -0.23329 0.971829,
+                          0.255018 -0.307073 0.916882,
+                          0.0165788 -0.196141 0.980435,
+                          0.0335298 -0.23329 0.971829,
+                          0.160322 -0.271125 0.949099,
+                          0.255018 -0.307073 0.916882,
+                          -0.249847 -0.0553123 0.966704,
+                          0.0165788 -0.196141 0.980435,
+                          -0.778902 0.221473 0.586738,
+                          -0.249847 -0.0553123 0.966704,
+                          0.0335298 -0.23329 0.971829,
+                          0.0165788 -0.196141 0.980435,
+                          -0.249847 -0.0553123 0.966704,
+                          -0.778902 0.221473 0.586738,
+                          -0.353089 0.0455973 0.934478,
+                          0.185324 -0.23071 0.955211,
+                          0.160059 -0.260343 0.952157,
+                          0.195093 -0.231253 0.953132,
+                          0.185324 -0.23071 0.955211,
+                          0.143734 -0.299298 0.943272,
+                          0.160059 -0.260343 0.952157,
+                          0.189222 -0.246935 0.950378,
+                          0.195093 -0.231253 0.953132,
+                          0.164277 -0.272721 0.947964,
+                          0.189222 -0.246935 0.950378,
+                          0.185324 -0.23071 0.955211,
+                          0.195093 -0.231253 0.953132,
+                          0.15117 -0.283023 0.947125,
+                          0.164277 -0.272721 0.947964,
+                          0.147351 -0.284842 0.947181,
+                          0.15117 -0.283023 0.947125,
+                          0.189222 -0.246935 0.950378,
+                          0.164277 -0.272721 0.947964,
+                          -0.435379 0.840438 0.322659,
+                          -0.533536 0.784067 0.317141,
+                          -0.505425 0.757504 0.413199,
+                          0.0867049 -0.317953 0.944133,
+                          0.147351 -0.284842 0.947181,
+                          0.077117 -0.320736 0.944024,
+                          0.0867049 -0.317953 0.944133,
+                          0.15117 -0.283023 0.947125,
+                          0.147351 -0.284842 0.947181,
+                          -0.365389 0.873722 0.321093,
+                          -0.435379 0.840438 0.322659,
+                          -0.505425 0.757504 0.413199,
+                          0.0704755 -0.318433 0.945322,
+                          0.077117 -0.320736 0.944024,
+                          0.0663166 -0.316575 0.946247,
+                          0.0704755 -0.318433 0.945322,
+                          0.0867049 -0.317953 0.944133,
+                          0.077117 -0.320736 0.944024,
+                          0.0624972 -0.309185 0.948946,
+                          0.0704755 -0.318433 0.945322,
+                          0.0663166 -0.316575 0.946247,
+                          -0.83295 -0.439043 0.336803,
+                          -0.582054 -0.731389 0.355364,
+                          -0.592374 -0.738306 0.322485,
+                          -0.741656 0.655585 0.141967,
+                          -0.748032 0.649371 0.13699,
+                          -0.745544 0.652024 0.137942,
+                          -0.818964 -0.443708 0.363897,
+                          -0.83295 -0.439043 0.336803,
+                          -0.592374 -0.738306 0.322485,
+                          -0.684814 -0.65629 0.316723,
+                          -0.818964 -0.443708 0.363897,
+                          -0.592374 -0.738306 0.322485,
+                          -0.854827 -0.418864 0.306306,
+                          -0.593696 -0.716981 0.365325,
+                          -0.582054 -0.731389 0.355364,
+                          -0.741656 0.655585 0.141967,
+                          -0.745544 0.652024 0.137942,
+                          -0.739818 0.663394 0.112153,
+                          -0.83295 -0.439043 0.336803,
+                          -0.854827 -0.418864 0.306306,
+                          -0.582054 -0.731389 0.355364,
+                          -0.88221 -0.392213 0.260526,
+                          -0.624432 -0.704783 0.336698,
+                          -0.593696 -0.716981 0.365325,
+                          -0.854827 -0.418864 0.306306,
+                          -0.88221 -0.392213 0.260526,
+                          -0.593696 -0.716981 0.365325,
+                          -0.907701 -0.36668 0.20402,
+                          -0.655587 -0.697843 0.28848,
+                          -0.624432 -0.704783 0.336698,
+                          -0.88221 -0.392213 0.260526,
+                          -0.907701 -0.36668 0.20402,
+                          -0.624432 -0.704783 0.336698,
+                          -0.926138 -0.345159 0.152099,
+                          -0.679864 -0.692038 0.242627,
+                          -0.655587 -0.697843 0.28848,
+                          -0.907701 -0.36668 0.20402,
+                          -0.926138 -0.345159 0.152099,
+                          -0.655587 -0.697843 0.28848,
+                          -0.926138 -0.345159 0.152099,
+                          -0.698284 -0.686698 0.202101,
+                          -0.679864 -0.692038 0.242627,
+                          -0.926138 -0.345159 0.152099,
+                          -0.738756 -0.645935 0.192372,
+                          -0.698284 -0.686698 0.202101,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.926138 -0.345159 0.152099,
+                          -0.776878 -0.602858 0.18172,
+                          -0.738756 -0.645935 0.192372,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.939001 -0.326619 0.107691,
+                          -0.823475 -0.550475 0.137354,
+                          -0.776878 -0.602858 0.18172,
+                          -0.926138 -0.345159 0.152099,
+                          -0.939001 -0.326619 0.107691,
+                          -0.776878 -0.602858 0.18172,
+                          -0.948379 -0.309489 0.0692348,
+                          -0.889575 -0.448753 0.0853018,
+                          -0.823475 -0.550475 0.137354,
+                          -0.939001 -0.326619 0.107691,
+                          -0.948379 -0.309489 0.0692348,
+                          -0.823475 -0.550475 0.137354,
+                          -0.955332 -0.293321 0.0361072,
+                          -0.948307 -0.314734 0.0406912,
+                          -0.889575 -0.448753 0.0853018,
+                          -0.948379 -0.309489 0.0692348,
+                          -0.955332 -0.293321 0.0361072,
+                          -0.889575 -0.448753 0.0853018,
+                          -0.999966 -0.00666107 0.00478963,
+                          -0.955332 -0.293321 0.0361072,
+                          -0.948379 -0.309489 0.0692348,
+                          -0.999878 0.000638396 -0.0155946,
+                          -0.999718 -0.0160977 -0.017437,
+                          -0.955332 -0.293321 0.0361072,
+                          -0.999966 -0.00666107 0.00478963,
+                          -0.999878 0.000638396 -0.0155946,
+                          -0.955332 -0.293321 0.0361072,
+                          -0.999465 -0.0135088 0.029795,
+                          -0.948379 -0.309489 0.0692348,
+                          -0.939001 -0.326619 0.107691,
+                          -0.999465 -0.0135088 0.029795,
+                          -0.999966 -0.00666107 0.00478963,
+                          -0.948379 -0.309489 0.0692348,
+                          -0.997961 -0.0210505 0.0602533,
+                          -0.939001 -0.326619 0.107691,
+                          -0.926138 -0.345159 0.152099,
+                          -0.997961 -0.0210505 0.0602533,
+                          -0.999465 -0.0135088 0.029795,
+                          -0.939001 -0.326619 0.107691,
+                          -0.994987 -0.0311637 0.0950298,
+                          -0.926138 -0.345159 0.152099,
+                          -0.907701 -0.36668 0.20402,
+                          -0.994987 -0.0311637 0.0950298,
+                          -0.997961 -0.0210505 0.0602533,
+                          -0.926138 -0.345159 0.152099,
+                          -0.989718 -0.0472321 0.135006,
+                          -0.907701 -0.36668 0.20402,
+                          -0.88221 -0.392213 0.260526,
+                          -0.989718 -0.0472321 0.135006,
+                          -0.994987 -0.0311637 0.0950298,
+                          -0.907701 -0.36668 0.20402,
+                          -0.98087 -0.0717658 0.180953,
+                          -0.88221 -0.392213 0.260526,
+                          -0.854827 -0.418864 0.306306,
+                          -0.98087 -0.0717658 0.180953,
+                          -0.989718 -0.0472321 0.135006,
+                          -0.88221 -0.392213 0.260526,
+                          -0.966586 -0.103606 0.234474,
+                          -0.854827 -0.418864 0.306306,
+                          -0.83295 -0.439043 0.336803,
+                          -0.966586 -0.103606 0.234474,
+                          -0.98087 -0.0717658 0.180953,
+                          -0.854827 -0.418864 0.306306,
+                          -0.942738 -0.134963 0.305009,
+                          -0.83295 -0.439043 0.336803,
+                          -0.818964 -0.443708 0.363897,
+                          -0.942738 -0.134963 0.305009,
+                          -0.966586 -0.103606 0.234474,
+                          -0.83295 -0.439043 0.336803,
+                          -0.684814 -0.65629 0.316723,
+                          -0.81044 -0.423962 0.404282,
+                          -0.818964 -0.443708 0.363897,
+                          -0.903023 -0.158325 0.399354,
+                          -0.818964 -0.443708 0.363897,
+                          -0.81044 -0.423962 0.404282,
+                          -0.903023 -0.158325 0.399354,
+                          -0.942738 -0.134963 0.305009,
+                          -0.818964 -0.443708 0.363897,
+                          -0.754302 -0.54348 0.368317,
+                          -0.793387 -0.372827 0.481183,
+                          -0.81044 -0.423962 0.404282,
+                          -0.837541 -0.167833 0.519959,
+                          -0.81044 -0.423962 0.404282,
+                          -0.793387 -0.372827 0.481183,
+                          -0.684814 -0.65629 0.316723,
+                          -0.754302 -0.54348 0.368317,
+                          -0.81044 -0.423962 0.404282,
+                          -0.837541 -0.167833 0.519959,
+                          -0.903023 -0.158325 0.399354,
+                          -0.81044 -0.423962 0.404282,
+                          -0.781206 -0.398061 0.4809,
+                          -0.748685 -0.28114 0.600359,
+                          -0.793387 -0.372827 0.481183,
+                          -0.727389 -0.164286 0.66627,
+                          -0.793387 -0.372827 0.481183,
+                          -0.748685 -0.28114 0.600359,
+                          -0.754302 -0.54348 0.368317,
+                          -0.781206 -0.398061 0.4809,
+                          -0.793387 -0.372827 0.481183,
+                          -0.727389 -0.164286 0.66627,
+                          -0.837541 -0.167833 0.519959,
+                          -0.793387 -0.372827 0.481183,
+                          -0.555027 -0.148919 0.818394,
+                          -0.748685 -0.28114 0.600359,
+                          -0.714049 -0.228999 0.661584,
+                          -0.555027 -0.148919 0.818394,
+                          -0.727389 -0.164286 0.66627,
+                          -0.748685 -0.28114 0.600359,
+                          -0.373601 -0.113321 0.920641,
+                          -0.555027 -0.148919 0.818394,
+                          -0.714049 -0.228999 0.661584,
+                          -0.565591 -0.072541 0.821489,
+                          -0.373601 -0.113321 0.920641,
+                          -0.714049 -0.228999 0.661584,
+                          -0.999181 0.0404431 0.00143205,
+                          -0.999878 0.000638396 -0.0155946,
+                          -0.999966 -0.00666107 0.00478963,
+                          -0.998961 0.0415846 0.0186559,
+                          -0.999966 -0.00666107 0.00478963,
+                          -0.999465 -0.0135088 0.029795,
+                          -0.998961 0.0415846 0.0186559,
+                          -0.999181 0.0404431 0.00143205,
+                          -0.999966 -0.00666107 0.00478963,
+                          -0.99816 0.039317 0.0461628,
+                          -0.999465 -0.0135088 0.029795,
+                          -0.997961 -0.0210505 0.0602533,
+                          -0.998416 0.0400177 0.0395406,
+                          -0.998961 0.0415846 0.0186559,
+                          -0.999465 -0.0135088 0.029795,
+                          -0.99816 0.039317 0.0461628,
+                          -0.998416 0.0400177 0.0395406,
+                          -0.999465 -0.0135088 0.029795,
+                          -0.996661 0.0341975 0.0741404,
+                          -0.997961 -0.0210505 0.0602533,
+                          -0.994987 -0.0311637 0.0950298,
+                          -0.99785 0.0385485 0.0529995,
+                          -0.99816 0.039317 0.0461628,
+                          -0.997961 -0.0210505 0.0602533,
+                          -0.996661 0.0341975 0.0741404,
+                          -0.99785 0.0385485 0.0529995,
+                          -0.997961 -0.0210505 0.0602533,
+                          -0.99585 0.0264665 0.0870774,
+                          -0.996661 0.0341975 0.0741404,
+                          -0.994987 -0.0311637 0.0950298,
+                          -0.530617 0.0402324 0.846657,
+                          -0.421691 -0.0157304 0.906603,
+                          -0.373601 -0.113321 0.920641,
+                          -0.565591 -0.072541 0.821489,
+                          -0.530617 0.0402324 0.846657,
+                          -0.373601 -0.113321 0.920641,
+                          -0.709086 0.153722 0.688161,
+                          -0.728599 0.159484 0.666115,
+                          -0.421691 -0.0157304 0.906603,
+                          -0.530617 0.0402324 0.846657,
+                          -0.709086 0.153722 0.688161,
+                          -0.421691 -0.0157304 0.906603,
+                          0 -0.974562 0.224117,
+                          -8.4969e-17 -0.931357 0.364107,
+                          3.23247e-17 -0.988942 0.148301,
+                          -0.0444116 -0.998184 0.0406868,
+                          -0.0440766 -0.997324 0.0583287,
+                          -0.0448891 -0.998853 0.0166878,
+                          -1.70708e-17 -0.980776 0.195135,
+                          3.23247e-17 -0.988942 0.148301,
+                          -2.02529e-18 -0.99269 0.120689,
+                          -1.70708e-17 -0.980776 0.195135,
+                          0 -0.974562 0.224117,
+                          3.23247e-17 -0.988942 0.148301,
+                          -0.0453473 -0.998971 -0.000573124,
+                          -0.0448891 -0.998853 0.0166878,
+                          -0.0459393 -0.998703 -0.0219417,
+                          -0.044795 -0.998737 0.0227654,
+                          -0.0444116 -0.998184 0.0406868,
+                          -0.0448891 -0.998853 0.0166878,
+                          -0.0453473 -0.998971 -0.000573124,
+                          -0.044795 -0.998737 0.0227654,
+                          -0.0448891 -0.998853 0.0166878,
+                          -0.045956 -0.998697 -0.0222117,
+                          -0.0459286 -0.998708 -0.0217398,
+                          0.0138175 -0.811819 0.583746,
+                          -0.0453473 -0.998971 -0.000573124,
+                          -0.0459393 -0.998703 -0.0219417,
+                          -0.0459587 -0.998695 -0.0222612,
+                          0.0220752 -0.775866 0.630512,
+                          0.0138175 -0.811819 0.583746,
+                          0.0506791 -0.693135 0.719024,
+                          -0.045956 -0.998697 -0.0222117,
+                          0.0138175 -0.811819 0.583746,
+                          -0.0459873 -0.998683 -0.0227469,
+                          0.0220752 -0.775866 0.630512,
+                          -0.0459873 -0.998683 -0.0227469,
+                          0.0138175 -0.811819 0.583746,
+                          0.058581 -0.68417 0.726966,
+                          0.0220752 -0.775866 0.630512,
+                          0.0506791 -0.693135 0.719024,
+                          -0.0453473 -0.998971 -0.000573124,
+                          -0.0459587 -0.998695 -0.0222612,
+                          -0.0459787 -0.998687 -0.0226026,
+                          0.70684 -0.68542 -0.174864,
+                          0.121377 -0.988765 -0.0872474,
+                          -0.057073 -0.998123 -0.0222199,
+                          0.738706 -0.599682 0.307725,
+                          -0.057073 -0.998123 -0.0222199,
+                          0.0113395 -0.775722 0.630973,
+                          0.738706 -0.599682 0.307725,
+                          0.70684 -0.68542 -0.174864,
+                          -0.057073 -0.998123 -0.0222199,
+                          -1.70708e-17 -0.980776 0.195135,
+                          -2.02529e-18 -0.99269 0.120689,
+                          0 -0.99573 0.0923152,
+                          0.70684 -0.68542 -0.174864,
+                          0.276332 -0.951455 -0.135552,
+                          0.121377 -0.988765 -0.0872474,
+                          0.738706 -0.599682 0.307725,
+                          0.0113395 -0.775722 0.630973,
+                          0.04761 -0.684244 0.727698,
+                          0.761193 -0.485493 0.429978,
+                          0.04761 -0.684244 0.727698,
+                          0.0613232 -0.67159 0.738381,
+                          0.761193 -0.485493 0.429978,
+                          0.738706 -0.599682 0.307725,
+                          0.04761 -0.684244 0.727698,
+                          0.762557 -0.461113 0.453742,
+                          0.0613232 -0.67159 0.738381,
+                          0.0715843 -0.652248 0.754618,
+                          0.762557 -0.461113 0.453742,
+                          0.761193 -0.485493 0.429978,
+                          0.0613232 -0.67159 0.738381,
+                          0.762557 -0.461113 0.453742,
+                          0.0715843 -0.652248 0.754618,
+                          0.0828853 -0.598513 0.796813,
+                          0.755683 -0.424929 0.498376,
+                          0.0828853 -0.598513 0.796813,
+                          0.100294 -0.467051 0.878524,
+                          0.755683 -0.424929 0.498376,
+                          0.762557 -0.461113 0.453742,
+                          0.0828853 -0.598513 0.796813,
+                          0.754112 -0.377624 0.537322,
+                          0.100294 -0.467051 0.878524,
+                          0.133987 -0.29635 0.945634,
+                          0.754112 -0.377624 0.537322,
+                          0.755683 -0.424929 0.498376,
+                          0.100294 -0.467051 0.878524,
+                          0.736148 -0.431272 0.521622,
+                          0.133987 -0.29635 0.945634,
+                          0.177436 -0.226651 0.957677,
+                          0.736148 -0.431272 0.521622,
+                          0.754112 -0.377624 0.537322,
+                          0.133987 -0.29635 0.945634,
+                          0.631835 -0.614309 0.472662,
+                          0.177436 -0.226651 0.957677,
+                          0.184314 -0.23925 0.953304,
+                          0.631835 -0.614309 0.472662,
+                          0.736148 -0.431272 0.521622,
+                          0.177436 -0.226651 0.957677,
+                          0.631835 -0.614309 0.472662,
+                          0.184314 -0.23925 0.953304,
+                          0.140284 -0.279941 0.949712,
+                          0.428541 -0.787286 0.44332,
+                          0.140284 -0.279941 0.949712,
+                          0.0897693 -0.305075 0.948088,
+                          0.428541 -0.787286 0.44332,
+                          0.631835 -0.614309 0.472662,
+                          0.140284 -0.279941 0.949712,
+                          0.428541 -0.787286 0.44332,
+                          0.0897693 -0.305075 0.948088,
+                          0.0651692 -0.309744 0.948584,
+                          0.300401 -0.846631 0.43929,
+                          0.0651692 -0.309744 0.948584,
+                          0.0579625 -0.302014 0.95154,
+                          0.300401 -0.846631 0.43929,
+                          0.428541 -0.787286 0.44332,
+                          0.0651692 -0.309744 0.948584,
+                          0.221671 -0.86175 0.456343,
+                          0.0579625 -0.302014 0.95154,
+                          0.0432005 -0.284913 0.957579,
+                          0.221671 -0.86175 0.456343,
+                          0.300401 -0.846631 0.43929,
+                          0.0579625 -0.302014 0.95154,
+                          0.221671 -0.86175 0.456343,
+                          0.0432005 -0.284913 0.957579,
+                          0.0160037 -0.258707 0.965823,
+                          -0.0271695 -0.243695 0.969471,
+                          -0.026434 -0.24395 0.969428,
+                          0.0180077 -0.268888 0.963003,
+                          0.132202 -0.865447 0.483244,
+                          0.0160037 -0.258707 0.965823,
+                          -0.0230837 -0.234236 0.971906,
+                          0.132202 -0.865447 0.483244,
+                          0.221671 -0.86175 0.456343,
+                          0.0160037 -0.258707 0.965823,
+                          -0.0286089 -0.28318 0.95864,
+                          0.0264344 -0.24395 0.969428,
+                          0.0271695 -0.243695 0.969471,
+                          -0.00900156 -0.26102 0.965291,
+                          0.0264344 -0.24395 0.969428,
+                          -0.0286089 -0.28318 0.95864,
+                          0.00466106 -0.864682 0.502298,
+                          0.0230643 -0.23423 0.971908,
+                          -0.0068557 -0.251852 0.967741,
+                          0.132202 -0.865447 0.483244,
+                          -0.0230837 -0.234236 0.971906,
+                          -0.00463999 -0.864686 0.502291,
+                          0.386522 0.907492 -0.164499,
+                          0.182963 0.975113 -0.125216,
+                          0.390184 0.904984 -0.169588,
+                          0.187719 0.974345 -0.124148,
+                          0.182963 0.975113 -0.125216,
+                          0.386522 0.907492 -0.164499,
+                          -0.295638 0.0287268 -0.954868,
+                          -0.255998 -0.0401468 -0.965843,
+                          -0.166394 -0.00047035 -0.986059,
+                          0.553157 0.817369 -0.161014,
+                          0.390184 0.904984 -0.169588,
+                          0.638497 0.749398 -0.175284,
+                          0.553157 0.817369 -0.161014,
+                          0.386522 0.907492 -0.164499,
+                          0.390184 0.904984 -0.169588,
+                          0.109535 0.261922 -0.958853,
+                          -0.166394 -0.00047035 -0.986059,
+                          -0.0350142 0.090381 -0.995292,
+                          -0.251922 0.0551414 -0.966175,
+                          -0.295638 0.0287268 -0.954868,
+                          -0.166394 -0.00047035 -0.986059,
+                          0.109535 0.261922 -0.958853,
+                          -0.251922 0.0551414 -0.966175,
+                          -0.166394 -0.00047035 -0.986059,
+                          0.175699 0.239845 -0.95478,
+                          -0.0350142 0.090381 -0.995292,
+                          -0.0233953 0.0607173 -0.997881,
+                          0.175699 0.239845 -0.95478,
+                          0.109535 0.261922 -0.958853,
+                          -0.0350142 0.090381 -0.995292,
+                          0.0677503 0.0932997 -0.99333,
+                          -0.0233953 0.0607173 -0.997881,
+                          -0.183505 -0.270914 -0.944951,
+                          0.0677503 0.0932997 -0.99333,
+                          0.175699 0.239845 -0.95478,
+                          -0.0233953 0.0607173 -0.997881,
+                          -0.139792 -0.172491 -0.975041,
+                          -0.183505 -0.270914 -0.944951,
+                          -0.294609 -0.634616 -0.714471,
+                          -0.139792 -0.172491 -0.975041,
+                          0.0677503 0.0932997 -0.99333,
+                          -0.183505 -0.270914 -0.944951,
+                          -0.343059 -0.472402 -0.811879,
+                          -0.294609 -0.634616 -0.714471,
+                          -0.294607 -0.797072 -0.527147,
+                          -0.343059 -0.472402 -0.811879,
+                          -0.139792 -0.172491 -0.975041,
+                          -0.294609 -0.634616 -0.714471,
+                          -0.440328 -0.642799 -0.626834,
+                          -0.294607 -0.797072 -0.527147,
+                          -0.268609 -0.871695 -0.409875,
+                          -0.440328 -0.642799 -0.626834,
+                          -0.343059 -0.472402 -0.811879,
+                          -0.294607 -0.797072 -0.527147,
+                          -0.147504 -0.947839 -0.282568,
+                          -0.245549 -0.916148 -0.316825,
+                          -0.268609 -0.871695 -0.409875,
+                          -0.480766 -0.723169 -0.495874,
+                          -0.268609 -0.871695 -0.409875,
+                          -0.245549 -0.916148 -0.316825,
+                          -0.480766 -0.723169 -0.495874,
+                          -0.440328 -0.642799 -0.626834,
+                          -0.268609 -0.871695 -0.409875,
+                          -0.132208 -0.865437 0.483259,
+                          -0.245601 -0.912673 -0.326664,
+                          -0.143415 -0.945587 -0.292058,
+                          -0.480766 -0.723169 -0.495874,
+                          -0.245549 -0.916148 -0.316825,
+                          -0.251305 -0.913831 -0.318997,
+                          -0.221746 -0.861748 0.456311,
+                          -0.25023 -0.910756 -0.328495,
+                          -0.245601 -0.912673 -0.326664,
+                          -0.132208 -0.865437 0.483259,
+                          -0.221746 -0.861748 0.456311,
+                          -0.245601 -0.912673 -0.326664,
+                          0.00466106 -0.864682 0.502298,
+                          -0.132208 -0.865437 0.483259,
+                          -0.143415 -0.945587 -0.292058,
+                          -0.319948 -0.88392 -0.341056,
+                          -0.480766 -0.723169 -0.495874,
+                          -0.251305 -0.913831 -0.318997,
+                          -0.221746 -0.861748 0.456311,
+                          -0.3212 -0.879755 -0.350516,
+                          -0.25023 -0.910756 -0.328495,
+                          0.769735 0.624657 -0.131572,
+                          0.638497 0.749398 -0.175284,
+                          0.785987 0.600891 -0.145446,
+                          0.553157 0.817369 -0.161014,
+                          0.638497 0.749398 -0.175284,
+                          0.769735 0.624657 -0.131572,
+                          0.164263 0.261851 -0.951027,
+                          -0.251922 0.0551414 -0.966175,
+                          0.109535 0.261922 -0.958853,
+                          -0.802097 -0.23478 -0.549108,
+                          -0.315878 -0.0205262 -0.948578,
+                          -0.251922 0.0551414 -0.966175,
+                          0.769735 0.624657 -0.131572,
+                          0.785987 0.600891 -0.145446,
+                          0.848602 0.468297 -0.246116,
+                          0.164263 0.261851 -0.951027,
+                          -0.802097 -0.23478 -0.549108,
+                          -0.251922 0.0551414 -0.966175,
+                          0.259114 0.324392 -0.909742,
+                          0.109535 0.261922 -0.958853,
+                          0.175699 0.239845 -0.95478,
+                          0.259114 0.324392 -0.909742,
+                          0.164263 0.261851 -0.951027,
+                          0.109535 0.261922 -0.958853,
+                          0.0904416 0.280725 -0.955518,
+                          0.175699 0.239845 -0.95478,
+                          0.0677503 0.0932997 -0.99333,
+                          0.0904416 0.280725 -0.955518,
+                          0.259114 0.324392 -0.909742,
+                          0.175699 0.239845 -0.95478,
+                          -0.23535 0.158201 -0.958949,
+                          0.0677503 0.0932997 -0.99333,
+                          -0.139792 -0.172491 -0.975041,
+                          -0.23535 0.158201 -0.958949,
+                          0.0904416 0.280725 -0.955518,
+                          0.0677503 0.0932997 -0.99333,
+                          -0.542992 0.0153098 -0.839598,
+                          -0.139792 -0.172491 -0.975041,
+                          -0.343059 -0.472402 -0.811879,
+                          -0.542992 0.0153098 -0.839598,
+                          -0.23535 0.158201 -0.958949,
+                          -0.139792 -0.172491 -0.975041,
+                          -0.737613 -0.0976493 -0.668126,
+                          -0.343059 -0.472402 -0.811879,
+                          -0.440328 -0.642799 -0.626834,
+                          -0.737613 -0.0976493 -0.668126,
+                          -0.542992 0.0153098 -0.839598,
+                          -0.343059 -0.472402 -0.811879,
+                          -0.830357 -0.151737 -0.536175,
+                          -0.440328 -0.642799 -0.626834,
+                          -0.480766 -0.723169 -0.495874,
+                          -0.830357 -0.151737 -0.536175,
+                          -0.737613 -0.0976493 -0.668126,
+                          -0.440328 -0.642799 -0.626834,
+                          -0.409966 -0.84063 -0.353935,
+                          -0.519359 -0.777423 -0.354794,
+                          -0.480766 -0.723169 -0.495874,
+                          -0.902211 -0.176577 -0.393493,
+                          -0.480766 -0.723169 -0.495874,
+                          -0.519359 -0.777423 -0.354794,
+                          -0.319948 -0.88392 -0.341056,
+                          -0.409966 -0.84063 -0.353935,
+                          -0.480766 -0.723169 -0.495874,
+                          -0.902211 -0.176577 -0.393493,
+                          -0.830357 -0.151737 -0.536175,
+                          -0.480766 -0.723169 -0.495874,
+                          -0.428616 -0.787288 0.443245,
+                          -0.518282 -0.771906 -0.368164,
+                          -0.406865 -0.838031 -0.363544,
+                          -0.902211 -0.176577 -0.393493,
+                          -0.519359 -0.777423 -0.354794,
+                          -0.539147 -0.76428 -0.353831,
+                          -0.631698 -0.614493 0.472605,
+                          -0.537498 -0.758757 -0.367946,
+                          -0.518282 -0.771906 -0.368164,
+                          -0.428616 -0.787288 0.443245,
+                          -0.631698 -0.614493 0.472605,
+                          -0.518282 -0.771906 -0.368164,
+                          -0.300271 -0.846691 0.439263,
+                          -0.406865 -0.838031 -0.363544,
+                          -0.3212 -0.879755 -0.350516,
+                          -0.300271 -0.846691 0.439263,
+                          -0.428616 -0.787288 0.443245,
+                          -0.406865 -0.838031 -0.363544,
+                          -0.221746 -0.861748 0.456311,
+                          -0.300271 -0.846691 0.439263,
+                          -0.3212 -0.879755 -0.350516,
+                          -0.755786 -0.567931 -0.325946,
+                          -0.902211 -0.176577 -0.393493,
+                          -0.539147 -0.76428 -0.353831,
+                          -0.631698 -0.614493 0.472605,
+                          -0.753217 -0.565244 -0.336398,
+                          -0.537498 -0.758757 -0.367946,
+                          0.924945 0.186941 -0.330952,
+                          0.848602 0.468297 -0.246116,
+                          0.513829 0.229627 -0.82659,
+                          0.769735 0.624657 -0.131572,
+                          0.848602 0.468297 -0.246116,
+                          0.924945 0.186941 -0.330952,
+                          -0.963622 -0.25104 -0.0917151,
+                          -0.802097 -0.23478 -0.549108,
+                          0.164263 0.261851 -0.951027,
+                          0.618402 -0.215215 -0.755819,
+                          0.513829 0.229627 -0.82659,
+                          0.0622414 0.0416609 -0.997191,
+                          0.924945 0.186941 -0.330952,
+                          0.513829 0.229627 -0.82659,
+                          0.618402 -0.215215 -0.755819,
+                          -0.243879 0.331169 -0.91151,
+                          0.164263 0.261851 -0.951027,
+                          0.259114 0.324392 -0.909742,
+                          -0.928505 -0.170292 -0.329969,
+                          -0.963622 -0.25104 -0.0917151,
+                          0.164263 0.261851 -0.951027,
+                          -0.243879 0.331169 -0.91151,
+                          -0.928505 -0.170292 -0.329969,
+                          0.164263 0.261851 -0.951027,
+                          -0.133434 0.490401 -0.861221,
+                          0.259114 0.324392 -0.909742,
+                          0.0904416 0.280725 -0.955518,
+                          -0.133434 0.490401 -0.861221,
+                          -0.243879 0.331169 -0.91151,
+                          0.259114 0.324392 -0.909742,
+                          -0.414582 0.445648 -0.793422,
+                          0.0904416 0.280725 -0.955518,
+                          -0.23535 0.158201 -0.958949,
+                          -0.414582 0.445648 -0.793422,
+                          -0.133434 0.490401 -0.861221,
+                          0.0904416 0.280725 -0.955518,
+                          -0.678136 0.325168 -0.659089,
+                          -0.23535 0.158201 -0.958949,
+                          -0.542992 0.0153098 -0.839598,
+                          -0.678136 0.325168 -0.659089,
+                          -0.414582 0.445648 -0.793422,
+                          -0.23535 0.158201 -0.958949,
+                          -0.852915 0.203397 -0.480797,
+                          -0.542992 0.0153098 -0.839598,
+                          -0.737613 -0.0976493 -0.668126,
+                          -0.852915 0.203397 -0.480797,
+                          -0.678136 0.325168 -0.659089,
+                          -0.542992 0.0153098 -0.839598,
+                          -0.953434 0.100507 -0.284361,
+                          -0.737613 -0.0976493 -0.668126,
+                          -0.830357 -0.151737 -0.536175,
+                          -0.953434 0.100507 -0.284361,
+                          -0.852915 0.203397 -0.480797,
+                          -0.737613 -0.0976493 -0.668126,
+                          -0.953434 0.100507 -0.284361,
+                          -0.830357 -0.151737 -0.536175,
+                          -0.902211 -0.176577 -0.393493,
+                          -0.915522 -0.313882 -0.251589,
+                          -0.961279 -0.189715 -0.199876,
+                          -0.902211 -0.176577 -0.393493,
+                          -0.989161 0.0306337 -0.143601,
+                          -0.902211 -0.176577 -0.393493,
+                          -0.961279 -0.189715 -0.199876,
+                          -0.755786 -0.567931 -0.325946,
+                          -0.915522 -0.313882 -0.251589,
+                          -0.902211 -0.176577 -0.393493,
+                          -0.989161 0.0306337 -0.143601,
+                          -0.953434 0.100507 -0.284361,
+                          -0.902211 -0.176577 -0.393493,
+                          -0.754167 -0.377587 0.537271,
+                          -0.962037 -0.176293 -0.208339,
+                          -0.912475 -0.311869 -0.264816,
+                          -0.989161 0.0306337 -0.143601,
+                          -0.961279 -0.189715 -0.199876,
+                          -0.987954 -0.0747507 -0.135498,
+                          -0.754167 -0.377587 0.537271,
+                          -0.986778 -0.0698257 -0.146268,
+                          -0.962037 -0.176293 -0.208339,
+                          -0.736183 -0.431222 0.521615,
+                          -0.912475 -0.311869 -0.264816,
+                          -0.753217 -0.565244 -0.336398,
+                          -0.736183 -0.431222 0.521615,
+                          -0.754167 -0.377587 0.537271,
+                          -0.912475 -0.311869 -0.264816,
+                          -0.631698 -0.614493 0.472605,
+                          -0.736183 -0.431222 0.521615,
+                          -0.753217 -0.565244 -0.336398,
+                          -0.994399 -0.0318524 -0.100782,
+                          -0.989161 0.0306337 -0.143601,
+                          -0.987954 -0.0747507 -0.135498,
+                          -0.755709 -0.424939 0.498329,
+                          -0.993813 -0.0261418 -0.107947,
+                          -0.986778 -0.0698257 -0.146268,
+                          -0.754167 -0.377587 0.537271,
+                          -0.755709 -0.424939 0.498329,
+                          -0.986778 -0.0698257 -0.146268,
+                          1.09727e-17 0.354975 -0.934876,
+                          1.10588e-17 0.350932 -0.936401,
+                          0 0.405863 -0.913934,
+                          0.0844325 -0.0109864 -0.996369,
+                          0.618402 -0.215215 -0.755819,
+                          0.0622414 0.0416609 -0.997191,
+                          -0.77728 -0.118769 -0.617843,
+                          -0.928505 -0.170292 -0.329969,
+                          -0.243879 0.331169 -0.91151,
+                          -1.87926e-17 0.415586 -0.909554,
+                          0 0.405863 -0.913934,
+                          0 0.473745 -0.880662,
+                          1.61274e-17 0.359513 -0.93314,
+                          0 0.405863 -0.913934,
+                          -1.87926e-17 0.415586 -0.909554,
+                          1.09727e-17 0.354975 -0.934876,
+                          0 0.405863 -0.913934,
+                          1.61274e-17 0.359513 -0.93314,
+                          -0.438087 0.00214235 -0.89893,
+                          -0.243879 0.331169 -0.91151,
+                          -0.133434 0.490401 -0.861221,
+                          -0.438087 0.00214235 -0.89893,
+                          -0.77728 -0.118769 -0.617843,
+                          -0.243879 0.331169 -0.91151,
+                          -0.410724 0.128524 -0.902656,
+                          -0.133434 0.490401 -0.861221,
+                          -0.414582 0.445648 -0.793422,
+                          -0.410724 0.128524 -0.902656,
+                          -0.438087 0.00214235 -0.89893,
+                          -0.133434 0.490401 -0.861221,
+                          -0.682416 0.160118 -0.713211,
+                          -0.414582 0.445648 -0.793422,
+                          -0.678136 0.325168 -0.659089,
+                          -0.682416 0.160118 -0.713211,
+                          -0.410724 0.128524 -0.902656,
+                          -0.414582 0.445648 -0.793422,
+                          -0.844968 0.169741 -0.507166,
+                          -0.678136 0.325168 -0.659089,
+                          -0.852915 0.203397 -0.480797,
+                          -0.844968 0.169741 -0.507166,
+                          -0.682416 0.160118 -0.713211,
+                          -0.678136 0.325168 -0.659089,
+                          -0.925815 0.151449 -0.346308,
+                          -0.852915 0.203397 -0.480797,
+                          -0.953434 0.100507 -0.284361,
+                          -0.925815 0.151449 -0.346308,
+                          -0.844968 0.169741 -0.507166,
+                          -0.852915 0.203397 -0.480797,
+                          -0.966152 0.108226 -0.234175,
+                          -0.953434 0.100507 -0.284361,
+                          -0.989161 0.0306337 -0.143601,
+                          -0.966152 0.108226 -0.234175,
+                          -0.925815 0.151449 -0.346308,
+                          -0.953434 0.100507 -0.284361,
+                          -0.995918 -0.00930479 -0.0897769,
+                          -0.995797 -0.0114627 -0.0908735,
+                          -0.989161 0.0306337 -0.143601,
+                          -0.994107 0.0343605 -0.102815,
+                          -0.989161 0.0306337 -0.143601,
+                          -0.995797 -0.0114627 -0.0908735,
+                          -0.996176 -0.00917039 -0.0868824,
+                          -0.995918 -0.00930479 -0.0897769,
+                          -0.989161 0.0306337 -0.143601,
+                          -0.994399 -0.0318524 -0.100782,
+                          -0.996176 -0.00917039 -0.0868824,
+                          -0.989161 0.0306337 -0.143601,
+                          -0.98478 0.063397 -0.161828,
+                          -0.966152 0.108226 -0.234175,
+                          -0.989161 0.0306337 -0.143601,
+                          -0.994107 0.0343605 -0.102815,
+                          -0.98478 0.063397 -0.161828,
+                          -0.989161 0.0306337 -0.143601,
+                          -0.761237 -0.485463 0.429935,
+                          -0.994985 -0.00394016 -0.0999509,
+                          -0.99517 -0.00280186 -0.0981289,
+                          -0.994107 0.0343605 -0.102815,
+                          -0.995797 -0.0114627 -0.0908735,
+                          -0.995275 -0.0238072 -0.0941335,
+                          -0.761237 -0.485463 0.429935,
+                          -0.994763 -0.0165733 -0.100855,
+                          -0.994985 -0.00394016 -0.0999509,
+                          -0.762599 -0.461076 0.453709,
+                          -0.99517 -0.00280186 -0.0981289,
+                          -0.995711 -0.0042473 -0.0924156,
+                          -0.762599 -0.461076 0.453709,
+                          -0.761237 -0.485463 0.429935,
+                          -0.99517 -0.00280186 -0.0981289,
+                          -0.755709 -0.424939 0.498329,
+                          -0.995711 -0.0042473 -0.0924156,
+                          -0.993813 -0.0261418 -0.107947,
+                          -0.755709 -0.424939 0.498329,
+                          -0.762599 -0.461076 0.453709,
+                          -0.995711 -0.0042473 -0.0924156,
+                          -0.996216 -0.0331118 -0.0803581,
+                          -0.994107 0.0343605 -0.102815,
+                          -0.995275 -0.0238072 -0.0941335,
+                          -0.738757 -0.599664 0.307637,
+                          -0.996111 -0.0259996 -0.0841797,
+                          -0.994763 -0.0165733 -0.100855,
+                          -0.761237 -0.485463 0.429935,
+                          -0.738757 -0.599664 0.307637,
+                          -0.994763 -0.0165733 -0.100855,
+                          0 0.504872 -0.863194,
+                          0 0.473745 -0.880662,
+                          8.69324e-17 0.53953 -0.841966,
+                          -2.32481e-17 0.42372 -0.905793,
+                          0 0.473745 -0.880662,
+                          0 0.504872 -0.863194,
+                          -1.87926e-17 0.415586 -0.909554,
+                          0 0.473745 -0.880662,
+                          -2.32481e-17 0.42372 -0.905793,
+                          -0.415011 0.0170192 -0.909657,
+                          -0.438087 0.00214235 -0.89893,
+                          -0.410724 0.128524 -0.902656,
+                          1.27506e-17 0.552662 -0.833405,
+                          8.69324e-17 0.53953 -0.841966,
+                          4.06551e-17 0.556875 -0.830596,
+                          0 0.504872 -0.863194,
+                          8.69324e-17 0.53953 -0.841966,
+                          1.27506e-17 0.552662 -0.833405,
+                          -0.615519 0.141496 -0.775316,
+                          -0.410724 0.128524 -0.902656,
+                          -0.682416 0.160118 -0.713211,
+                          -0.615519 0.141496 -0.775316,
+                          -0.415011 0.0170192 -0.909657,
+                          -0.410724 0.128524 -0.902656,
+                          -0.793107 0.370103 -0.483741,
+                          -0.682416 0.160118 -0.713211,
+                          -0.844968 0.169741 -0.507166,
+                          -0.793107 0.370103 -0.483741,
+                          -0.615519 0.141496 -0.775316,
+                          -0.682416 0.160118 -0.713211,
+                          -0.813021 0.43997 -0.381344,
+                          -0.844968 0.169741 -0.507166,
+                          -0.925815 0.151449 -0.346308,
+                          -0.794015 0.381232 -0.473501,
+                          -0.793107 0.370103 -0.483741,
+                          -0.844968 0.169741 -0.507166,
+                          -0.813021 0.43997 -0.381344,
+                          -0.794015 0.381232 -0.473501,
+                          -0.844968 0.169741 -0.507166,
+                          -0.829328 0.4432 -0.340279,
+                          -0.925815 0.151449 -0.346308,
+                          -0.966152 0.108226 -0.234175,
+                          -0.829328 0.4432 -0.340279,
+                          -0.813021 0.43997 -0.381344,
+                          -0.925815 0.151449 -0.346308,
+                          -0.862143 0.413263 -0.293125,
+                          -0.966152 0.108226 -0.234175,
+                          -0.98478 0.063397 -0.161828,
+                          -0.862143 0.413263 -0.293125,
+                          -0.829328 0.4432 -0.340279,
+                          -0.966152 0.108226 -0.234175,
+                          -0.899972 0.375461 -0.221538,
+                          -0.98478 0.063397 -0.161828,
+                          -0.994107 0.0343605 -0.102815,
+                          -0.899972 0.375461 -0.221538,
+                          -0.862143 0.413263 -0.293125,
+                          -0.98478 0.063397 -0.161828,
+                          -0.996216 -0.0331118 -0.0803581,
+                          -0.998308 0.019633 -0.0547321,
+                          -0.994107 0.0343605 -0.102815,
+                          -0.927189 0.344338 -0.147486,
+                          -0.994107 0.0343605 -0.102815,
+                          -0.998308 0.019633 -0.0547321,
+                          -0.927189 0.344338 -0.147486,
+                          -0.899972 0.375461 -0.221538,
+                          -0.994107 0.0343605 -0.102815,
+                          -0.997764 -0.0359746 -0.0563211,
+                          -0.999852 0.00942684 -0.0143956,
+                          -0.998308 0.019633 -0.0547321,
+                          -0.943678 0.318924 -0.088088,
+                          -0.998308 0.019633 -0.0547321,
+                          -0.999852 0.00942684 -0.0143956,
+                          -0.996216 -0.0331118 -0.0803581,
+                          -0.997764 -0.0359746 -0.0563211,
+                          -0.998308 0.019633 -0.0547321,
+                          -0.943678 0.318924 -0.088088,
+                          -0.927189 0.344338 -0.147486,
+                          -0.998308 0.019633 -0.0547321,
+                          -0.999195 -0.0400936 -0.00124969,
+                          -0.999897 -0.000324471 0.0143593,
+                          -0.999852 0.00942684 -0.0143956,
+                          -0.954524 0.295499 -0.0395538,
+                          -0.999852 0.00942684 -0.0143956,
+                          -0.999897 -0.000324471 0.0143593,
+                          -0.999095 -0.0415496 -0.0091486,
+                          -0.999195 -0.0400936 -0.00124969,
+                          -0.999852 0.00942684 -0.0143956,
+                          -0.998963 -0.041913 -0.0177683,
+                          -0.999095 -0.0415496 -0.0091486,
+                          -0.999852 0.00942684 -0.0143956,
+                          -0.997764 -0.0359746 -0.0563211,
+                          -0.998963 -0.041913 -0.0177683,
+                          -0.999852 0.00942684 -0.0143956,
+                          -0.954524 0.295499 -0.0395538,
+                          -0.943678 0.318924 -0.088088,
+                          -0.999852 0.00942684 -0.0143956,
+                          3.20821e-18 -0.40689 0.913477,
+                          -1.54635e-17 -0.408015 0.912975,
+                          -3.06513e-16 -0.885074 0.46545,
+                          -0.959228 0.28051 -0.0345866,
+                          -0.954524 0.295499 -0.0395538,
+                          -0.999897 -0.000324471 0.0143593,
+                          -0.992465 0.122522 0.00157007,
+                          -0.959228 0.28051 -0.0345866,
+                          -0.999897 -0.000324471 0.0143593,
+                          -0.999722 0.0173921 0.0159466,
+                          -0.992465 0.122522 0.00157007,
+                          -0.999897 -0.000324471 0.0143593,
+                          -8.60778e-16 -0.251258 0.96792,
+                          2.646e-15 -0.241134 0.970492,
+                          -1.54635e-17 -0.408015 0.912975,
+                          -8.60778e-16 -0.251258 0.96792,
+                          -1.54635e-17 -0.408015 0.912975,
+                          3.20821e-18 -0.40689 0.913477,
+                          0 -0.829854 0.557981,
+                          0 -0.829854 0.557981,
+                          -1.63392e-15 -0.885557 0.46453,
+                          3.20821e-18 -0.40689 0.913477,
+                          -3.06513e-16 -0.885074 0.46545,
+                          2.4521e-16 -0.885074 0.46545,
+                          0 -0.829854 0.557981,
+                          -1.63392e-15 -0.885557 0.46453,
+                          -2.89947e-15 -0.930969 0.365098,
+                          -0.80433 -0.571693 -0.161926,
+                          -0.999281 -0.0346941 -0.0152797,
+                          -0.998015 -0.0289985 -0.0559017,
+                          0 -0.829854 0.557981,
+                          -2.89947e-15 -0.930969 0.365098,
+                          -2.89904e-15 -0.931357 0.364107,
+                          0 -0.973918 0.226898,
+                          -2.89904e-15 -0.931357 0.364107,
+                          -2.89947e-15 -0.930969 0.365098,
+                          -0.706904 -0.68535 -0.174878,
+                          -0.998015 -0.0289985 -0.0559017,
+                          -0.996111 -0.0259996 -0.0841797,
+                          -0.80433 -0.571693 -0.161926,
+                          -0.998015 -0.0289985 -0.0559017,
+                          -0.706904 -0.68535 -0.174878,
+                          -0.738757 -0.599664 0.307637,
+                          -0.706904 -0.68535 -0.174878,
+                          -0.996111 -0.0259996 -0.0841797,
+                          1.78938e-17 0.56066 -0.828046,
+                          4.06551e-17 0.556875 -0.830596,
+                          -6.34411e-17 0.622314 -0.782768,
+                          1.78938e-17 0.56066 -0.828046,
+                          1.27506e-17 0.552662 -0.833405,
+                          4.06551e-17 0.556875 -0.830596,
+                          6.69796e-17 0.647104 -0.762402,
+                          -6.34411e-17 0.622314 -0.782768,
+                          3.16328e-16 0.708153 -0.706059,
+                          1.55375e-16 0.617336 -0.786699,
+                          -6.34411e-17 0.622314 -0.782768,
+                          6.69796e-17 0.647104 -0.762402,
+                          1.78938e-17 0.56066 -0.828046,
+                          -6.34411e-17 0.622314 -0.782768,
+                          1.55375e-16 0.617336 -0.786699,
+                          -1.10227e-17 0.688935 -0.724823,
+                          3.16328e-16 0.708153 -0.706059,
+                          3.74516e-16 0.712488 -0.701684,
+                          4.42747e-18 0.677252 -0.735751,
+                          3.16328e-16 0.708153 -0.706059,
+                          -1.10227e-17 0.688935 -0.724823,
+                          6.69796e-17 0.647104 -0.762402,
+                          3.16328e-16 0.708153 -0.706059,
+                          4.42747e-18 0.677252 -0.735751,
+                          -0.776227 0.499455 -0.38473,
+                          -0.794015 0.381232 -0.473501,
+                          -0.813021 0.43997 -0.381344,
+                          0 0.715268 -0.698851,
+                          3.74516e-16 0.712488 -0.701684,
+                          1.03499e-15 0.759479 -0.650532,
+                          0 0.715268 -0.698851,
+                          -1.10227e-17 0.688935 -0.724823,
+                          3.74516e-16 0.712488 -0.701684,
+                          -0.718105 0.604752 -0.344383,
+                          -0.813021 0.43997 -0.381344,
+                          -0.829328 0.4432 -0.340279,
+                          -0.718105 0.604752 -0.344383,
+                          -0.776227 0.499455 -0.38473,
+                          -0.813021 0.43997 -0.381344,
+                          -0.646643 0.675172 -0.35496,
+                          -0.829328 0.4432 -0.340279,
+                          -0.862143 0.413263 -0.293125,
+                          -0.646643 0.675172 -0.35496,
+                          -0.718105 0.604752 -0.344383,
+                          -0.829328 0.4432 -0.340279,
+                          -0.603589 0.713421 -0.355964,
+                          -0.862143 0.413263 -0.293125,
+                          -0.899972 0.375461 -0.221538,
+                          -0.603589 0.713421 -0.355964,
+                          -0.646643 0.675172 -0.35496,
+                          -0.862143 0.413263 -0.293125,
+                          -0.659559 0.698517 -0.277588,
+                          -0.899972 0.375461 -0.221538,
+                          -0.927189 0.344338 -0.147486,
+                          -0.632546 0.704152 -0.322576,
+                          -0.603589 0.713421 -0.355964,
+                          -0.899972 0.375461 -0.221538,
+                          -0.659559 0.698517 -0.277588,
+                          -0.632546 0.704152 -0.322576,
+                          -0.899972 0.375461 -0.221538,
+                          -0.833927 0.528771 -0.158012,
+                          -0.927189 0.344338 -0.147486,
+                          -0.943678 0.318924 -0.088088,
+                          -0.699015 0.687936 -0.195251,
+                          -0.659559 0.698517 -0.277588,
+                          -0.927189 0.344338 -0.147486,
+                          -0.770544 0.612044 -0.177943,
+                          -0.699015 0.687936 -0.195251,
+                          -0.927189 0.344338 -0.147486,
+                          -0.833927 0.528771 -0.158012,
+                          -0.770544 0.612044 -0.177943,
+                          -0.927189 0.344338 -0.147486,
+                          -0.891521 0.442728 -0.0958249,
+                          -0.943678 0.318924 -0.088088,
+                          -0.954524 0.295499 -0.0395538,
+                          -0.891521 0.442728 -0.0958249,
+                          -0.833927 0.528771 -0.158012,
+                          -0.943678 0.318924 -0.088088,
+                          -5.99411e-19 0.822371 0.568952,
+                          -1.03032e-16 0.64515 0.764056,
+                          -1.62043e-16 0.610511 0.792008,
+                          -5.99411e-19 0.822371 0.568952,
+                          3.52486e-16 0.903852 0.427846,
+                          -1.03032e-16 0.64515 0.764056,
+                          4.77018e-16 0.604413 0.796671,
+                          -1.62043e-16 0.610511 0.792008,
+                          4.56285e-15 0.201696 0.979448,
+                          -5.99411e-19 0.822371 0.568952,
+                          -1.62043e-16 0.610511 0.792008,
+                          4.77018e-16 0.604413 0.796671,
+                          2.75053e-16 0.563585 0.826058,
+                          4.56285e-15 0.201696 0.979448,
+                          2.646e-15 -0.241134 0.970492,
+                          4.77018e-16 0.604413 0.796671,
+                          4.56285e-15 0.201696 0.979448,
+                          2.75053e-16 0.563585 0.826058,
+                          2.75053e-16 0.563585 0.826058,
+                          2.646e-15 -0.241134 0.970492,
+                          -8.60778e-16 -0.251258 0.96792,
+                          -2.61498e-17 0.804531 -0.593911,
+                          1.03499e-15 0.759479 -0.650532,
+                          1.09095e-15 0.811318 -0.584606,
+                          0 0.758935 -0.651166,
+                          1.03499e-15 0.759479 -0.650532,
+                          -2.61498e-17 0.804531 -0.593911,
+                          0 0.715268 -0.698851,
+                          1.03499e-15 0.759479 -0.650532,
+                          0 0.758935 -0.651166,
+                          1.39947e-17 0.849781 -0.527136,
+                          1.09095e-15 0.811318 -0.584606,
+                          2.51317e-17 0.860811 -0.508925,
+                          -2.61498e-17 0.804531 -0.593911,
+                          1.09095e-15 0.811318 -0.584606,
+                          1.39947e-17 0.849781 -0.527136,
+                          -8.92837e-18 0.878603 -0.477554,
+                          2.51317e-17 0.860811 -0.508925,
+                          6.87921e-16 0.905204 -0.424976,
+                          -8.92837e-18 0.878603 -0.477554,
+                          1.39947e-17 0.849781 -0.527136,
+                          2.51317e-17 0.860811 -0.508925,
+                          0.736717 0.67406 0.0537594,
+                          0.729667 0.674472 0.112577,
+                          0.728747 0.682554 0.055208,
+                          0.739818 0.663394 0.112153,
+                          0.729667 0.674472 0.112577,
+                          0.736717 0.67406 0.0537594,
+                          0.741656 0.655585 0.141967,
+                          0.729667 0.674472 0.112577,
+                          0.739818 0.663394 0.112153,
+                          0.73143 0.681887 -0.00637074,
+                          0.728747 0.682554 0.055208,
+                          0.724824 0.688931 0.0019936,
+                          0.736717 0.67406 0.0537594,
+                          0.728747 0.682554 0.055208,
+                          0.73143 0.681887 -0.00637074,
+                          0.721124 0.691307 -0.0455562,
+                          0.724824 0.688931 0.0019936,
+                          0.705378 0.706618 -0.05597,
+                          0.73143 0.681887 -0.00637074,
+                          0.724824 0.688931 0.0019936,
+                          0.721124 0.691307 -0.0455562,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.721124 0.691307 -0.0455562,
+                          0.705378 0.706618 -0.05597,
+                          0.709389 0.701605 -0.0672173,
+                          0.707344 0.704194 -0.0614443,
+                          0.709389 0.701605 -0.0672173,
+                          0.705378 0.706618 -0.05597,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          1.42365e-15 0.999983 -0.00589021,
+                          -1.10818e-15 0.999983 -0.00589021,
+                          3.52486e-16 0.903852 0.427846,
+                          1.91022e-16 0.959119 0.283002,
+                          3.52486e-16 0.903852 0.427846,
+                          -5.99411e-19 0.822371 0.568952,
+                          1.42365e-15 0.999983 -0.00589021,
+                          3.52486e-16 0.903852 0.427846,
+                          1.91022e-16 0.959119 0.283002,
+                          0.255495 0.899242 0.355085,
+                          0.242724 0.923939 0.295672,
+                          0.213351 0.93399 0.286607,
+                          -0.0326208 -0.282088 0.958834,
+                          -0.0286089 -0.28318 0.95864,
+                          -0.0407642 -0.294818 0.954684,
+                          -0.0326208 -0.282088 0.958834,
+                          -0.00900156 -0.26102 0.965291,
+                          -0.0286089 -0.28318 0.95864,
+                          0.505425 0.757504 0.413199,
+                          0.242724 0.923939 0.295672,
+                          0.255495 0.899242 0.355085,
+                          0.365389 0.873722 0.321093,
+                          0.242724 0.923939 0.295672,
+                          0.505425 0.757504 0.413199,
+                          -0.0489161 -0.297826 0.953366,
+                          -0.0407642 -0.294818 0.954684,
+                          -0.0663166 -0.316575 0.946247,
+                          -0.0489161 -0.297826 0.953366,
+                          -0.0326208 -0.282088 0.958834,
+                          -0.0407642 -0.294818 0.954684,
+                          0.478944 0.716167 0.507658,
+                          0.255495 0.899242 0.355085,
+                          0.272414 0.864531 0.422346,
+                          0.505425 0.757504 0.413199,
+                          0.255495 0.899242 0.355085,
+                          0.478944 0.716167 0.507658,
+                          0.449388 0.659924 0.602122,
+                          0.272414 0.864531 0.422346,
+                          0.290234 0.81442 0.502478,
+                          0.478944 0.716167 0.507658,
+                          0.272414 0.864531 0.422346,
+                          0.449388 0.659924 0.602122,
+                          0.401512 0.571712 0.715495,
+                          0.290234 0.81442 0.502478,
+                          0.300554 0.73156 0.611954,
+                          0.449388 0.659924 0.602122,
+                          0.290234 0.81442 0.502478,
+                          0.401512 0.571712 0.715495,
+                          0.30895 0.419535 0.853546,
+                          0.300554 0.73156 0.611954,
+                          0.285443 0.585657 0.758636,
+                          0.401512 0.571712 0.715495,
+                          0.300554 0.73156 0.611954,
+                          0.30895 0.419535 0.853546,
+                          0.165251 0.208397 0.963983,
+                          0.285443 0.585657 0.758636,
+                          0.207026 0.331087 0.920609,
+                          0.30895 0.419535 0.853546,
+                          0.285443 0.585657 0.758636,
+                          0.165251 0.208397 0.963983,
+                          0.0151815 0.0095446 0.999839,
+                          0.207026 0.331087 0.920609,
+                          0.0806768 0.0505452 0.995458,
+                          0.165251 0.208397 0.963983,
+                          0.207026 0.331087 0.920609,
+                          0.0151815 0.0095446 0.999839,
+                          -0.107548 -0.143016 0.98386,
+                          0.0806768 0.0505452 0.995458,
+                          0.00636165 -0.0948697 0.995469,
+                          0.0151815 0.0095446 0.999839,
+                          0.0806768 0.0505452 0.995458,
+                          -0.107548 -0.143016 0.98386,
+                          -0.173303 -0.23585 0.956212,
+                          0.00636165 -0.0948697 0.995469,
+                          0.0253113 -0.0994692 0.994719,
+                          -0.107548 -0.143016 0.98386,
+                          0.00636165 -0.0948697 0.995469,
+                          -0.173303 -0.23585 0.956212,
+                          -0.160322 -0.271125 0.949099,
+                          0.0253113 -0.0994692 0.994719,
+                          0.117242 -0.0290739 0.992678,
+                          -0.173303 -0.23585 0.956212,
+                          0.0253113 -0.0994692 0.994719,
+                          -0.160322 -0.271125 0.949099,
+                          -0.0335298 -0.23329 0.971829,
+                          0.117242 -0.0290739 0.992678,
+                          0.200806 0.0176098 0.979473,
+                          -0.160322 -0.271125 0.949099,
+                          0.117242 -0.0290739 0.992678,
+                          -0.0335298 -0.23329 0.971829,
+                          0.307526 -0.00199125 0.951538,
+                          0.200806 0.0176098 0.979473,
+                          0.262863 0.0601202 0.962958,
+                          0.307526 -0.00199125 0.951538,
+                          -0.0335298 -0.23329 0.971829,
+                          0.200806 0.0176098 0.979473,
+                          0.999465 -0.0135088 0.029795,
+                          0.99816 0.039317 0.0461628,
+                          0.99785 0.0385485 0.0529995,
+                          0.0459586 -0.998695 -0.0222592,
+                          0.0459393 -0.998703 -0.0219417,
+                          0.0448891 -0.998853 0.0166878,
+                          0.997961 -0.0210505 0.0602533,
+                          0.999465 -0.0135088 0.029795,
+                          0.99785 0.0385485 0.0529995,
+                          0.996661 0.0341975 0.0741404,
+                          0.997961 -0.0210505 0.0602533,
+                          0.99785 0.0385485 0.0529995,
+                          -0.0274133 -0.754843 0.655332,
+                          -0.0138176 -0.811818 0.583746,
+                          0.0459286 -0.998708 -0.0217403,
+                          -0.0274133 -0.754843 0.655332,
+                          0.0459286 -0.998708 -0.0217403,
+                          0.0459564 -0.998696 -0.0222177,
+                          0.999465 -0.0135088 0.029795,
+                          0.998416 0.0400177 0.0395406,
+                          0.99816 0.039317 0.0461628,
+                          0.044795 -0.998737 0.0227651,
+                          0.0448891 -0.998853 0.0166878,
+                          0.0440766 -0.997324 0.0583287,
+                          0.0453473 -0.998971 -0.000573705,
+                          0.0448891 -0.998853 0.0166878,
+                          0.044795 -0.998737 0.0227651,
+                          0.0459786 -0.998687 -0.0226,
+                          0.0459586 -0.998695 -0.0222592,
+                          0.0448891 -0.998853 0.0166878,
+                          0.0453473 -0.998971 -0.000573705,
+                          0.0459786 -0.998687 -0.0226,
+                          0.0448891 -0.998853 0.0166878,
+                          0.999966 -0.00666107 0.00478963,
+                          0.998961 0.0415846 0.0186559,
+                          0.998416 0.0400177 0.0395406,
+                          0 -0.980732 0.195358,
+                          -1.80504e-16 -0.988942 0.148301,
+                          -2.89904e-15 -0.931357 0.364107,
+                          0.999465 -0.0135088 0.029795,
+                          0.999966 -0.00666107 0.00478963,
+                          0.998416 0.0400177 0.0395406,
+                          0.0444117 -0.998184 0.0406867,
+                          0.044795 -0.998737 0.0227651,
+                          0.0440766 -0.997324 0.0583287,
+                          0 -0.980732 0.195358,
+                          0 -0.99269 0.120689,
+                          -1.80504e-16 -0.988942 0.148301,
+                          0.999966 -0.00666107 0.00478963,
+                          0.999181 0.0404431 0.00143205,
+                          0.998961 0.0415846 0.0186559,
+                          0 -0.973918 0.226898,
+                          0 -0.980732 0.195358,
+                          -2.89904e-15 -0.931357 0.364107,
+                          0.999966 -0.00666107 0.00478963,
+                          0.999878 0.000638396 -0.0155946,
+                          0.999181 0.0404431 0.00143205,
+                          0.955332 -0.293321 0.0361072,
+                          0.999878 0.000638396 -0.0155946,
+                          0.999966 -0.00666107 0.00478963,
+                          0.955332 -0.293321 0.0361072,
+                          0.999718 -0.0160977 -0.017437,
+                          0.999878 0.000638396 -0.0155946,
+                          0.948379 -0.309489 0.0692348,
+                          0.999966 -0.00666107 0.00478963,
+                          0.999465 -0.0135088 0.029795,
+                          0.948379 -0.309489 0.0692348,
+                          0.955332 -0.293321 0.0361072,
+                          0.999966 -0.00666107 0.00478963,
+                          0.939001 -0.326619 0.107691,
+                          0.999465 -0.0135088 0.029795,
+                          0.997961 -0.0210505 0.0602533,
+                          0.939001 -0.326619 0.107691,
+                          0.948379 -0.309489 0.0692348,
+                          0.999465 -0.0135088 0.029795,
+                          0.995764 0.0215583 0.0893857,
+                          0.994987 -0.0311637 0.0950298,
+                          0.997961 -0.0210505 0.0602533,
+                          0.926138 -0.345159 0.152099,
+                          0.997961 -0.0210505 0.0602533,
+                          0.994987 -0.0311637 0.0950298,
+                          0.99585 0.0264665 0.0870774,
+                          0.995764 0.0215583 0.0893857,
+                          0.997961 -0.0210505 0.0602533,
+                          0.996661 0.0341975 0.0741404,
+                          0.99585 0.0264665 0.0870774,
+                          0.997961 -0.0210505 0.0602533,
+                          0.926138 -0.345159 0.152099,
+                          0.939001 -0.326619 0.107691,
+                          0.997961 -0.0210505 0.0602533,
+                          0.994285 0.00251376 0.106732,
+                          0.989718 -0.0472321 0.135006,
+                          0.994987 -0.0311637 0.0950298,
+                          0.907701 -0.36668 0.20402,
+                          0.994987 -0.0311637 0.0950298,
+                          0.989718 -0.0472321 0.135006,
+                          0.995764 0.0215583 0.0893857,
+                          0.994285 0.00251376 0.106732,
+                          0.994987 -0.0311637 0.0950298,
+                          0.907701 -0.36668 0.20402,
+                          0.926138 -0.345159 0.152099,
+                          0.994987 -0.0311637 0.0950298,
+                          0.988429 -0.0282985 0.149018,
+                          0.98087 -0.0717658 0.180953,
+                          0.989718 -0.0472321 0.135006,
+                          0.88221 -0.392213 0.260526,
+                          0.989718 -0.0472321 0.135006,
+                          0.98087 -0.0717658 0.180953,
+                          0.994285 0.00251376 0.106732,
+                          0.988429 -0.0282985 0.149018,
+                          0.989718 -0.0472321 0.135006,
+                          0.88221 -0.392213 0.260526,
+                          0.907701 -0.36668 0.20402,
+                          0.989718 -0.0472321 0.135006,
+                          0.969242 -0.0750954 0.234371,
+                          0.966586 -0.103606 0.234474,
+                          0.98087 -0.0717658 0.180953,
+                          0.854827 -0.418864 0.306306,
+                          0.98087 -0.0717658 0.180953,
+                          0.966586 -0.103606 0.234474,
+                          0.988429 -0.0282985 0.149018,
+                          0.969242 -0.0750954 0.234371,
+                          0.98087 -0.0717658 0.180953,
+                          0.854827 -0.418864 0.306306,
+                          0.88221 -0.392213 0.260526,
+                          0.98087 -0.0717658 0.180953,
+                          0.925441 -0.136227 0.353554,
+                          0.942738 -0.134963 0.305009,
+                          0.966586 -0.103606 0.234474,
+                          0.83295 -0.439043 0.336803,
+                          0.966586 -0.103606 0.234474,
+                          0.942738 -0.134963 0.305009,
+                          0.969242 -0.0750954 0.234371,
+                          0.925441 -0.136227 0.353554,
+                          0.966586 -0.103606 0.234474,
+                          0.83295 -0.439043 0.336803,
+                          0.854827 -0.418864 0.306306,
+                          0.966586 -0.103606 0.234474,
+                          0.842885 -0.216925 0.492431,
+                          0.903023 -0.158325 0.399354,
+                          0.942738 -0.134963 0.305009,
+                          0.818964 -0.443708 0.363897,
+                          0.942738 -0.134963 0.305009,
+                          0.903023 -0.158325 0.399354,
+                          0.925441 -0.136227 0.353554,
+                          0.842885 -0.216925 0.492431,
+                          0.942738 -0.134963 0.305009,
+                          0.818964 -0.443708 0.363897,
+                          0.83295 -0.439043 0.336803,
+                          0.942738 -0.134963 0.305009,
+                          0.716697 -0.307717 0.625824,
+                          0.837541 -0.167833 0.519959,
+                          0.903023 -0.158325 0.399354,
+                          0.81044 -0.423962 0.404282,
+                          0.903023 -0.158325 0.399354,
+                          0.837541 -0.167833 0.519959,
+                          0.842885 -0.216925 0.492431,
+                          0.716697 -0.307717 0.625824,
+                          0.903023 -0.158325 0.399354,
+                          0.81044 -0.423962 0.404282,
+                          0.818964 -0.443708 0.363897,
+                          0.903023 -0.158325 0.399354,
+                          0.546312 -0.397497 0.737252,
+                          0.727389 -0.164286 0.66627,
+                          0.837541 -0.167833 0.519959,
+                          0.793387 -0.372827 0.481183,
+                          0.837541 -0.167833 0.519959,
+                          0.727389 -0.164286 0.66627,
+                          0.716697 -0.307717 0.625824,
+                          0.546312 -0.397497 0.737252,
+                          0.837541 -0.167833 0.519959,
+                          0.793387 -0.372827 0.481183,
+                          0.81044 -0.423962 0.404282,
+                          0.837541 -0.167833 0.519959,
+                          0.335034 -0.469696 0.816785,
+                          0.555027 -0.148919 0.818394,
+                          0.727389 -0.164286 0.66627,
+                          0.748685 -0.28114 0.600359,
+                          0.727389 -0.164286 0.66627,
+                          0.555027 -0.148919 0.818394,
+                          0.546312 -0.397497 0.737252,
+                          0.335034 -0.469696 0.816785,
+                          0.727389 -0.164286 0.66627,
+                          0.748685 -0.28114 0.600359,
+                          0.793387 -0.372827 0.481183,
+                          0.727389 -0.164286 0.66627,
+                          0.137312 -0.492055 0.859667,
+                          0.373601 -0.113321 0.920641,
+                          0.555027 -0.148919 0.818394,
+                          0.714049 -0.228999 0.661584,
+                          0.555027 -0.148919 0.818394,
+                          0.373601 -0.113321 0.920641,
+                          0.335034 -0.469696 0.816785,
+                          0.137312 -0.492055 0.859667,
+                          0.555027 -0.148919 0.818394,
+                          0.714049 -0.228999 0.661584,
+                          0.748685 -0.28114 0.600359,
+                          0.555027 -0.148919 0.818394,
+                          0.137327 -0.414572 0.899595,
+                          0.421691 -0.0157304 0.906603,
+                          0.373601 -0.113321 0.920641,
+                          0.565591 -0.072541 0.821489,
+                          0.373601 -0.113321 0.920641,
+                          0.421691 -0.0157304 0.906603,
+                          0.137312 -0.492055 0.859667,
+                          0.137327 -0.414572 0.899595,
+                          0.373601 -0.113321 0.920641,
+                          0.565591 -0.072541 0.821489,
+                          0.714049 -0.228999 0.661584,
+                          0.373601 -0.113321 0.920641,
+                          0.482545 -0.175989 0.858008,
+                          0.728599 0.159484 0.666115,
+                          0.421691 -0.0157304 0.906603,
+                          0.709086 0.153722 0.688161,
+                          0.421691 -0.0157304 0.906603,
+                          0.728599 0.159484 0.666115,
+                          0.137327 -0.414572 0.899595,
+                          0.482545 -0.175989 0.858008,
+                          0.421691 -0.0157304 0.906603,
+                          0.530617 0.0402324 0.846657,
+                          0.565591 -0.072541 0.821489,
+                          0.421691 -0.0157304 0.906603,
+                          0.709086 0.153722 0.688161,
+                          0.530617 0.0402324 0.846657,
+                          0.421691 -0.0157304 0.906603,
+                          0.951044 0.199036 0.236431,
+                          0.852457 0.190459 0.486871,
+                          0.728599 0.159484 0.666115,
+                          0.482545 -0.175989 0.858008,
+                          0.951044 0.199036 0.236431,
+                          0.728599 0.159484 0.666115,
+                          0.951044 0.199036 0.236431,
+                          0.946359 0.192631 0.25942,
+                          0.852457 0.190459 0.486871,
+                          -0.0165788 -0.196141 0.980435,
+                          0.951044 0.199036 0.236431,
+                          0.482545 -0.175989 0.858008,
+                          0.778902 0.221473 0.586738,
+                          0.960484 0.250939 0.120413,
+                          0.951044 0.199036 0.236431,
+                          -0.0165788 -0.196141 0.980435,
+                          0.778902 0.221473 0.586738,
+                          0.951044 0.199036 0.236431,
+                          -0.255018 -0.307073 0.916882,
+                          0.482545 -0.175989 0.858008,
+                          0.137327 -0.414572 0.899595,
+                          -0.255018 -0.307073 0.916882,
+                          -0.0165788 -0.196141 0.980435,
+                          0.482545 -0.175989 0.858008,
+                          -0.247035 -0.323202 0.913518,
+                          0.137327 -0.414572 0.899595,
+                          0.137312 -0.492055 0.859667,
+                          -0.247035 -0.323202 0.913518,
+                          -0.255018 -0.307073 0.916882,
+                          0.137327 -0.414572 0.899595,
+                          -0.126872 -0.291549 0.948105,
+                          0.137312 -0.492055 0.859667,
+                          0.335034 -0.469696 0.816785,
+                          -0.126872 -0.291549 0.948105,
+                          -0.247035 -0.323202 0.913518,
+                          0.137312 -0.492055 0.859667,
+                          0.090887 -0.213489 0.972709,
+                          0.335034 -0.469696 0.816785,
+                          0.546312 -0.397497 0.737252,
+                          0.090887 -0.213489 0.972709,
+                          -0.126872 -0.291549 0.948105,
+                          0.335034 -0.469696 0.816785,
+                          0.329525 -0.114292 0.937204,
+                          0.546312 -0.397497 0.737252,
+                          0.716697 -0.307717 0.625824,
+                          0.329525 -0.114292 0.937204,
+                          0.090887 -0.213489 0.972709,
+                          0.546312 -0.397497 0.737252,
+                          0.5376 -0.0151858 0.843063,
+                          0.716697 -0.307717 0.625824,
+                          0.842885 -0.216925 0.492431,
+                          0.5376 -0.0151858 0.843063,
+                          0.329525 -0.114292 0.937204,
+                          0.716697 -0.307717 0.625824,
+                          0.693621 0.0711805 0.716815,
+                          0.842885 -0.216925 0.492431,
+                          0.925441 -0.136227 0.353554,
+                          0.693621 0.0711805 0.716815,
+                          0.5376 -0.0151858 0.843063,
+                          0.842885 -0.216925 0.492431,
+                          0.847576 0.156578 0.507048,
+                          0.925441 -0.136227 0.353554,
+                          0.969242 -0.0750954 0.234371,
+                          0.787508 0.126598 0.603161,
+                          0.693621 0.0711805 0.716815,
+                          0.925441 -0.136227 0.353554,
+                          0.847576 0.156578 0.507048,
+                          0.787508 0.126598 0.603161,
+                          0.925441 -0.136227 0.353554,
+                          0.901234 0.175731 0.396101,
+                          0.969242 -0.0750954 0.234371,
+                          0.988429 -0.0282985 0.149018,
+                          0.901234 0.175731 0.396101,
+                          0.847576 0.156578 0.507048,
+                          0.969242 -0.0750954 0.234371,
+                          0.945989 0.184908 0.266297,
+                          0.988429 -0.0282985 0.149018,
+                          0.994285 0.00251376 0.106732,
+                          0.945989 0.184908 0.266297,
+                          0.901234 0.175731 0.396101,
+                          0.988429 -0.0282985 0.149018,
+                          0.995993 0.0194826 0.0872825,
+                          0.994285 0.00251376 0.106732,
+                          0.995764 0.0215583 0.0893857,
+                          0.995101 0.0505349 0.0849728,
+                          0.994285 0.00251376 0.106732,
+                          0.995993 0.0194826 0.0872825,
+                          0.970285 0.190321 0.149412,
+                          0.945989 0.184908 0.266297,
+                          0.994285 0.00251376 0.106732,
+                          0.995101 0.0505349 0.0849728,
+                          0.970285 0.190321 0.149412,
+                          0.994285 0.00251376 0.106732,
+                          -0.0644747 -0.678342 0.731912,
+                          -0.0659442 -0.675302 0.734588,
+                          -0.0506792 -0.693134 0.719024,
+                          -0.0773379 -0.663403 0.744255,
+                          -0.0749824 -0.666713 0.741533,
+                          -0.0659442 -0.675302 0.734588,
+                          -0.0644747 -0.678342 0.731912,
+                          -0.0773379 -0.663403 0.744255,
+                          -0.0659442 -0.675302 0.734588,
+                          -0.0274133 -0.754843 0.655332,
+                          -0.0506792 -0.693134 0.719024,
+                          -0.0138176 -0.811818 0.583746,
+                          -0.0274133 -0.754843 0.655332,
+                          -0.0644747 -0.678342 0.731912,
+                          -0.0506792 -0.693134 0.719024,
+                          -0.0888338 -0.623556 0.776715,
+                          -0.095728 -0.578002 0.810401,
+                          -0.0749824 -0.666713 0.741533,
+                          -0.0773379 -0.663403 0.744255,
+                          -0.0888338 -0.623556 0.776715,
+                          -0.0749824 -0.666713 0.741533,
+                          0.0844325 -0.0109864 -0.996369,
+                          0.107244 -0.0708239 -0.991707,
+                          0.618402 -0.215215 -0.755819,
+                          0.249847 -0.0553123 0.966704,
+                          0.778902 0.221473 0.586738,
+                          -0.0165788 -0.196141 0.980435,
+                          0.249847 -0.0553123 0.966704,
+                          0.353089 0.0455973 0.934478,
+                          0.778902 0.221473 0.586738,
+                          -0.0335298 -0.23329 0.971829,
+                          -0.0165788 -0.196141 0.980435,
+                          -0.255018 -0.307073 0.916882,
+                          -0.0335298 -0.23329 0.971829,
+                          0.249847 -0.0553123 0.966704,
+                          -0.0165788 -0.196141 0.980435,
+                          -0.160322 -0.271125 0.949099,
+                          -0.255018 -0.307073 0.916882,
+                          -0.247035 -0.323202 0.913518,
+                          -0.160322 -0.271125 0.949099,
+                          -0.0335298 -0.23329 0.971829,
+                          -0.255018 -0.307073 0.916882,
+                          -0.173303 -0.23585 0.956212,
+                          -0.247035 -0.323202 0.913518,
+                          -0.126872 -0.291549 0.948105,
+                          -0.173303 -0.23585 0.956212,
+                          -0.160322 -0.271125 0.949099,
+                          -0.247035 -0.323202 0.913518,
+                          -0.107548 -0.143016 0.98386,
+                          -0.126872 -0.291549 0.948105,
+                          0.090887 -0.213489 0.972709,
+                          -0.107548 -0.143016 0.98386,
+                          -0.173303 -0.23585 0.956212,
+                          -0.126872 -0.291549 0.948105,
+                          0.0151815 0.0095446 0.999839,
+                          0.090887 -0.213489 0.972709,
+                          0.329525 -0.114292 0.937204,
+                          0.0151815 0.0095446 0.999839,
+                          -0.107548 -0.143016 0.98386,
+                          0.090887 -0.213489 0.972709,
+                          0.165251 0.208397 0.963983,
+                          0.329525 -0.114292 0.937204,
+                          0.5376 -0.0151858 0.843063,
+                          0.165251 0.208397 0.963983,
+                          0.0151815 0.0095446 0.999839,
+                          0.329525 -0.114292 0.937204,
+                          0.30895 0.419535 0.853546,
+                          0.5376 -0.0151858 0.843063,
+                          0.693621 0.0711805 0.716815,
+                          0.30895 0.419535 0.853546,
+                          0.165251 0.208397 0.963983,
+                          0.5376 -0.0151858 0.843063,
+                          0.401512 0.571712 0.715495,
+                          0.693621 0.0711805 0.716815,
+                          0.787508 0.126598 0.603161,
+                          0.401512 0.571712 0.715495,
+                          0.30895 0.419535 0.853546,
+                          0.693621 0.0711805 0.716815,
+                          0.449388 0.659924 0.602122,
+                          0.787508 0.126598 0.603161,
+                          0.847576 0.156578 0.507048,
+                          0.449388 0.659924 0.602122,
+                          0.401512 0.571712 0.715495,
+                          0.787508 0.126598 0.603161,
+                          0.478944 0.716167 0.507658,
+                          0.847576 0.156578 0.507048,
+                          0.901234 0.175731 0.396101,
+                          0.478944 0.716167 0.507658,
+                          0.449388 0.659924 0.602122,
+                          0.847576 0.156578 0.507048,
+                          0.505425 0.757504 0.413199,
+                          0.901234 0.175731 0.396101,
+                          0.945989 0.184908 0.266297,
+                          0.505425 0.757504 0.413199,
+                          0.478944 0.716167 0.507658,
+                          0.901234 0.175731 0.396101,
+                          0.912857 0.350298 0.209723,
+                          0.945989 0.184908 0.266297,
+                          0.970285 0.190321 0.149412,
+                          0.533536 0.784067 0.317141,
+                          0.945989 0.184908 0.266297,
+                          0.912857 0.350298 0.209723,
+                          0.533536 0.784067 0.317141,
+                          0.505425 0.757504 0.413199,
+                          0.945989 0.184908 0.266297,
+                          -0.105666 -0.500619 0.859194,
+                          -0.127223 -0.360406 0.924079,
+                          -0.095728 -0.578002 0.810401,
+                          -0.139162 -0.313626 0.939294,
+                          -0.16006 -0.260343 0.952157,
+                          -0.127223 -0.360406 0.924079,
+                          -0.105666 -0.500619 0.859194,
+                          -0.139162 -0.313626 0.939294,
+                          -0.127223 -0.360406 0.924079,
+                          -0.0888338 -0.623556 0.776715,
+                          -0.105666 -0.500619 0.859194,
+                          -0.095728 -0.578002 0.810401,
+                          0.738186 0.611803 0.284216,
+                          0.533536 0.784067 0.317141,
+                          0.912857 0.350298 0.209723,
+                          -0.185875 -0.230442 0.955169,
+                          -0.195093 -0.231254 0.953132,
+                          -0.16006 -0.260343 0.952157,
+                          -0.139162 -0.313626 0.939294,
+                          -0.185875 -0.230442 0.955169,
+                          -0.16006 -0.260343 0.952157,
+                          0.307526 -0.00199125 0.951538,
+                          0.249847 -0.0553123 0.966704,
+                          -0.0335298 -0.23329 0.971829,
+                          0.365389 0.873722 0.321093,
+                          0.505425 0.757504 0.413199,
+                          0.533536 0.784067 0.317141,
+                          0.738186 0.611803 0.284216,
+                          0.56057 0.76623 0.31409,
+                          0.533536 0.784067 0.317141,
+                          -0.126827 -0.298013 0.946099,
+                          -0.147351 -0.284842 0.947181,
+                          -0.164277 -0.272721 0.947964,
+                          0.365389 0.873722 0.321093,
+                          0.533536 0.784067 0.317141,
+                          0.435379 0.840438 0.322659,
+                          -0.126827 -0.298013 0.946099,
+                          -0.077117 -0.320736 0.944024,
+                          -0.147351 -0.284842 0.947181,
+                          -0.184989 -0.253345 0.949524,
+                          -0.164277 -0.272721 0.947964,
+                          -0.195093 -0.231254 0.953132,
+                          -0.184989 -0.253345 0.949524,
+                          -0.126827 -0.298013 0.946099,
+                          -0.164277 -0.272721 0.947964,
+                          -0.185875 -0.230442 0.955169,
+                          -0.184989 -0.253345 0.949524,
+                          -0.195093 -0.231254 0.953132,
+                          -0.0726414 -0.320933 0.944312,
+                          -0.0663166 -0.316575 0.946247,
+                          -0.077117 -0.320736 0.944024,
+                          -0.126827 -0.298013 0.946099,
+                          -0.0726414 -0.320933 0.944312,
+                          -0.077117 -0.320736 0.944024,
+                          -0.0663267 -0.312329 0.947656,
+                          -0.0489161 -0.297826 0.953366,
+                          -0.0663166 -0.316575 0.946247,
+                          -0.0726414 -0.320933 0.944312,
+                          -0.0663267 -0.312329 0.947656,
+                          -0.0663166 -0.316575 0.946247,
+                          0.948307 -0.314734 0.0406912,
+                          0.955332 -0.293321 0.0361072,
+                          0.948379 -0.309489 0.0692348,
+                          0.823475 -0.550475 0.137354,
+                          0.948379 -0.309489 0.0692348,
+                          0.939001 -0.326619 0.107691,
+                          0.889575 -0.448753 0.0853018,
+                          0.948307 -0.314734 0.0406912,
+                          0.948379 -0.309489 0.0692348,
+                          0.823475 -0.550475 0.137354,
+                          0.889575 -0.448753 0.0853018,
+                          0.948379 -0.309489 0.0692348,
+                          0.776878 -0.602858 0.18172,
+                          0.939001 -0.326619 0.107691,
+                          0.926138 -0.345159 0.152099,
+                          0.776878 -0.602858 0.18172,
+                          0.823475 -0.550475 0.137354,
+                          0.939001 -0.326619 0.107691,
+                          0.679864 -0.692038 0.242627,
+                          0.926138 -0.345159 0.152099,
+                          0.907701 -0.36668 0.20402,
+                          0.738756 -0.645935 0.192372,
+                          0.776878 -0.602858 0.18172,
+                          0.926138 -0.345159 0.152099,
+                          0.698284 -0.686698 0.202101,
+                          0.738756 -0.645935 0.192372,
+                          0.926138 -0.345159 0.152099,
+                          0.679864 -0.692038 0.242627,
+                          0.698284 -0.686698 0.202101,
+                          0.926138 -0.345159 0.152099,
+                          0.624432 -0.704783 0.336698,
+                          0.907701 -0.36668 0.20402,
+                          0.88221 -0.392213 0.260526,
+                          0.655587 -0.697843 0.28848,
+                          0.679864 -0.692038 0.242627,
+                          0.907701 -0.36668 0.20402,
+                          0.624432 -0.704783 0.336698,
+                          0.655587 -0.697843 0.28848,
+                          0.907701 -0.36668 0.20402,
+                          0.593696 -0.716981 0.365325,
+                          0.88221 -0.392213 0.260526,
+                          0.854827 -0.418864 0.306306,
+                          0.593696 -0.716981 0.365325,
+                          0.624432 -0.704783 0.336698,
+                          0.88221 -0.392213 0.260526,
+                          0.582054 -0.731389 0.355364,
+                          0.854827 -0.418864 0.306306,
+                          0.83295 -0.439043 0.336803,
+                          0.582054 -0.731389 0.355364,
+                          0.593696 -0.716981 0.365325,
+                          0.854827 -0.418864 0.306306,
+                          0.592374 -0.738306 0.322485,
+                          0.83295 -0.439043 0.336803,
+                          0.818964 -0.443708 0.363897,
+                          0.592374 -0.738306 0.322485,
+                          0.582054 -0.731389 0.355364,
+                          0.83295 -0.439043 0.336803,
+                          0.684814 -0.65629 0.316723,
+                          0.818964 -0.443708 0.363897,
+                          0.81044 -0.423962 0.404282,
+                          0.684814 -0.65629 0.316723,
+                          0.592374 -0.738306 0.322485,
+                          0.818964 -0.443708 0.363897,
+                          0.754302 -0.54348 0.368317,
+                          0.81044 -0.423962 0.404282,
+                          0.793387 -0.372827 0.481183,
+                          0.754302 -0.54348 0.368317,
+                          0.684814 -0.65629 0.316723,
+                          0.81044 -0.423962 0.404282,
+                          0.781206 -0.398061 0.4809,
+                          0.793387 -0.372827 0.481183,
+                          0.748685 -0.28114 0.600359,
+                          0.781206 -0.398061 0.4809,
+                          0.754302 -0.54348 0.368317,
+                          0.793387 -0.372827 0.481183,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.741656 0.655585 0.141967,
+                          0.739818 0.663394 0.112153,
+                          0.745544 0.652024 0.137942,
+                          0.741656 0.655585 0.141967,
+                          0.745544 0.652024 0.137942,
+                          0.748032 0.649371 0.13699,
+                          0 -0.980732 0.195358,
+                          0 -0.99573 0.0923147,
+                          0 -0.99269 0.120689,
+                          -0.738757 -0.599664 0.307637,
+                          -0.121347 -0.98877 -0.0872316,
+                          -0.276334 -0.951453 -0.135561,
+                          -0.738757 -0.599664 0.307637,
+                          -0.276334 -0.951453 -0.135561,
+                          -0.706904 -0.68535 -0.174878,
+                          -0.0274133 -0.754843 0.655332,
+                          0.0459564 -0.998696 -0.0222177,
+                          0.0459882 -0.998683 -0.0227618,
+                          -0.738757 -0.599664 0.307637,
+                          0.0570737 -0.998123 -0.0221976,
+                          -0.121347 -0.98877 -0.0872316,
+                          -0.738757 -0.599664 0.307637,
+                          -0.0164605 -0.756428 0.653869,
+                          0.0570737 -0.998123 -0.0221976,
+                          -0.132208 -0.865437 0.483259,
+                          -0.0068557 -0.251852 0.967741,
+                          -0.0307821 -0.272028 0.961797,
+                          0.00466106 -0.864682 0.502298,
+                          -0.0068557 -0.251852 0.967741,
+                          -0.132208 -0.865437 0.483259,
+                          -0.221746 -0.861748 0.456311,
+                          -0.0307821 -0.272028 0.961797,
+                          -0.0472913 -0.289131 0.956121,
+                          -0.132208 -0.865437 0.483259,
+                          -0.0307821 -0.272028 0.961797,
+                          -0.221746 -0.861748 0.456311,
+                          -0.221746 -0.861748 0.456311,
+                          -0.0472913 -0.289131 0.956121,
+                          -0.0603381 -0.305279 0.95035,
+                          -0.300271 -0.846691 0.439263,
+                          -0.0603381 -0.305279 0.95035,
+                          -0.0722342 -0.309509 0.948149,
+                          -0.221746 -0.861748 0.456311,
+                          -0.0603381 -0.305279 0.95035,
+                          -0.300271 -0.846691 0.439263,
+                          -0.428616 -0.787288 0.443245,
+                          -0.0722342 -0.309509 0.948149,
+                          -0.115496 -0.294418 0.948672,
+                          -0.300271 -0.846691 0.439263,
+                          -0.0722342 -0.309509 0.948149,
+                          -0.428616 -0.787288 0.443245,
+                          -0.428616 -0.787288 0.443245,
+                          -0.115496 -0.294418 0.948672,
+                          -0.18015 -0.245157 0.952598,
+                          -0.631698 -0.614493 0.472605,
+                          -0.18015 -0.245157 0.952598,
+                          -0.177969 -0.226525 0.957608,
+                          -0.428616 -0.787288 0.443245,
+                          -0.18015 -0.245157 0.952598,
+                          -0.631698 -0.614493 0.472605,
+                          -0.736183 -0.431222 0.521615,
+                          -0.177969 -0.226525 0.957608,
+                          -0.13009 -0.310029 0.941785,
+                          -0.631698 -0.614493 0.472605,
+                          -0.177969 -0.226525 0.957608,
+                          -0.736183 -0.431222 0.521615,
+                          -0.754167 -0.377587 0.537271,
+                          -0.13009 -0.310029 0.941785,
+                          -0.0953415 -0.502923 0.859057,
+                          -0.736183 -0.431222 0.521615,
+                          -0.13009 -0.310029 0.941785,
+                          -0.754167 -0.377587 0.537271,
+                          -0.755709 -0.424939 0.498329,
+                          -0.0953415 -0.502923 0.859057,
+                          -0.0787748 -0.623272 0.778028,
+                          -0.754167 -0.377587 0.537271,
+                          -0.0953415 -0.502923 0.859057,
+                          -0.755709 -0.424939 0.498329,
+                          -0.762599 -0.461076 0.453709,
+                          -0.0787748 -0.623272 0.778028,
+                          -0.0673729 -0.663577 0.745068,
+                          -0.755709 -0.424939 0.498329,
+                          -0.0787748 -0.623272 0.778028,
+                          -0.762599 -0.461076 0.453709,
+                          -0.762599 -0.461076 0.453709,
+                          -0.0673729 -0.663577 0.745068,
+                          -0.0536827 -0.678579 0.732563,
+                          -0.761237 -0.485463 0.429935,
+                          -0.0536827 -0.678579 0.732563,
+                          -0.0164605 -0.756428 0.653869,
+                          -0.762599 -0.461076 0.453709,
+                          -0.0536827 -0.678579 0.732563,
+                          -0.761237 -0.485463 0.429935,
+                          -0.761237 -0.485463 0.429935,
+                          -0.0164605 -0.756428 0.653869,
+                          -0.738757 -0.599664 0.307637 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 91.1828 -11.1017 20.5838,
+                          90.8787 -24.1398 7.07082,
+                          90.7772 -25.5682 3.95586,
+                          84.7701 -25.5834 3.9161,
+                          90.7772 -25.5682 3.95586,
+                          90.8787 -24.1398 7.07082,
+                          91.212 -9.92873 7.83787,
+                          91.1828 -11.1017 20.5838,
+                          90.7772 -25.5682 3.95586,
+                          90.4294 -23.3643 -7.81433,
+                          91.212 -9.92873 7.83787,
+                          90.7772 -25.5682 3.95586,
+                          89.4302 -27.1217 -1.38997,
+                          90.4294 -23.3643 -7.81433,
+                          90.7772 -25.5682 3.95586,
+                          89.8369 -26.9083 -0.386391,
+                          90.7772 -25.5682 3.95586,
+                          84.7701 -25.5834 3.9161,
+                          89.4302 -27.1217 -1.38997,
+                          90.7772 -25.5682 3.95586,
+                          89.8369 -26.9083 -0.386391,
+                          91.1828 -11.1017 20.5838,
+                          90.9711 -22.2772 10.2011,
+                          90.8787 -24.1398 7.07082,
+                          84.7701 -25.5834 3.9161,
+                          90.8787 -24.1398 7.07082,
+                          90.9711 -22.2772 10.2011,
+                          84.9686 -22.2762 10.1937,
+                          90.9711 -22.2772 10.2011,
+                          91.1828 -11.1017 20.5838,
+                          84.7701 -25.5834 3.9161,
+                          90.9711 -22.2772 10.2011,
+                          84.9686 -22.2762 10.1937,
+                          90.4222 4.39823 22.3974,
+                          91.1828 -11.1017 20.5838,
+                          91.212 -9.92873 7.83787,
+                          90.4222 4.39823 22.3974,
+                          91.1384 -6.61546 22.1551,
+                          91.1828 -11.1017 20.5838,
+                          85.1826 -11.0342 20.6174,
+                          91.1828 -11.1017 20.5838,
+                          91.1384 -6.61546 22.1551,
+                          84.9686 -22.2762 10.1937,
+                          91.1828 -11.1017 20.5838,
+                          85.1826 -11.0342 20.6174,
+                          90.4294 -23.3643 -7.81433,
+                          90.8115 -10.5622 -4.34683,
+                          91.212 -9.92873 7.83787,
+                          87.7572 13.4642 4.83948,
+                          91.212 -9.92873 7.83787,
+                          90.8115 -10.5622 -4.34683,
+                          88.1617 14.7853 17.387,
+                          91.212 -9.92873 7.83787,
+                          87.7572 13.4642 4.83948,
+                          88.4225 14.0018 18.0181,
+                          91.212 -9.92873 7.83787,
+                          88.1617 14.7853 17.387,
+                          90.4222 4.39823 22.3974,
+                          91.212 -9.92873 7.83787,
+                          88.4225 14.0018 18.0181,
+                          88.8986 -32.3495 -23.7399,
+                          89.8754 -11.5486 -16.5653,
+                          90.8115 -10.5622 -4.34683,
+                          86.839 11.6499 -7.67597,
+                          90.8115 -10.5622 -4.34683,
+                          89.8754 -11.5486 -16.5653,
+                          89.8083 -25.4728 -15.7739,
+                          88.8986 -32.3495 -23.7399,
+                          90.8115 -10.5622 -4.34683,
+                          90.4294 -23.3643 -7.81433,
+                          89.8083 -25.4728 -15.7739,
+                          90.8115 -10.5622 -4.34683,
+                          87.7572 13.4642 4.83948,
+                          90.8115 -10.5622 -4.34683,
+                          86.839 11.6499 -7.67597,
+                          86.4756 -40.9142 -45.3794,
+                          88.341 -12.7466 -28.5753,
+                          89.8754 -11.5486 -16.5653,
+                          85.2333 9.6033 -19.736,
+                          89.8754 -11.5486 -16.5653,
+                          88.341 -12.7466 -28.5753,
+                          87.9488 -41.2815 -32.1771,
+                          86.4756 -40.9142 -45.3794,
+                          89.8754 -11.5486 -16.5653,
+                          88.8986 -32.3495 -23.7399,
+                          87.9488 -41.2815 -32.1771,
+                          89.8754 -11.5486 -16.5653,
+                          86.839 11.6499 -7.67597,
+                          89.8754 -11.5486 -16.5653,
+                          85.2333 9.6033 -19.736,
+                          83.9304 -40.4018 -57.2687,
+                          86.1521 -14.044 -40.0837,
+                          88.341 -12.7466 -28.5753,
+                          82.8345 7.56881 -30.9977,
+                          88.341 -12.7466 -28.5753,
+                          86.1521 -14.044 -40.0837,
+                          86.4756 -40.9142 -45.3794,
+                          83.9304 -40.4018 -57.2687,
+                          88.341 -12.7466 -28.5753,
+                          85.2333 9.6033 -19.736,
+                          88.341 -12.7466 -28.5753,
+                          82.8345 7.56881 -30.9977,
+                          83.9304 -40.4018 -57.2687,
+                          83.0872 -15.3392 -50.8441,
+                          86.1521 -14.044 -40.0837,
+                          79.814 5.6256 -41.6278,
+                          86.1521 -14.044 -40.0837,
+                          83.0872 -15.3392 -50.8441,
+                          82.8345 7.56881 -30.9977,
+                          86.1521 -14.044 -40.0837,
+                          79.814 5.6256 -41.6278,
+                          79.6454 -39.9116 -67.3708,
+                          78.7358 -16.5162 -60.4894,
+                          83.0872 -15.3392 -50.8441,
+                          76.3177 3.80842 -51.8609,
+                          83.0872 -15.3392 -50.8441,
+                          78.7358 -16.5162 -60.4894,
+                          83.9304 -40.4018 -57.2687,
+                          79.6454 -39.9116 -67.3708,
+                          83.0872 -15.3392 -50.8441,
+                          79.814 5.6256 -41.6278,
+                          83.0872 -15.3392 -50.8441,
+                          76.3177 3.80842 -51.8609,
+                          73.7103 -39.3413 -75.1345,
+                          72.7855 -17.402 -68.3174,
+                          78.7358 -16.5162 -60.4894,
+                          72.1796 2.21302 -61.365,
+                          78.7358 -16.5162 -60.4894,
+                          72.7855 -17.402 -68.3174,
+                          79.6454 -39.9116 -67.3708,
+                          73.7103 -39.3413 -75.1345,
+                          78.7358 -16.5162 -60.4894,
+                          76.3177 3.80842 -51.8609,
+                          78.7358 -16.5162 -60.4894,
+                          72.1796 2.21302 -61.365,
+                          66.5783 -38.5771 -80.1539,
+                          65.2022 -17.7683 -73.5141,
+                          72.7855 -17.402 -68.3174,
+                          68.1994 -7.7649 -70.336,
+                          72.7855 -17.402 -68.3174,
+                          65.2022 -17.7683 -73.5141,
+                          73.7103 -39.3413 -75.1345,
+                          66.5783 -38.5771 -80.1539,
+                          72.7855 -17.402 -68.3174,
+                          72.1179 1.76755 -61.8166,
+                          72.1796 2.21302 -61.365,
+                          72.7855 -17.402 -68.3174,
+                          68.1994 -7.7649 -70.336,
+                          72.1179 1.76755 -61.8166,
+                          72.7855 -17.402 -68.3174,
+                          58.3612 -37.5185 -82.0962,
+                          56.8807 -17.0257 -76.962,
+                          65.2022 -17.7683 -73.5141,
+                          59.2341 -15.2917 -75.8302,
+                          65.2022 -17.7683 -73.5141,
+                          56.8807 -17.0257 -76.962,
+                          66.5783 -38.5771 -80.1539,
+                          58.3612 -37.5185 -82.0962,
+                          65.2022 -17.7683 -73.5141,
+                          59.2341 -15.2917 -75.8302,
+                          68.1994 -7.7649 -70.336,
+                          65.2022 -17.7683 -73.5141,
+                          50.3206 -36.1971 -82.702,
+                          49.4383 -25.4549 -81.9331,
+                          56.8807 -17.0257 -76.962,
+                          44.3963 -21.5523 -79.7514,
+                          56.8807 -17.0257 -76.962,
+                          49.4383 -25.4549 -81.9331,
+                          58.3612 -37.5185 -82.0962,
+                          50.3206 -36.1971 -82.702,
+                          56.8807 -17.0257 -76.962,
+                          48.2214 -15.8809 -76.2161,
+                          59.2341 -15.2917 -75.8302,
+                          56.8807 -17.0257 -76.962,
+                          44.3963 -21.5523 -79.7514,
+                          48.2214 -15.8809 -76.2161,
+                          56.8807 -17.0257 -76.962,
+                          50.3206 -36.1971 -82.702,
+                          45.7587 -33.818 -86.0489,
+                          49.4383 -25.4549 -81.9331,
+                          39.9657 -32.0367 -85.2465,
+                          49.4383 -25.4549 -81.9331,
+                          45.7587 -33.818 -86.0489,
+                          39.9657 -32.0367 -85.2465,
+                          44.3963 -21.5523 -79.7514,
+                          49.4383 -25.4549 -81.9331,
+                          42.5693 -54.8198 -89.7362,
+                          45.7587 -33.818 -86.0489,
+                          50.3206 -36.1971 -82.702,
+                          39.5735 -53.9413 -90.1567,
+                          43.027 -42.4516 -89.6172,
+                          45.7587 -33.818 -86.0489,
+                          37.1274 -41.1665 -89.1289,
+                          45.7587 -33.818 -86.0489,
+                          43.027 -42.4516 -89.6172,
+                          42.5693 -54.8198 -89.7362,
+                          39.5735 -53.9413 -90.1567,
+                          45.7587 -33.818 -86.0489,
+                          39.5998 -33.153 -85.7624,
+                          45.7587 -33.818 -86.0489,
+                          37.1274 -41.1665 -89.1289,
+                          39.9657 -32.0367 -85.2465,
+                          45.7587 -33.818 -86.0489,
+                          39.5998 -33.153 -85.7624,
+                          47.281 -57.3983 -91.8618,
+                          50.3206 -36.1971 -82.702,
+                          58.3612 -37.5185 -82.0962,
+                          47.281 -57.3983 -91.8618,
+                          42.5693 -54.8198 -89.7362,
+                          50.3206 -36.1971 -82.702,
+                          52.9634 -60.331 -94.0116,
+                          58.3612 -37.5185 -82.0962,
+                          66.5783 -38.5771 -80.1539,
+                          52.9634 -60.331 -94.0116,
+                          47.281 -57.3983 -91.8618,
+                          58.3612 -37.5185 -82.0962,
+                          58.6289 -63.4499 -94.3381,
+                          66.5783 -38.5771 -80.1539,
+                          73.7103 -39.3413 -75.1345,
+                          58.6289 -63.4499 -94.3381,
+                          52.9634 -60.331 -94.0116,
+                          66.5783 -38.5771 -80.1539,
+                          64.0555 -66.6094 -92.2522,
+                          73.7103 -39.3413 -75.1345,
+                          79.6454 -39.9116 -67.3708,
+                          64.0555 -66.6094 -92.2522,
+                          58.6289 -63.4499 -94.3381,
+                          73.7103 -39.3413 -75.1345,
+                          69.363 -69.7138 -87.4108,
+                          79.6454 -39.9116 -67.3708,
+                          83.9304 -40.4018 -57.2687,
+                          69.363 -69.7138 -87.4108,
+                          64.0555 -66.6094 -92.2522,
+                          79.6454 -39.9116 -67.3708,
+                          74.7275 -72.7358 -79.6382,
+                          83.9304 -40.4018 -57.2687,
+                          86.4756 -40.9142 -45.3794,
+                          74.7275 -72.7358 -79.6382,
+                          69.363 -69.7138 -87.4108,
+                          83.9304 -40.4018 -57.2687,
+                          87.7666 -43.2505 -33.96,
+                          86.4756 -40.9142 -45.3794,
+                          87.9488 -41.2815 -32.1771,
+                          87.1609 -50.4439 -40.2261,
+                          86.4756 -40.9142 -45.3794,
+                          87.7666 -43.2505 -33.96,
+                          79.7722 -75.652 -69.2597,
+                          74.7275 -72.7358 -79.6382,
+                          86.4756 -40.9142 -45.3794,
+                          83.4032 -77.5938 -56.4482,
+                          79.7722 -75.652 -69.2597,
+                          86.4756 -40.9142 -45.3794,
+                          85.3531 -67.5865 -52.1147,
+                          83.4032 -77.5938 -56.4482,
+                          86.4756 -40.9142 -45.3794,
+                          86.3567 -59.3952 -47.1026,
+                          85.3531 -67.5865 -52.1147,
+                          86.4756 -40.9142 -45.3794,
+                          87.1609 -50.4439 -40.2261,
+                          86.3567 -59.3952 -47.1026,
+                          86.4756 -40.9142 -45.3794,
+                          87.4763 -38.1186 -25.0886,
+                          87.9488 -41.2815 -32.1771,
+                          88.8986 -32.3495 -23.7399,
+                          86.3822 -49.3047 -35.2106,
+                          87.7666 -43.2505 -33.96,
+                          87.9488 -41.2815 -32.1771,
+                          86.3822 -49.3047 -35.2106,
+                          87.9488 -41.2815 -32.1771,
+                          87.4763 -38.1186 -25.0886,
+                          88.6698 -28.1439 -14.4119,
+                          88.8986 -32.3495 -23.7399,
+                          89.8083 -25.4728 -15.7739,
+                          87.4763 -38.1186 -25.0886,
+                          88.8986 -32.3495 -23.7399,
+                          88.6698 -28.1439 -14.4119,
+                          88.6698 -28.1439 -14.4119,
+                          89.8083 -25.4728 -15.7739,
+                          90.4294 -23.3643 -7.81433,
+                          88.6698 -28.1439 -14.4119,
+                          90.4294 -23.3643 -7.81433,
+                          89.4302 -27.1217 -1.38997,
+                          86.3822 -49.3047 -35.2106,
+                          87.1609 -50.4439 -40.2261,
+                          87.7666 -43.2505 -33.96,
+                          40.0166 -41.842 -89.3868,
+                          43.027 -42.4516 -89.6172,
+                          39.5735 -53.9413 -90.1567,
+                          40.0166 -41.842 -89.3868,
+                          37.1274 -41.1665 -89.1289,
+                          43.027 -42.4516 -89.6172,
+                          31.7215 -69.3305 -92.4408,
+                          39.5735 -53.9413 -90.1567,
+                          42.5693 -54.8198 -89.7362,
+                          31.7215 -69.3305 -92.4408,
+                          35.956 -62.5056 -91.0756,
+                          39.5735 -53.9413 -90.1567,
+                          34.8607 -60.4148 -85.2524,
+                          39.5735 -53.9413 -90.1567,
+                          35.956 -62.5056 -91.0756,
+                          35.3414 -52.149 -86.3758,
+                          37.1274 -41.1665 -89.1289,
+                          39.5735 -53.9413 -90.1567,
+                          40.0166 -41.842 -89.3868,
+                          39.5735 -53.9413 -90.1567,
+                          37.1274 -41.1665 -89.1289,
+                          34.8607 -60.4148 -85.2524,
+                          35.3414 -52.149 -86.3758,
+                          39.5735 -53.9413 -90.1567,
+                          33.7346 -73.1845 -93.1132,
+                          42.5693 -54.8198 -89.7362,
+                          47.281 -57.3983 -91.8618,
+                          33.7346 -73.1845 -93.1132,
+                          31.7215 -69.3305 -92.4408,
+                          42.5693 -54.8198 -89.7362,
+                          35.9293 -78.2592 -94.8867,
+                          47.281 -57.3983 -91.8618,
+                          52.9634 -60.331 -94.0116,
+                          35.9293 -78.2592 -94.8867,
+                          33.7346 -73.1845 -93.1132,
+                          47.281 -57.3983 -91.8618,
+                          38.8349 -83.5671 -96.2464,
+                          52.9634 -60.331 -94.0116,
+                          58.6289 -63.4499 -94.3381,
+                          38.8349 -83.5671 -96.2464,
+                          35.9293 -78.2592 -94.8867,
+                          52.9634 -60.331 -94.0116,
+                          42.3384 -88.9786 -95.9525,
+                          58.6289 -63.4499 -94.3381,
+                          64.0555 -66.6094 -92.2522,
+                          42.3384 -88.9786 -95.9525,
+                          38.8349 -83.5671 -96.2464,
+                          58.6289 -63.4499 -94.3381,
+                          46.3755 -94.3776 -92.8388,
+                          64.0555 -66.6094 -92.2522,
+                          69.363 -69.7138 -87.4108,
+                          46.3755 -94.3776 -92.8388,
+                          42.3384 -88.9786 -95.9525,
+                          64.0555 -66.6094 -92.2522,
+                          51.0928 -99.6605 -85.8967,
+                          69.363 -69.7138 -87.4108,
+                          74.7275 -72.7358 -79.6382,
+                          51.0928 -99.6605 -85.8967,
+                          46.3755 -94.3776 -92.8388,
+                          69.363 -69.7138 -87.4108,
+                          56.4788 -104.675 -75.22,
+                          74.7275 -72.7358 -79.6382,
+                          79.7722 -75.652 -69.2597,
+                          56.4788 -104.675 -75.22,
+                          51.0928 -99.6605 -85.8967,
+                          74.7275 -72.7358 -79.6382,
+                          80.8075 -85.6922 -58.7482,
+                          79.7722 -75.652 -69.2597,
+                          83.4032 -77.5938 -56.4482,
+                          73.8246 -97.9811 -60.6827,
+                          79.7722 -75.652 -69.2597,
+                          80.8075 -85.6922 -58.7482,
+                          61.6406 -109.085 -61.3464,
+                          56.4788 -104.675 -75.22,
+                          79.7722 -75.652 -69.2597,
+                          73.8246 -97.9811 -60.6827,
+                          61.6406 -109.085 -61.3464,
+                          79.7722 -75.652 -69.2597,
+                          83.452 -74.163 -51.879,
+                          83.4032 -77.5938 -56.4482,
+                          85.3531 -67.5865 -52.1147,
+                          79.1937 -88.2576 -56.1787,
+                          80.8075 -85.6922 -58.7482,
+                          83.4032 -77.5938 -56.4482,
+                          79.1937 -88.2576 -56.1787,
+                          83.4032 -77.5938 -56.4482,
+                          83.452 -74.163 -51.879,
+                          83.452 -74.163 -51.879,
+                          85.3531 -67.5865 -52.1147,
+                          86.3567 -59.3952 -47.1026,
+                          85.3054 -61.1081 -44.5542,
+                          86.3567 -59.3952 -47.1026,
+                          87.1609 -50.4439 -40.2261,
+                          83.452 -74.163 -51.879,
+                          86.3567 -59.3952 -47.1026,
+                          85.3054 -61.1081 -44.5542,
+                          85.3054 -61.1081 -44.5542,
+                          87.1609 -50.4439 -40.2261,
+                          86.3822 -49.3047 -35.2106,
+                          79.1937 -88.2576 -56.1787,
+                          73.8246 -97.9811 -60.6827,
+                          80.8075 -85.6922 -58.7482,
+                          34.8607 -60.4148 -85.2524,
+                          35.956 -62.5056 -91.0756,
+                          31.7215 -69.3305 -92.4408,
+                          27.7083 -73.7807 -93.821,
+                          31.7215 -69.3305 -92.4408,
+                          33.7346 -73.1845 -93.1132,
+                          31.7378 -67.8747 -86.1999,
+                          31.7215 -69.3305 -92.4408,
+                          27.7083 -73.7807 -93.821,
+                          31.7378 -67.8747 -86.1999,
+                          34.8607 -60.4148 -85.2524,
+                          31.7215 -69.3305 -92.4408,
+                          18.3225 -93.2355 -96.5459,
+                          33.7346 -73.1845 -93.1132,
+                          35.9293 -78.2592 -94.8867,
+                          19.3943 -79.4159 -96.2749,
+                          27.7083 -73.7807 -93.821,
+                          33.7346 -73.1845 -93.1132,
+                          18.8011 -86.6677 -96.2154,
+                          19.3943 -79.4159 -96.2749,
+                          33.7346 -73.1845 -93.1132,
+                          18.3225 -93.2355 -96.5459,
+                          18.8011 -86.6677 -96.2154,
+                          33.7346 -73.1845 -93.1132,
+                          18.2652 -98.8417 -97.114,
+                          35.9293 -78.2592 -94.8867,
+                          38.8349 -83.5671 -96.2464,
+                          18.2652 -98.8417 -97.114,
+                          18.3225 -93.2355 -96.5459,
+                          35.9293 -78.2592 -94.8867,
+                          18.7863 -103.855 -96.6289,
+                          38.8349 -83.5671 -96.2464,
+                          42.3384 -88.9786 -95.9525,
+                          18.7863 -103.855 -96.6289,
+                          18.2652 -98.8417 -97.114,
+                          38.8349 -83.5671 -96.2464,
+                          19.9247 -108.72 -93.4787,
+                          42.3384 -88.9786 -95.9525,
+                          46.3755 -94.3776 -92.8388,
+                          19.9247 -108.72 -93.4787,
+                          18.7863 -103.855 -96.6289,
+                          42.3384 -88.9786 -95.9525,
+                          21.7894 -113.641 -86.6245,
+                          46.3755 -94.3776 -92.8388,
+                          51.0928 -99.6605 -85.8967,
+                          21.7894 -113.641 -86.6245,
+                          19.9247 -108.72 -93.4787,
+                          46.3755 -94.3776 -92.8388,
+                          24.4342 -118.444 -76.2996,
+                          51.0928 -99.6605 -85.8967,
+                          56.4788 -104.675 -75.22,
+                          24.4342 -118.444 -76.2996,
+                          21.7894 -113.641 -86.6245,
+                          51.0928 -99.6605 -85.8967,
+                          40.1509 -119.086 -62.604,
+                          56.4788 -104.675 -75.22,
+                          61.6406 -109.085 -61.3464,
+                          27.4573 -122.932 -63.0118,
+                          24.4342 -118.444 -76.2996,
+                          56.4788 -104.675 -75.22,
+                          28.6146 -122.627 -62.9834,
+                          27.4573 -122.932 -63.0118,
+                          56.4788 -104.675 -75.22,
+                          40.1509 -119.086 -62.604,
+                          28.6146 -122.627 -62.9834,
+                          56.4788 -104.675 -75.22,
+                          73.8246 -97.9811 -60.6827,
+                          62.8945 -108.243 -61.2885,
+                          61.6406 -109.085 -61.3464,
+                          58.5905 -110.79 -58.3922,
+                          61.6406 -109.085 -61.3464,
+                          62.8945 -108.243 -61.2885,
+                          40.1509 -119.086 -62.604,
+                          61.6406 -109.085 -61.3464,
+                          51.7585 -114.462 -61.9369,
+                          58.5905 -110.79 -58.3922,
+                          51.7585 -114.462 -61.9369,
+                          61.6406 -109.085 -61.3464,
+                          70.7732 -101.161 -57.8413,
+                          62.8945 -108.243 -61.2885,
+                          73.8246 -97.9811 -60.6827,
+                          58.5905 -110.79 -58.3922,
+                          62.8945 -108.243 -61.2885,
+                          70.7732 -101.161 -57.8413,
+                          70.7732 -101.161 -57.8413,
+                          73.8246 -97.9811 -60.6827,
+                          79.1937 -88.2576 -56.1787,
+                          44.7133 -117.236 -59.285,
+                          40.1509 -119.086 -62.604,
+                          51.7585 -114.462 -61.9369,
+                          44.7133 -117.236 -59.285,
+                          51.7585 -114.462 -61.9369,
+                          58.5905 -110.79 -58.3922,
+                          24.7788 -74.8717 -88.5231,
+                          27.7083 -73.7807 -93.821,
+                          19.3943 -79.4159 -96.2749,
+                          24.7788 -74.8717 -88.5231,
+                          31.7378 -67.8747 -86.1999,
+                          27.7083 -73.7807 -93.821,
+                          -2.00305e-19 -90.1079 -98.0202,
+                          19.3943 -79.4159 -96.2749,
+                          18.8011 -86.6677 -96.2154,
+                          -2.00022e-19 -83.2754 -98.5674,
+                          10.706 -82.2666 -97.894,
+                          19.3943 -79.4159 -96.2749,
+                          17.993 -78.9474 -90.478,
+                          19.3943 -79.4159 -96.2749,
+                          10.706 -82.2666 -97.894,
+                          -2.00305e-19 -90.1079 -98.0202,
+                          -2.00022e-19 -83.2754 -98.5674,
+                          19.3943 -79.4159 -96.2749,
+                          24.7788 -74.8717 -88.5231,
+                          19.3943 -79.4159 -96.2749,
+                          17.993 -78.9474 -90.478,
+                          -2.00442e-19 -96.0033 -97.6142,
+                          18.8011 -86.6677 -96.2154,
+                          18.3225 -93.2355 -96.5459,
+                          -2.00442e-19 -96.0033 -97.6142,
+                          -2.00305e-19 -90.1079 -98.0202,
+                          18.8011 -86.6677 -96.2154,
+                          -2.0047e-19 -101.049 -97.6115,
+                          18.3225 -93.2355 -96.5459,
+                          18.2652 -98.8417 -97.114,
+                          -2.0047e-19 -101.049 -97.6115,
+                          -2.00442e-19 -96.0033 -97.6142,
+                          18.3225 -93.2355 -96.5459,
+                          -2.00155e-19 -108.945 -97.5863,
+                          18.2652 -98.8417 -97.114,
+                          18.7863 -103.855 -96.6289,
+                          -2.00358e-19 -105.328 -97.881,
+                          -2.0047e-19 -101.049 -97.6115,
+                          18.2652 -98.8417 -97.114,
+                          -2.00155e-19 -108.945 -97.5863,
+                          -2.00358e-19 -105.328 -97.881,
+                          18.2652 -98.8417 -97.114,
+                          -2.00053e-19 -111.928 -96.1331,
+                          18.7863 -103.855 -96.6289,
+                          19.9247 -108.72 -93.4787,
+                          -2.00053e-19 -111.928 -96.1331,
+                          -2.00155e-19 -108.945 -97.5863,
+                          18.7863 -103.855 -96.6289,
+                          -2.0003e-19 -115.94 -91.5473,
+                          19.9247 -108.72 -93.4787,
+                          21.7894 -113.641 -86.6245,
+                          -2.0003e-19 -115.94 -91.5473,
+                          -2.00053e-19 -111.928 -96.1331,
+                          19.9247 -108.72 -93.4787,
+                          -2.00094e-19 -119.646 -84.7014,
+                          21.7894 -113.641 -86.6245,
+                          24.4342 -118.444 -76.2996,
+                          -2.00094e-19 -119.646 -84.7014,
+                          -2.0003e-19 -115.94 -91.5473,
+                          21.7894 -113.641 -86.6245,
+                          -1.99785e-19 -123.318 -75.5385,
+                          24.4342 -118.444 -76.2996,
+                          27.4573 -122.932 -63.0118,
+                          -1.99785e-19 -123.318 -75.5385,
+                          -2.00094e-19 -119.646 -84.7014,
+                          24.4342 -118.444 -76.2996,
+                          15.3595 -125.234 -60.2086,
+                          27.4573 -122.932 -63.0118,
+                          28.6146 -122.627 -62.9834,
+                          -1.99785e-19 -123.318 -75.5385,
+                          27.4573 -122.932 -63.0118,
+                          12.5065 -126.014 -63.3405,
+                          15.3595 -125.234 -60.2086,
+                          12.5065 -126.014 -63.3405,
+                          27.4573 -122.932 -63.0118,
+                          30.2586 -121.947 -59.8529,
+                          28.6146 -122.627 -62.9834,
+                          40.1509 -119.086 -62.604,
+                          15.3595 -125.234 -60.2086,
+                          28.6146 -122.627 -62.9834,
+                          30.2586 -121.947 -59.8529,
+                          30.2586 -121.947 -59.8529,
+                          40.1509 -119.086 -62.604,
+                          44.7133 -117.236 -59.285,
+                          -1.98673e-19 -127.023 -63.6013,
+                          -1.99785e-19 -123.318 -75.5385,
+                          12.5065 -126.014 -63.3405,
+                          0.000557583 -126.624 -60.5453,
+                          -1.98673e-19 -127.023 -63.6013,
+                          12.5065 -126.014 -63.3405,
+                          15.3595 -125.234 -60.2086,
+                          0.000557583 -126.624 -60.5453,
+                          12.5065 -126.014 -63.3405,
+                          9.69967 -81.7047 -92.0062,
+                          10.706 -82.2666 -97.894,
+                          -2.00022e-19 -83.2754 -98.5674,
+                          17.993 -78.9474 -90.478,
+                          10.706 -82.2666 -97.894,
+                          9.69967 -81.7047 -92.0062,
+                          -10.706 -82.2666 -97.894,
+                          -2.00022e-19 -83.2754 -98.5674,
+                          -2.00305e-19 -90.1079 -98.0202,
+                          2.77556e-16 -82.9648 -95.5814,
+                          9.69967 -81.7047 -92.0062,
+                          -2.00022e-19 -83.2754 -98.5674,
+                          -10.706 -82.2666 -97.894,
+                          2.77556e-16 -82.9648 -95.5814,
+                          -2.00022e-19 -83.2754 -98.5674,
+                          -18.8011 -86.6677 -96.2154,
+                          -2.00305e-19 -90.1079 -98.0202,
+                          -2.00442e-19 -96.0033 -97.6142,
+                          -19.3943 -79.4159 -96.2749,
+                          -10.706 -82.2666 -97.894,
+                          -2.00305e-19 -90.1079 -98.0202,
+                          -18.8011 -86.6677 -96.2154,
+                          -19.3943 -79.4159 -96.2749,
+                          -2.00305e-19 -90.1079 -98.0202,
+                          -18.3225 -93.2354 -96.5459,
+                          -2.00442e-19 -96.0033 -97.6142,
+                          -2.0047e-19 -101.049 -97.6115,
+                          -18.3225 -93.2354 -96.5459,
+                          -18.8011 -86.6677 -96.2154,
+                          -2.00442e-19 -96.0033 -97.6142,
+                          -18.3225 -93.2354 -96.5459,
+                          -2.0047e-19 -101.049 -97.6115,
+                          -2.00358e-19 -105.328 -97.881,
+                          -18.2652 -98.8415 -97.114,
+                          -2.00358e-19 -105.328 -97.881,
+                          -2.00155e-19 -108.945 -97.5863,
+                          -18.2652 -98.8415 -97.114,
+                          -18.3225 -93.2354 -96.5459,
+                          -2.00358e-19 -105.328 -97.881,
+                          -18.7862 -103.855 -96.629,
+                          -2.00155e-19 -108.945 -97.5863,
+                          -2.00053e-19 -111.928 -96.1331,
+                          -18.7862 -103.855 -96.629,
+                          -18.2652 -98.8415 -97.114,
+                          -2.00155e-19 -108.945 -97.5863,
+                          -19.9246 -108.72 -93.479,
+                          -2.00053e-19 -111.928 -96.1331,
+                          -2.0003e-19 -115.94 -91.5473,
+                          -19.9246 -108.72 -93.479,
+                          -18.7862 -103.855 -96.629,
+                          -2.00053e-19 -111.928 -96.1331,
+                          -21.7892 -113.64 -86.6252,
+                          -2.0003e-19 -115.94 -91.5473,
+                          -2.00094e-19 -119.646 -84.7014,
+                          -21.7892 -113.64 -86.6252,
+                          -19.9246 -108.72 -93.479,
+                          -2.0003e-19 -115.94 -91.5473,
+                          -24.4339 -118.444 -76.3007,
+                          -2.00094e-19 -119.646 -84.7014,
+                          -1.99785e-19 -123.318 -75.5385,
+                          -24.4339 -118.444 -76.3007,
+                          -21.7892 -113.64 -86.6252,
+                          -2.00094e-19 -119.646 -84.7014,
+                          -24.4339 -118.444 -76.3007,
+                          -1.99785e-19 -123.318 -75.5385,
+                          -1.98673e-19 -127.023 -63.6013,
+                          -12.5181 -126.012 -63.3402,
+                          -24.4339 -118.444 -76.3007,
+                          -1.98673e-19 -127.023 -63.6013,
+                          0.000557583 -126.624 -60.5453,
+                          -12.5181 -126.012 -63.3402,
+                          -1.98673e-19 -127.023 -63.6013,
+                          75.9425 31.2558 0.0167273,
+                          82.6015 22.8777 0.0108459,
+                          79.5135 27.2149 -0.00172324,
+                          86.839 11.6499 -7.67597,
+                          79.5135 27.2149 -0.00172324,
+                          82.6015 22.8777 0.0108459,
+                          75.15 22.8851 0.0180616,
+                          82.6015 22.8777 0.0108459,
+                          75.9425 31.2558 0.0167273,
+                          87.7572 13.4642 4.83948,
+                          86.839 11.6499 -7.67597,
+                          82.6015 22.8777 0.0108459,
+                          85.2522 20.6895 9.71249,
+                          87.7572 13.4642 4.83948,
+                          82.6015 22.8777 0.0108459,
+                          77.0903 21.9541 6.39278,
+                          85.2522 20.6895 9.71249,
+                          82.6015 22.8777 0.0108459,
+                          77.0903 21.9541 6.39278,
+                          82.6015 22.8777 0.0108459,
+                          75.15 22.8851 0.0180616,
+                          86.839 11.6499 -7.67597,
+                          75.9425 31.2558 0.0167273,
+                          79.5135 27.2149 -0.00172324,
+                          86.839 11.6499 -7.67597,
+                          73.8869 28.4742 -14.1408,
+                          75.9425 31.2558 0.0167273,
+                          73.7708 29.0674 6.38373e-05,
+                          75.9425 31.2558 0.0167273,
+                          73.8869 28.4742 -14.1408,
+                          73.7708 29.0674 6.38373e-05,
+                          75.15 22.8851 0.0180616,
+                          75.9425 31.2558 0.0167273,
+                          85.2333 9.6033 -19.736,
+                          72.3695 27.1251 -20.5612,
+                          73.8869 28.4742 -14.1408,
+                          69.6251 23.9516 -13.961,
+                          73.8869 28.4742 -14.1408,
+                          72.3695 27.1251 -20.5612,
+                          86.839 11.6499 -7.67597,
+                          85.2333 9.6033 -19.736,
+                          73.8869 28.4742 -14.1408,
+                          70.7978 25.481 -6.99455,
+                          73.8869 28.4742 -14.1408,
+                          69.6251 23.9516 -13.961,
+                          71.621 26.9192 0.0239417,
+                          73.8869 28.4742 -14.1408,
+                          70.7978 25.481 -6.99455,
+                          73.7708 29.0674 6.38373e-05,
+                          73.8869 28.4742 -14.1408,
+                          71.621 26.9192 0.0239417,
+                          82.8345 7.56881 -30.9977,
+                          70.3928 25.7887 -26.9185,
+                          72.3695 27.1251 -20.5612,
+                          68.0041 22.4187 -20.7042,
+                          72.3695 27.1251 -20.5612,
+                          70.3928 25.7887 -26.9185,
+                          85.2333 9.6033 -19.736,
+                          82.8345 7.56881 -30.9977,
+                          72.3695 27.1251 -20.5612,
+                          69.6251 23.9516 -13.961,
+                          72.3695 27.1251 -20.5612,
+                          68.0041 22.4187 -20.7042,
+                          82.8345 7.56881 -30.9977,
+                          70.5104 19.6444 -38.5684,
+                          70.3928 25.7887 -26.9185,
+                          65.6278 22.0069 -34.3951,
+                          70.3928 25.7887 -26.9185,
+                          70.5104 19.6444 -38.5684,
+                          68.0041 22.4187 -20.7042,
+                          70.3928 25.7887 -26.9185,
+                          65.7963 20.8603 -27.6198,
+                          65.6278 22.0069 -34.3951,
+                          65.7963 20.8603 -27.6198,
+                          70.3928 25.7887 -26.9185,
+                          79.814 5.6256 -41.6278,
+                          71.5142 13.5009 -47.9786,
+                          70.5104 19.6444 -38.5684,
+                          61.0938 18.2203 -40.9315,
+                          70.5104 19.6444 -38.5684,
+                          71.5142 13.5009 -47.9786,
+                          82.8345 7.56881 -30.9977,
+                          79.814 5.6256 -41.6278,
+                          70.5104 19.6444 -38.5684,
+                          65.6278 22.0069 -34.3951,
+                          70.5104 19.6444 -38.5684,
+                          61.0938 18.2203 -40.9315,
+                          76.3177 3.80842 -51.8609,
+                          72.3114 7.49889 -55.6117,
+                          71.5142 13.5009 -47.9786,
+                          63.1233 12.6951 -49.0817,
+                          71.5142 13.5009 -47.9786,
+                          72.3114 7.49889 -55.6117,
+                          79.814 5.6256 -41.6278,
+                          76.3177 3.80842 -51.8609,
+                          71.5142 13.5009 -47.9786,
+                          63.1233 12.6951 -49.0817,
+                          61.0938 18.2203 -40.9315,
+                          71.5142 13.5009 -47.9786,
+                          76.3177 3.80842 -51.8609,
+                          72.1796 2.21302 -61.365,
+                          72.3114 7.49889 -55.6117,
+                          64.442 7.43777 -55.687,
+                          72.3114 7.49889 -55.6117,
+                          72.1796 2.21302 -61.365,
+                          63.1233 12.6951 -49.0817,
+                          72.3114 7.49889 -55.6117,
+                          64.442 7.43777 -55.687,
+                          64.571 2.55538 -61.0149,
+                          72.1796 2.21302 -61.365,
+                          72.1179 1.76755 -61.8166,
+                          64.442 7.43777 -55.687,
+                          72.1796 2.21302 -61.365,
+                          64.571 2.55538 -61.0149,
+                          85.2522 20.6895 9.71249,
+                          88.1617 14.7853 17.387,
+                          87.7572 13.4642 4.83948,
+                          79.7616 18.8276 12.9439,
+                          88.1617 14.7853 17.387,
+                          85.2522 20.6895 9.71249,
+                          82.1698 13.8614 18.1255,
+                          88.4225 14.0018 18.0181,
+                          88.1617 14.7853 17.387,
+                          82.1698 13.8614 18.1255,
+                          88.1617 14.7853 17.387,
+                          79.7616 18.8276 12.9439,
+                          79.7616 18.8276 12.9439,
+                          85.2522 20.6895 9.71249,
+                          77.0903 21.9541 6.39278,
+                          82.4934 12.9299 18.7951,
+                          90.4222 4.39823 22.3974,
+                          88.4225 14.0018 18.0181,
+                          82.4934 12.9299 18.7951,
+                          88.4225 14.0018 18.0181,
+                          82.1698 13.8614 18.1255,
+                          63.83 -0.477376 -64.0104,
+                          72.1179 1.76755 -61.8166,
+                          68.1994 -7.7649 -70.336,
+                          64.571 2.55538 -61.0149,
+                          72.1179 1.76755 -61.8166,
+                          63.83 -0.477376 -64.0104,
+                          56.3423 -8.33011 -70.7719,
+                          68.1994 -7.7649 -70.336,
+                          59.2341 -15.2917 -75.8302,
+                          63.3028 -1.64527 -65.0965,
+                          63.83 -0.477376 -64.0104,
+                          68.1994 -7.7649 -70.336,
+                          60.5688 -4.98799 -68.0502,
+                          63.3028 -1.64527 -65.0965,
+                          68.1994 -7.7649 -70.336,
+                          60.5688 -4.98799 -68.0502,
+                          68.1994 -7.7649 -70.336,
+                          56.3423 -8.33011 -70.7719,
+                          49.088 -14.8461 -75.5286,
+                          59.2341 -15.2917 -75.8302,
+                          48.2214 -15.8809 -76.2161,
+                          56.3423 -8.33011 -70.7719,
+                          59.2341 -15.2917 -75.8302,
+                          49.088 -14.8461 -75.5286,
+                          85.1422 -6.87398 22.0906,
+                          91.1384 -6.61546 22.1551,
+                          90.4222 4.39823 22.3974,
+                          85.1826 -11.0342 20.6174,
+                          91.1384 -6.61546 22.1551,
+                          85.1422 -6.87398 22.0906,
+                          85.1422 -6.87398 22.0906,
+                          90.4222 4.39823 22.3974,
+                          82.4934 12.9299 18.7951,
+                          24.5905 -115.594 -66.9001,
+                          1.4722e-15 -119.532 -67.6938,
+                          3.62406e-17 -122.21 -58.1867,
+                          -24.5905 -115.594 -66.9001,
+                          3.62406e-17 -122.21 -58.1867,
+                          1.4722e-15 -119.532 -67.6938,
+                          22.1237 -119.491 -57.494,
+                          24.5905 -115.594 -66.9001,
+                          3.62406e-17 -122.21 -58.1867,
+                          15.556 -122.704 -58.2577,
+                          22.1237 -119.491 -57.494,
+                          3.62406e-17 -122.21 -58.1867,
+                          -1.69787e-06 -123.17 -58.4278,
+                          15.556 -122.704 -58.2577,
+                          3.62406e-17 -122.21 -58.1867,
+                          -22.1237 -119.491 -57.494,
+                          -1.69787e-06 -123.17 -58.4278,
+                          3.62406e-17 -122.21 -58.1867,
+                          -24.5905 -115.594 -66.9001,
+                          -22.1237 -119.491 -57.494,
+                          3.62406e-17 -122.21 -58.1867,
+                          22.4753 -112.59 -75.1889,
+                          1.36121e-15 -117.035 -75.0798,
+                          1.4722e-15 -119.532 -67.6938,
+                          -24.5905 -115.594 -66.9001,
+                          1.4722e-15 -119.532 -67.6938,
+                          1.36121e-15 -117.035 -75.0798,
+                          24.5905 -115.594 -66.9001,
+                          22.4753 -112.59 -75.1889,
+                          1.4722e-15 -119.532 -67.6938,
+                          22.4753 -112.59 -75.1889,
+                          1.13974e-15 -114.732 -80.8043,
+                          1.36121e-15 -117.035 -75.0798,
+                          -22.4753 -112.59 -75.1889,
+                          1.36121e-15 -117.035 -75.0798,
+                          1.13974e-15 -114.732 -80.8043,
+                          -22.4753 -112.59 -75.1889,
+                          -24.5905 -115.594 -66.9001,
+                          1.36121e-15 -117.035 -75.0798,
+                          20.5773 -109.542 -81.9354,
+                          1.46658e-16 -112.611 -85.2069,
+                          1.13974e-15 -114.732 -80.8043,
+                          -20.5773 -109.542 -81.9354,
+                          1.13974e-15 -114.732 -80.8043,
+                          1.46658e-16 -112.611 -85.2069,
+                          22.4753 -112.59 -75.1889,
+                          20.5773 -109.542 -81.9354,
+                          1.13974e-15 -114.732 -80.8043,
+                          -20.5773 -109.542 -81.9354,
+                          -22.4753 -112.59 -75.1889,
+                          1.13974e-15 -114.732 -80.8043,
+                          19.0581 -106.615 -86.8925,
+                          1.00986e-15 -110.623 -88.5276,
+                          1.46658e-16 -112.611 -85.2069,
+                          -19.0581 -106.615 -86.8925,
+                          1.46658e-16 -112.611 -85.2069,
+                          1.00986e-15 -110.623 -88.5276,
+                          20.5773 -109.542 -81.9354,
+                          19.0581 -106.615 -86.8925,
+                          1.46658e-16 -112.611 -85.2069,
+                          -19.0581 -106.615 -86.8925,
+                          -20.5773 -109.542 -81.9354,
+                          1.46658e-16 -112.611 -85.2069,
+                          18.0558 -104.131 -89.8139,
+                          4.19054e-16 -108.76 -90.8698,
+                          1.00986e-15 -110.623 -88.5276,
+                          -18.0558 -104.131 -89.8139,
+                          1.00986e-15 -110.623 -88.5276,
+                          4.19054e-16 -108.76 -90.8698,
+                          19.0581 -106.615 -86.8925,
+                          18.0558 -104.131 -89.8139,
+                          1.00986e-15 -110.623 -88.5276,
+                          -18.0558 -104.131 -89.8139,
+                          -19.0581 -106.615 -86.8925,
+                          1.00986e-15 -110.623 -88.5276,
+                          17.7571 -102.393 -90.8888,
+                          7.09621e-17 -107.665 -91.6911,
+                          4.19054e-16 -108.76 -90.8698,
+                          -17.7571 -102.393 -90.8888,
+                          4.19054e-16 -108.76 -90.8698,
+                          7.09621e-17 -107.665 -91.6911,
+                          18.0558 -104.131 -89.8139,
+                          17.7571 -102.393 -90.8888,
+                          4.19054e-16 -108.76 -90.8698,
+                          -17.7571 -102.393 -90.8888,
+                          -18.0558 -104.131 -89.8139,
+                          4.19054e-16 -108.76 -90.8698,
+                          18.0121 -100.755 -91.1525,
+                          -3.00061e-17 -106.572 -91.8768,
+                          7.09621e-17 -107.665 -91.6911,
+                          -18.0121 -100.755 -91.1525,
+                          7.09621e-17 -107.665 -91.6911,
+                          -3.00061e-17 -106.572 -91.8768,
+                          17.7571 -102.393 -90.8888,
+                          18.0121 -100.755 -91.1525,
+                          7.09621e-17 -107.665 -91.6911,
+                          -18.0121 -100.755 -91.1525,
+                          -17.7571 -102.393 -90.8888,
+                          7.09621e-17 -107.665 -91.6911,
+                          18.2824 -98.1636 -91.0399,
+                          -1.62188e-17 -105.201 -91.8684,
+                          -3.00061e-17 -106.572 -91.8768,
+                          -18.0121 -100.755 -91.1525,
+                          -3.00061e-17 -106.572 -91.8768,
+                          -1.62188e-17 -105.201 -91.8684,
+                          18.0121 -100.755 -91.1525,
+                          18.2824 -98.1636 -91.0399,
+                          -3.00061e-17 -106.572 -91.8768,
+                          18.2824 -98.1636 -91.0399,
+                          -1.6989e-17 -103.676 -91.7732,
+                          -1.62188e-17 -105.201 -91.8684,
+                          -18.2824 -98.1636 -91.0399,
+                          -1.62188e-17 -105.201 -91.8684,
+                          -1.6989e-17 -103.676 -91.7732,
+                          -18.2824 -98.1636 -91.0399,
+                          -18.0121 -100.755 -91.1525,
+                          -1.62188e-17 -105.201 -91.8684,
+                          18.2544 -94.3054 -90.6195,
+                          -9.23548e-18 -100.011 -91.5669,
+                          -1.6989e-17 -103.676 -91.7732,
+                          -18.2544 -94.3054 -90.6195,
+                          -1.6989e-17 -103.676 -91.7732,
+                          -9.23548e-18 -100.011 -91.5669,
+                          18.2824 -98.1636 -91.0399,
+                          18.2544 -94.3054 -90.6195,
+                          -1.6989e-17 -103.676 -91.7732,
+                          -18.2544 -94.3054 -90.6195,
+                          -18.2824 -98.1636 -91.0399,
+                          -1.6989e-17 -103.676 -91.7732,
+                          17.9817 -89.453 -90.3265,
+                          -3.29226e-19 -95.4089 -91.6329,
+                          -9.23548e-18 -100.011 -91.5669,
+                          -18.2544 -94.3054 -90.6195,
+                          -9.23548e-18 -100.011 -91.5669,
+                          -3.29226e-19 -95.4089 -91.6329,
+                          18.2544 -94.3054 -90.6195,
+                          17.9817 -89.453 -90.3265,
+                          -9.23548e-18 -100.011 -91.5669,
+                          17.9817 -89.453 -90.3265,
+                          2.8314e-18 -91.7573 -91.8692,
+                          -3.29226e-19 -95.4089 -91.6329,
+                          -17.9817 -89.453 -90.3265,
+                          -3.29226e-19 -95.4089 -91.6329,
+                          2.8314e-18 -91.7573 -91.8692,
+                          -17.9817 -89.453 -90.3265,
+                          -18.2544 -94.3054 -90.6195,
+                          -3.29226e-19 -95.4089 -91.6329,
+                          17.8832 -84.3336 -90.3235,
+                          4.63242e-18 -87.5519 -92.2078,
+                          2.8314e-18 -91.7573 -91.8692,
+                          -17.8832 -84.3336 -90.3235,
+                          2.8314e-18 -91.7573 -91.8692,
+                          4.63242e-18 -87.5519 -92.2078,
+                          17.9817 -89.453 -90.3265,
+                          17.8832 -84.3336 -90.3235,
+                          2.8314e-18 -91.7573 -91.8692,
+                          -17.8832 -84.3336 -90.3235,
+                          -17.9817 -89.453 -90.3265,
+                          2.8314e-18 -91.7573 -91.8692,
+                          9.69967 -81.7047 -92.0062,
+                          8.53459e-18 -82.6541 -92.5955,
+                          4.63242e-18 -87.5519 -92.2078,
+                          -17.993 -78.9474 -90.478,
+                          4.63242e-18 -87.5519 -92.2078,
+                          8.53459e-18 -82.6541 -92.5955,
+                          17.993 -78.9474 -90.478,
+                          9.69967 -81.7047 -92.0062,
+                          4.63242e-18 -87.5519 -92.2078,
+                          17.8832 -84.3336 -90.3235,
+                          17.993 -78.9474 -90.478,
+                          4.63242e-18 -87.5519 -92.2078,
+                          -17.993 -78.9474 -90.478,
+                          -17.8832 -84.3336 -90.3235,
+                          4.63242e-18 -87.5519 -92.2078,
+                          2.77556e-16 -82.9648 -95.5814,
+                          8.53459e-18 -82.6541 -92.5955,
+                          9.69967 -81.7047 -92.0062,
+                          -10.706 -82.2666 -97.894,
+                          8.53459e-18 -82.6541 -92.5955,
+                          2.77556e-16 -82.9648 -95.5814,
+                          -9.69967 -81.7047 -92.0062,
+                          8.53459e-18 -82.6541 -92.5955,
+                          -10.706 -82.2666 -97.894,
+                          -9.69967 -81.7047 -92.0062,
+                          -17.993 -78.9474 -90.478,
+                          8.53459e-18 -82.6541 -92.5955,
+                          24.7788 -74.8717 -88.5231,
+                          17.993 -78.9474 -90.478,
+                          17.8832 -84.3336 -90.3235,
+                          33.6553 -73.2901 -86.8743,
+                          17.8832 -84.3336 -90.3235,
+                          17.9817 -89.453 -90.3265,
+                          31.7378 -67.8747 -86.1999,
+                          17.8832 -84.3336 -90.3235,
+                          33.6553 -73.2901 -86.8743,
+                          24.7788 -74.8717 -88.5231,
+                          17.8832 -84.3336 -90.3235,
+                          31.7378 -67.8747 -86.1999,
+                          35.6577 -76.9085 -88.0756,
+                          17.9817 -89.453 -90.3265,
+                          18.2544 -94.3054 -90.6195,
+                          33.6553 -73.2901 -86.8743,
+                          17.9817 -89.453 -90.3265,
+                          35.6577 -76.9085 -88.0756,
+                          37.3473 -80.187 -89.2781,
+                          18.2544 -94.3054 -90.6195,
+                          18.2824 -98.1636 -91.0399,
+                          35.6577 -76.9085 -88.0756,
+                          18.2544 -94.3054 -90.6195,
+                          37.3473 -80.187 -89.2781,
+                          38.9063 -83.1874 -90.1189,
+                          18.2824 -98.1636 -91.0399,
+                          18.0121 -100.755 -91.1525,
+                          37.3473 -80.187 -89.2781,
+                          18.2824 -98.1636 -91.0399,
+                          38.9063 -83.1874 -90.1189,
+                          40.4239 -85.8467 -90.3915,
+                          18.0121 -100.755 -91.1525,
+                          17.7571 -102.393 -90.8888,
+                          38.9063 -83.1874 -90.1189,
+                          18.0121 -100.755 -91.1525,
+                          40.4239 -85.8467 -90.3915,
+                          42.0282 -88.2063 -89.9868,
+                          17.7571 -102.393 -90.8888,
+                          18.0558 -104.131 -89.8139,
+                          40.4239 -85.8467 -90.3915,
+                          17.7571 -102.393 -90.8888,
+                          42.0282 -88.2063 -89.9868,
+                          43.9521 -90.5427 -88.6597,
+                          18.0558 -104.131 -89.8139,
+                          19.0581 -106.615 -86.8925,
+                          42.0282 -88.2063 -89.9868,
+                          18.0558 -104.131 -89.8139,
+                          43.9521 -90.5427 -88.6597,
+                          46.4432 -93.2208 -85.7597,
+                          19.0581 -106.615 -86.8925,
+                          20.5773 -109.542 -81.9354,
+                          43.9521 -90.5427 -88.6597,
+                          19.0581 -106.615 -86.8925,
+                          46.4432 -93.2208 -85.7597,
+                          49.531 -96.2805 -80.8226,
+                          20.5773 -109.542 -81.9354,
+                          22.4753 -112.59 -75.1889,
+                          46.4432 -93.2208 -85.7597,
+                          20.5773 -109.542 -81.9354,
+                          49.531 -96.2805 -80.8226,
+                          52.9618 -99.45 -73.9676,
+                          22.4753 -112.59 -75.1889,
+                          24.5905 -115.594 -66.9001,
+                          49.531 -96.2805 -80.8226,
+                          22.4753 -112.59 -75.1889,
+                          52.9618 -99.45 -73.9676,
+                          22.1237 -119.491 -57.494,
+                          27.6932 -118.166 -57.2915,
+                          24.5905 -115.594 -66.9001,
+                          56.2714 -102.551 -65.4601,
+                          24.5905 -115.594 -66.9001,
+                          27.6932 -118.166 -57.2915,
+                          52.9618 -99.45 -73.9676,
+                          24.5905 -115.594 -66.9001,
+                          56.2714 -102.551 -65.4601,
+                          28.7224 -119.862 -57.8594,
+                          27.6932 -118.166 -57.2915,
+                          22.1237 -119.491 -57.494,
+                          44.2698 -112.811 -56.5102,
+                          56.2714 -102.551 -65.4601,
+                          27.6932 -118.166 -57.2915,
+                          39.0762 -116.74 -57.4523,
+                          44.2698 -112.811 -56.5102,
+                          27.6932 -118.166 -57.2915,
+                          28.7224 -119.862 -57.8594,
+                          39.0762 -116.74 -57.4523,
+                          27.6932 -118.166 -57.2915,
+                          15.556 -122.704 -58.2577,
+                          28.7224 -119.862 -57.8594,
+                          22.1237 -119.491 -57.494,
+                          41.9923 -55.5627 -83.6099,
+                          39.5998 -33.153 -85.7624,
+                          37.1274 -41.1665 -89.1289,
+                          35.3414 -52.149 -86.3758,
+                          41.9923 -55.5627 -83.6099,
+                          37.1274 -41.1665 -89.1289,
+                          41.9923 -55.5627 -83.6099,
+                          45.1784 -36.8854 -78.3925,
+                          39.5998 -33.153 -85.7624,
+                          39.9657 -32.0367 -85.2465,
+                          39.5998 -33.153 -85.7624,
+                          45.1784 -36.8854 -78.3925,
+                          46.243 -58.0356 -85.0329,
+                          52.2972 -39.5808 -77.0931,
+                          45.1784 -36.8854 -78.3925,
+                          55.0268 -17.5531 -71.2585,
+                          45.1784 -36.8854 -78.3925,
+                          52.2972 -39.5808 -77.0931,
+                          41.9923 -55.5627 -83.6099,
+                          46.243 -58.0356 -85.0329,
+                          45.1784 -36.8854 -78.3925,
+                          48.2214 -15.8809 -76.2161,
+                          45.1784 -36.8854 -78.3925,
+                          55.0268 -17.5531 -71.2585,
+                          44.3963 -21.5523 -79.7514,
+                          45.1784 -36.8854 -78.3925,
+                          48.2214 -15.8809 -76.2161,
+                          39.9657 -32.0367 -85.2465,
+                          45.1784 -36.8854 -78.3925,
+                          44.3963 -21.5523 -79.7514,
+                          49.8669 -60.0696 -86.7919,
+                          58.236 -41.0221 -77.045,
+                          52.2972 -39.5808 -77.0931,
+                          61.1415 -18.4675 -68.8265,
+                          52.2972 -39.5808 -77.0931,
+                          58.236 -41.0221 -77.045,
+                          46.243 -58.0356 -85.0329,
+                          49.8669 -60.0696 -86.7919,
+                          52.2972 -39.5808 -77.0931,
+                          55.0268 -17.5531 -71.2585,
+                          52.2972 -39.5808 -77.0931,
+                          61.1415 -18.4675 -68.8265,
+                          53.2414 -61.9632 -88.1436,
+                          62.9073 -41.6561 -76.1863,
+                          58.236 -41.0221 -77.045,
+                          65.7443 -18.5761 -66.5004,
+                          58.236 -41.0221 -77.045,
+                          62.9073 -41.6561 -76.1863,
+                          49.8669 -60.0696 -86.7919,
+                          53.2414 -61.9632 -88.1436,
+                          58.236 -41.0221 -77.045,
+                          61.1415 -18.4675 -68.8265,
+                          58.236 -41.0221 -77.045,
+                          65.7443 -18.5761 -66.5004,
+                          56.0539 -63.6465 -88.6673,
+                          66.8623 -41.7409 -73.9893,
+                          62.9073 -41.6561 -76.1863,
+                          69.6392 -18.2155 -63.0108,
+                          62.9073 -41.6561 -76.1863,
+                          66.8623 -41.7409 -73.9893,
+                          53.2414 -61.9632 -88.1436,
+                          56.0539 -63.6465 -88.6673,
+                          62.9073 -41.6561 -76.1863,
+                          65.7443 -18.5761 -66.5004,
+                          62.9073 -41.6561 -76.1863,
+                          69.6392 -18.2155 -63.0108,
+                          58.5657 -65.2067 -88.389,
+                          70.4854 -41.52 -70.4956,
+                          66.8623 -41.7409 -73.9893,
+                          73.1248 -17.5605 -58.1736,
+                          66.8623 -41.7409 -73.9893,
+                          70.4854 -41.52 -70.4956,
+                          56.0539 -63.6465 -88.6673,
+                          58.5657 -65.2067 -88.389,
+                          66.8623 -41.7409 -73.9893,
+                          69.6392 -18.2155 -63.0108,
+                          66.8623 -41.7409 -73.9893,
+                          73.1248 -17.5605 -58.1736,
+                          61.0857 -66.7328 -87.254,
+                          73.7985 -41.2068 -65.6967,
+                          70.4854 -41.52 -70.4956,
+                          76.0787 -16.6922 -52.2069,
+                          70.4854 -41.52 -70.4956,
+                          73.7985 -41.2068 -65.6967,
+                          58.5657 -65.2067 -88.389,
+                          61.0857 -66.7328 -87.254,
+                          70.4854 -41.52 -70.4956,
+                          73.1248 -17.5605 -58.1736,
+                          70.4854 -41.52 -70.4956,
+                          76.0787 -16.6922 -52.2069,
+                          67.0177 -70.0946 -81.085,
+                          76.6379 -40.9733 -59.6071,
+                          73.7985 -41.2068 -65.6967,
+                          78.4852 -15.6852 -45.4213,
+                          73.7985 -41.2068 -65.6967,
+                          76.6379 -40.9733 -59.6071,
+                          63.8709 -68.3318 -84.9482,
+                          67.0177 -70.0946 -81.085,
+                          73.7985 -41.2068 -65.6967,
+                          61.0857 -66.7328 -87.254,
+                          63.8709 -68.3318 -84.9482,
+                          73.7985 -41.2068 -65.6967,
+                          76.0787 -16.6922 -52.2069,
+                          73.7985 -41.2068 -65.6967,
+                          78.4852 -15.6852 -45.4213,
+                          70.4008 -72.0222 -75.569,
+                          78.8419 -40.9004 -52.3734,
+                          76.6379 -40.9733 -59.6071,
+                          80.4022 -14.5971 -38.084,
+                          76.6379 -40.9733 -59.6071,
+                          78.8419 -40.9004 -52.3734,
+                          67.0177 -70.0946 -81.085,
+                          70.4008 -72.0222 -75.569,
+                          76.6379 -40.9733 -59.6071,
+                          78.4852 -15.6852 -45.4213,
+                          76.6379 -40.9733 -59.6071,
+                          80.4022 -14.5971 -38.084,
+                          73.6249 -74.0094 -68.5997,
+                          80.4095 -40.9972 -44.2169,
+                          78.8419 -40.9004 -52.3734,
+                          81.9484 -13.5067 -30.3309,
+                          78.8419 -40.9004 -52.3734,
+                          80.4095 -40.9972 -44.2169,
+                          70.4008 -72.0222 -75.569,
+                          73.6249 -74.0094 -68.5997,
+                          78.8419 -40.9004 -52.3734,
+                          80.4022 -14.5971 -38.084,
+                          78.8419 -40.9004 -52.3734,
+                          81.9484 -13.5067 -30.3309,
+                          76.1748 -75.991 -60.402,
+                          81.5229 -41.2467 -35.3653,
+                          80.4095 -40.9972 -44.2169,
+                          83.1786 -12.4784 -22.2484,
+                          80.4095 -40.9972 -44.2169,
+                          81.5229 -41.2467 -35.3653,
+                          73.6249 -74.0094 -68.5997,
+                          76.1748 -75.991 -60.402,
+                          80.4095 -40.9972 -44.2169,
+                          81.9484 -13.5067 -30.3309,
+                          80.4095 -40.9972 -44.2169,
+                          83.1786 -12.4784 -22.2484,
+                          81.9716 -46.0203 -30.1533,
+                          82.462 -41.1476 -25.7626,
+                          81.5229 -41.2467 -35.3653,
+                          84.1036 -11.5665 -13.9099,
+                          81.5229 -41.2467 -35.3653,
+                          82.462 -41.1476 -25.7626,
+                          80.4399 -61.5193 -42.7474,
+                          81.9716 -46.0203 -30.1533,
+                          81.5229 -41.2467 -35.3653,
+                          78.024 -76.7293 -50.9165,
+                          80.4399 -61.5193 -42.7474,
+                          81.5229 -41.2467 -35.3653,
+                          76.1748 -75.991 -60.402,
+                          78.024 -76.7293 -50.9165,
+                          81.5229 -41.2467 -35.3653,
+                          83.1786 -12.4784 -22.2484,
+                          81.5229 -41.2467 -35.3653,
+                          84.1036 -11.5665 -13.9099,
+                          84.1279 -44.1536 -28.6746,
+                          82.462 -41.1476 -25.7626,
+                          81.9716 -46.0203 -30.1533,
+                          83.028 -35.8509 -20.8458,
+                          84.1036 -11.5665 -13.9099,
+                          82.462 -41.1476 -25.7626,
+                          84.7147 -38.5178 -23.5099,
+                          83.028 -35.8509 -20.8458,
+                          82.462 -41.1476 -25.7626,
+                          84.1279 -44.1536 -28.6746,
+                          84.7147 -38.5178 -23.5099,
+                          82.462 -41.1476 -25.7626,
+                          83.4598 -51.0009 -34.7052,
+                          81.9716 -46.0203 -30.1533,
+                          80.4399 -61.5193 -42.7474,
+                          83.4598 -51.0009 -34.7052,
+                          84.1279 -44.1536 -28.6746,
+                          81.9716 -46.0203 -30.1533,
+                          81.2982 -70.3859 -48.3536,
+                          80.4399 -61.5193 -42.7474,
+                          78.024 -76.7293 -50.9165,
+                          82.6625 -59.4094 -41.4595,
+                          83.4598 -51.0009 -34.7052,
+                          80.4399 -61.5193 -42.7474,
+                          81.2982 -70.3859 -48.3536,
+                          82.6625 -59.4094 -41.4595,
+                          80.4399 -61.5193 -42.7474,
+                          74.882 -86.4868 -53.7165,
+                          78.024 -76.7293 -50.9165,
+                          76.1748 -75.991 -60.402,
+                          78.2846 -83.1694 -53.2803,
+                          78.024 -76.7293 -50.9165,
+                          74.882 -86.4868 -53.7165,
+                          78.2846 -83.1694 -53.2803,
+                          81.2982 -70.3859 -48.3536,
+                          78.024 -76.7293 -50.9165,
+                          56.2714 -102.551 -65.4601,
+                          76.1748 -75.991 -60.402,
+                          73.6249 -74.0094 -68.5997,
+                          68.1811 -97.3419 -55.108,
+                          74.882 -86.4868 -53.7165,
+                          76.1748 -75.991 -60.402,
+                          60.4168 -104.417 -55.4429,
+                          68.1811 -97.3419 -55.108,
+                          76.1748 -75.991 -60.402,
+                          58.8356 -105.508 -55.5005,
+                          60.4168 -104.417 -55.4429,
+                          76.1748 -75.991 -60.402,
+                          56.2714 -102.551 -65.4601,
+                          58.8356 -105.508 -55.5005,
+                          76.1748 -75.991 -60.402,
+                          52.9618 -99.45 -73.9676,
+                          73.6249 -74.0094 -68.5997,
+                          70.4008 -72.0222 -75.569,
+                          52.9618 -99.45 -73.9676,
+                          56.2714 -102.551 -65.4601,
+                          73.6249 -74.0094 -68.5997,
+                          49.531 -96.2805 -80.8226,
+                          70.4008 -72.0222 -75.569,
+                          67.0177 -70.0946 -81.085,
+                          49.531 -96.2805 -80.8226,
+                          52.9618 -99.45 -73.9676,
+                          70.4008 -72.0222 -75.569,
+                          46.4432 -93.2208 -85.7597,
+                          67.0177 -70.0946 -81.085,
+                          63.8709 -68.3318 -84.9482,
+                          46.4432 -93.2208 -85.7597,
+                          49.531 -96.2805 -80.8226,
+                          67.0177 -70.0946 -81.085,
+                          43.9521 -90.5427 -88.6597,
+                          63.8709 -68.3318 -84.9482,
+                          61.0857 -66.7328 -87.254,
+                          43.9521 -90.5427 -88.6597,
+                          46.4432 -93.2208 -85.7597,
+                          63.8709 -68.3318 -84.9482,
+                          42.0282 -88.2063 -89.9868,
+                          61.0857 -66.7328 -87.254,
+                          58.5657 -65.2067 -88.389,
+                          42.0282 -88.2063 -89.9868,
+                          43.9521 -90.5427 -88.6597,
+                          61.0857 -66.7328 -87.254,
+                          40.4239 -85.8467 -90.3915,
+                          58.5657 -65.2067 -88.389,
+                          56.0539 -63.6465 -88.6673,
+                          40.4239 -85.8467 -90.3915,
+                          42.0282 -88.2063 -89.9868,
+                          58.5657 -65.2067 -88.389,
+                          38.9063 -83.1874 -90.1189,
+                          56.0539 -63.6465 -88.6673,
+                          53.2414 -61.9632 -88.1436,
+                          38.9063 -83.1874 -90.1189,
+                          40.4239 -85.8467 -90.3915,
+                          56.0539 -63.6465 -88.6673,
+                          37.3473 -80.187 -89.2781,
+                          53.2414 -61.9632 -88.1436,
+                          49.8669 -60.0696 -86.7919,
+                          37.3473 -80.187 -89.2781,
+                          38.9063 -83.1874 -90.1189,
+                          53.2414 -61.9632 -88.1436,
+                          35.6577 -76.9085 -88.0756,
+                          49.8669 -60.0696 -86.7919,
+                          46.243 -58.0356 -85.0329,
+                          35.6577 -76.9085 -88.0756,
+                          37.3473 -80.187 -89.2781,
+                          49.8669 -60.0696 -86.7919,
+                          33.6553 -73.2901 -86.8743,
+                          46.243 -58.0356 -85.0329,
+                          41.9923 -55.5627 -83.6099,
+                          33.6553 -73.2901 -86.8743,
+                          35.6577 -76.9085 -88.0756,
+                          46.243 -58.0356 -85.0329,
+                          31.7378 -67.8747 -86.1999,
+                          41.9923 -55.5627 -83.6099,
+                          35.3414 -52.149 -86.3758,
+                          31.7378 -67.8747 -86.1999,
+                          33.6553 -73.2901 -86.8743,
+                          41.9923 -55.5627 -83.6099,
+                          31.7378 -67.8747 -86.1999,
+                          35.3414 -52.149 -86.3758,
+                          34.8607 -60.4148 -85.2524,
+                          73.0065 -94.1882 -55.3192,
+                          74.882 -86.4868 -53.7165,
+                          68.1811 -97.3419 -55.108,
+                          73.0065 -94.1882 -55.3192,
+                          78.2846 -83.1694 -53.2803,
+                          74.882 -86.4868 -53.7165,
+                          66.4493 -101.975 -55.9198,
+                          68.1811 -97.3419 -55.108,
+                          60.4168 -104.417 -55.4429,
+                          66.4493 -101.975 -55.9198,
+                          73.0065 -94.1882 -55.3192,
+                          68.1811 -97.3419 -55.108,
+                          60.0026 -107.073 -56.1533,
+                          60.4168 -104.417 -55.4429,
+                          58.8356 -105.508 -55.5005,
+                          60.0026 -107.073 -56.1533,
+                          66.4493 -101.975 -55.9198,
+                          60.4168 -104.417 -55.4429,
+                          51.5498 -109.626 -55.9698,
+                          58.8356 -105.508 -55.5005,
+                          56.2714 -102.551 -65.4601,
+                          53.7915 -110.656 -56.5131,
+                          58.8356 -105.508 -55.5005,
+                          51.5498 -109.626 -55.9698,
+                          53.7915 -110.656 -56.5131,
+                          60.0026 -107.073 -56.1533,
+                          58.8356 -105.508 -55.5005,
+                          44.2698 -112.811 -56.5102,
+                          51.5498 -109.626 -55.9698,
+                          56.2714 -102.551 -65.4601,
+                          47.1155 -113.7 -57.0145,
+                          51.5498 -109.626 -55.9698,
+                          44.2698 -112.811 -56.5102,
+                          47.1155 -113.7 -57.0145,
+                          53.7915 -110.656 -56.5131,
+                          51.5498 -109.626 -55.9698,
+                          39.0762 -116.74 -57.4523,
+                          47.1155 -113.7 -57.0145,
+                          44.2698 -112.811 -56.5102,
+                          75.0726 3.01852 -38.7925,
+                          63.3942 19.4491 -34.3132,
+                          61.0938 18.2203 -40.9315,
+                          65.6278 22.0069 -34.3951,
+                          61.0938 18.2203 -40.9315,
+                          63.3942 19.4491 -34.3132,
+                          72.7221 1.68912 -46.0158,
+                          75.0726 3.01852 -38.7925,
+                          61.0938 18.2203 -40.9315,
+                          63.1233 12.6951 -49.0817,
+                          72.7221 1.68912 -46.0158,
+                          61.0938 18.2203 -40.9315,
+                          77.1269 4.51132 -31.4254,
+                          65.7963 20.8603 -27.6198,
+                          63.3942 19.4491 -34.3132,
+                          65.6278 22.0069 -34.3951,
+                          63.3942 19.4491 -34.3132,
+                          65.7963 20.8603 -27.6198,
+                          75.0726 3.01852 -38.7925,
+                          77.1269 4.51132 -31.4254,
+                          63.3942 19.4491 -34.3132,
+                          78.865 6.10312 -23.8613,
+                          68.0041 22.4187 -20.7042,
+                          65.7963 20.8603 -27.6198,
+                          77.1269 4.51132 -31.4254,
+                          78.865 6.10312 -23.8613,
+                          65.7963 20.8603 -27.6198,
+                          80.2264 7.73506 -15.9558,
+                          69.6251 23.9516 -13.961,
+                          68.0041 22.4187 -20.7042,
+                          78.865 6.10312 -23.8613,
+                          80.2264 7.73506 -15.9558,
+                          68.0041 22.4187 -20.7042,
+                          81.2174 9.33985 -7.60365,
+                          70.7978 25.481 -6.99455,
+                          69.6251 23.9516 -13.961,
+                          80.2264 7.73506 -15.9558,
+                          81.2174 9.33985 -7.60365,
+                          69.6251 23.9516 -13.961,
+                          81.2174 9.33985 -7.60365,
+                          71.621 26.9192 0.0239417,
+                          70.7978 25.481 -6.99455,
+                          81.2174 9.33985 -7.60365,
+                          73.4649 24.9236 -0.00261418,
+                          71.621 26.9192 0.0239417,
+                          73.7708 29.0674 6.38373e-05,
+                          71.621 26.9192 0.0239417,
+                          73.4649 24.9236 -0.00261418,
+                          81.2174 9.33985 -7.60365,
+                          75.15 22.8851 0.0180616,
+                          73.4649 24.9236 -0.00261418,
+                          73.7708 29.0674 6.38373e-05,
+                          73.4649 24.9236 -0.00261418,
+                          75.15 22.8851 0.0180616,
+                          81.882 10.8256 1.05018,
+                          77.0903 21.9541 6.39278,
+                          75.15 22.8851 0.0180616,
+                          81.2174 9.33985 -7.60365,
+                          81.882 10.8256 1.05018,
+                          75.15 22.8851 0.0180616,
+                          82.282 12.0573 9.79247,
+                          79.7616 18.8276 12.9439,
+                          77.0903 21.9541 6.39278,
+                          81.882 10.8256 1.05018,
+                          82.282 12.0573 9.79247,
+                          77.0903 21.9541 6.39278,
+                          82.4934 12.9299 18.7951,
+                          82.1698 13.8614 18.1255,
+                          79.7616 18.8276 12.9439,
+                          82.282 12.0573 9.79247,
+                          82.4934 12.9299 18.7951,
+                          79.7616 18.8276 12.9439,
+                          85.2494 -9.87472 11.517,
+                          82.4934 12.9299 18.7951,
+                          82.282 12.0573 9.79247,
+                          85.1826 -11.0342 20.6174,
+                          85.1422 -6.87398 22.0906,
+                          82.4934 12.9299 18.7951,
+                          85.2494 -9.87472 11.517,
+                          85.1826 -11.0342 20.6174,
+                          82.4934 12.9299 18.7951,
+                          85.1099 -10.2225 3.06012,
+                          82.282 12.0573 9.79247,
+                          81.882 10.8256 1.05018,
+                          85.1099 -10.2225 3.06012,
+                          85.2494 -9.87472 11.517,
+                          82.282 12.0573 9.79247,
+                          84.741 -10.801 -5.44172,
+                          81.882 10.8256 1.05018,
+                          81.2174 9.33985 -7.60365,
+                          84.741 -10.801 -5.44172,
+                          85.1099 -10.2225 3.06012,
+                          81.882 10.8256 1.05018,
+                          84.1036 -11.5665 -13.9099,
+                          81.2174 9.33985 -7.60365,
+                          80.2264 7.73506 -15.9558,
+                          84.1036 -11.5665 -13.9099,
+                          84.741 -10.801 -5.44172,
+                          81.2174 9.33985 -7.60365,
+                          83.1786 -12.4784 -22.2484,
+                          80.2264 7.73506 -15.9558,
+                          78.865 6.10312 -23.8613,
+                          83.1786 -12.4784 -22.2484,
+                          84.1036 -11.5665 -13.9099,
+                          80.2264 7.73506 -15.9558,
+                          81.9484 -13.5067 -30.3309,
+                          78.865 6.10312 -23.8613,
+                          77.1269 4.51132 -31.4254,
+                          81.9484 -13.5067 -30.3309,
+                          83.1786 -12.4784 -22.2484,
+                          78.865 6.10312 -23.8613,
+                          80.4022 -14.5971 -38.084,
+                          77.1269 4.51132 -31.4254,
+                          75.0726 3.01852 -38.7925,
+                          80.4022 -14.5971 -38.084,
+                          81.9484 -13.5067 -30.3309,
+                          77.1269 4.51132 -31.4254,
+                          78.4852 -15.6852 -45.4213,
+                          75.0726 3.01852 -38.7925,
+                          72.7221 1.68912 -46.0158,
+                          78.4852 -15.6852 -45.4213,
+                          80.4022 -14.5971 -38.084,
+                          75.0726 3.01852 -38.7925,
+                          63.1233 12.6951 -49.0817,
+                          70.0791 0.597946 -52.9116,
+                          72.7221 1.68912 -46.0158,
+                          76.0787 -16.6922 -52.2069,
+                          72.7221 1.68912 -46.0158,
+                          70.0791 0.597946 -52.9116,
+                          76.0787 -16.6922 -52.2069,
+                          78.4852 -15.6852 -45.4213,
+                          72.7221 1.68912 -46.0158,
+                          64.442 7.43777 -55.687,
+                          67.0917 -0.152173 -59.068,
+                          70.0791 0.597946 -52.9116,
+                          73.1248 -17.5605 -58.1736,
+                          70.0791 0.597946 -52.9116,
+                          67.0917 -0.152173 -59.068,
+                          63.1233 12.6951 -49.0817,
+                          64.442 7.43777 -55.687,
+                          70.0791 0.597946 -52.9116,
+                          73.1248 -17.5605 -58.1736,
+                          76.0787 -16.6922 -52.2069,
+                          70.0791 0.597946 -52.9116,
+                          64.571 2.55538 -61.0149,
+                          63.83 -0.477376 -64.0104,
+                          67.0917 -0.152173 -59.068,
+                          69.6392 -18.2155 -63.0108,
+                          67.0917 -0.152173 -59.068,
+                          63.83 -0.477376 -64.0104,
+                          64.442 7.43777 -55.687,
+                          64.571 2.55538 -61.0149,
+                          67.0917 -0.152173 -59.068,
+                          69.6392 -18.2155 -63.0108,
+                          73.1248 -17.5605 -58.1736,
+                          67.0917 -0.152173 -59.068,
+                          65.7443 -18.5761 -66.5004,
+                          63.83 -0.477376 -64.0104,
+                          63.3028 -1.64527 -65.0965,
+                          65.7443 -18.5761 -66.5004,
+                          69.6392 -18.2155 -63.0108,
+                          63.83 -0.477376 -64.0104,
+                          61.1415 -18.4675 -68.8265,
+                          65.7443 -18.5761 -66.5004,
+                          63.3028 -1.64527 -65.0965,
+                          60.5688 -4.98799 -68.0502,
+                          61.1415 -18.4675 -68.8265,
+                          63.3028 -1.64527 -65.0965,
+                          84.9686 -22.2762 10.1937,
+                          85.1826 -11.0342 20.6174,
+                          85.2494 -9.87472 11.517,
+                          84.7701 -25.5834 3.9161,
+                          85.2494 -9.87472 11.517,
+                          85.1099 -10.2225 3.06012,
+                          84.7701 -25.5834 3.9161,
+                          84.9686 -22.2762 10.1937,
+                          85.2494 -9.87472 11.517,
+                          84.4133 -27.436 -4.80214,
+                          85.1099 -10.2225 3.06012,
+                          84.741 -10.801 -5.44172,
+                          84.5029 -27.3678 -2.77934,
+                          84.7701 -25.5834 3.9161,
+                          85.1099 -10.2225 3.06012,
+                          84.4133 -27.436 -4.80214,
+                          84.5029 -27.3678 -2.77934,
+                          85.1099 -10.2225 3.06012,
+                          83.7803 -29.4727 -14.0047,
+                          84.741 -10.801 -5.44172,
+                          84.1036 -11.5665 -13.9099,
+                          84.309 -27.428 -6.90859,
+                          84.4133 -27.436 -4.80214,
+                          84.741 -10.801 -5.44172,
+                          83.7803 -29.4727 -14.0047,
+                          84.309 -27.428 -6.90859,
+                          84.741 -10.801 -5.44172,
+                          83.028 -35.8509 -20.8458,
+                          83.7803 -29.4727 -14.0047,
+                          84.1036 -11.5665 -13.9099,
+                          56.3423 -8.33011 -70.7719,
+                          55.0268 -17.5531 -71.2585,
+                          61.1415 -18.4675 -68.8265,
+                          60.5688 -4.98799 -68.0502,
+                          56.3423 -8.33011 -70.7719,
+                          61.1415 -18.4675 -68.8265,
+                          49.088 -14.8461 -75.5286,
+                          48.2214 -15.8809 -76.2161,
+                          55.0268 -17.5531 -71.2585,
+                          56.3423 -8.33011 -70.7719,
+                          49.088 -14.8461 -75.5286,
+                          55.0268 -17.5531 -71.2585,
+                          89.8369 -26.9083 -0.386391,
+                          84.7701 -25.5834 3.9161,
+                          84.5029 -27.3678 -2.77934,
+                          86.1407 -27.4802 -3.63669,
+                          84.5029 -27.3678 -2.77934,
+                          84.4133 -27.436 -4.80214,
+                          89.4302 -27.1217 -1.38997,
+                          84.5029 -27.3678 -2.77934,
+                          86.1407 -27.4802 -3.63669,
+                          89.4302 -27.1217 -1.38997,
+                          89.8369 -26.9083 -0.386391,
+                          84.5029 -27.3678 -2.77934,
+                          86.9939 -27.5607 -5.78285,
+                          84.4133 -27.436 -4.80214,
+                          84.309 -27.428 -6.90859,
+                          87.6219 -27.5756 -4.55884,
+                          86.1407 -27.4802 -3.63669,
+                          84.4133 -27.436 -4.80214,
+                          86.9939 -27.5607 -5.78285,
+                          87.6219 -27.5756 -4.55884,
+                          84.4133 -27.436 -4.80214,
+                          85.3085 -27.4701 -6.95857,
+                          84.309 -27.428 -6.90859,
+                          83.7803 -29.4727 -14.0047,
+                          86.9939 -27.5607 -5.78285,
+                          84.309 -27.428 -6.90859,
+                          85.3085 -27.4701 -6.95857,
+                          85.6534 -30.3466 -15.1987,
+                          83.7803 -29.4727 -14.0047,
+                          83.028 -35.8509 -20.8458,
+                          85.3085 -27.4701 -6.95857,
+                          83.7803 -29.4727 -14.0047,
+                          86.3027 -27.5147 -7.0111,
+                          85.6534 -30.3466 -15.1987,
+                          86.3027 -27.5147 -7.0111,
+                          83.7803 -29.4727 -14.0047,
+                          84.7147 -38.5178 -23.5099,
+                          85.6534 -30.3466 -15.1987,
+                          83.028 -35.8509 -20.8458,
+                          86.9939 -27.5607 -5.78285,
+                          85.3085 -27.4701 -6.95857,
+                          86.3027 -27.5147 -7.0111,
+                          89.4302 -27.1217 -1.38997,
+                          86.9939 -27.5607 -5.78285,
+                          86.3027 -27.5147 -7.0111,
+                          88.6698 -28.1439 -14.4119,
+                          86.3027 -27.5147 -7.0111,
+                          85.6534 -30.3466 -15.1987,
+                          88.6698 -28.1439 -14.4119,
+                          89.4302 -27.1217 -1.38997,
+                          86.3027 -27.5147 -7.0111,
+                          89.4302 -27.1217 -1.38997,
+                          86.1407 -27.4802 -3.63669,
+                          87.6219 -27.5756 -4.55884,
+                          89.4302 -27.1217 -1.38997,
+                          87.6219 -27.5756 -4.55884,
+                          86.9939 -27.5607 -5.78285,
+                          88.6698 -28.1439 -14.4119,
+                          85.6534 -30.3466 -15.1987,
+                          84.7147 -38.5178 -23.5099,
+                          87.4763 -38.1186 -25.0886,
+                          84.7147 -38.5178 -23.5099,
+                          84.1279 -44.1536 -28.6746,
+                          87.4763 -38.1186 -25.0886,
+                          88.6698 -28.1439 -14.4119,
+                          84.7147 -38.5178 -23.5099,
+                          86.3822 -49.3047 -35.2106,
+                          84.1279 -44.1536 -28.6746,
+                          83.4598 -51.0009 -34.7052,
+                          86.3822 -49.3047 -35.2106,
+                          87.4763 -38.1186 -25.0886,
+                          84.1279 -44.1536 -28.6746,
+                          86.3822 -49.3047 -35.2106,
+                          83.4598 -51.0009 -34.7052,
+                          82.6625 -59.4094 -41.4595,
+                          85.3054 -61.1081 -44.5542,
+                          82.6625 -59.4094 -41.4595,
+                          81.2982 -70.3859 -48.3536,
+                          85.3054 -61.1081 -44.5542,
+                          86.3822 -49.3047 -35.2106,
+                          82.6625 -59.4094 -41.4595,
+                          83.452 -74.163 -51.879,
+                          81.2982 -70.3859 -48.3536,
+                          78.2846 -83.1694 -53.2803,
+                          83.452 -74.163 -51.879,
+                          85.3054 -61.1081 -44.5542,
+                          81.2982 -70.3859 -48.3536,
+                          79.1937 -88.2576 -56.1787,
+                          78.2846 -83.1694 -53.2803,
+                          73.0065 -94.1882 -55.3192,
+                          79.1937 -88.2576 -56.1787,
+                          83.452 -74.163 -51.879,
+                          78.2846 -83.1694 -53.2803,
+                          70.7732 -101.161 -57.8413,
+                          73.0065 -94.1882 -55.3192,
+                          66.4493 -101.975 -55.9198,
+                          70.7732 -101.161 -57.8413,
+                          79.1937 -88.2576 -56.1787,
+                          73.0065 -94.1882 -55.3192,
+                          70.7732 -101.161 -57.8413,
+                          66.4493 -101.975 -55.9198,
+                          60.0026 -107.073 -56.1533,
+                          58.5905 -110.79 -58.3922,
+                          60.0026 -107.073 -56.1533,
+                          53.7915 -110.656 -56.5131,
+                          58.5905 -110.79 -58.3922,
+                          70.7732 -101.161 -57.8413,
+                          60.0026 -107.073 -56.1533,
+                          58.5905 -110.79 -58.3922,
+                          53.7915 -110.656 -56.5131,
+                          47.1155 -113.7 -57.0145,
+                          44.7133 -117.236 -59.285,
+                          47.1155 -113.7 -57.0145,
+                          39.0762 -116.74 -57.4523,
+                          44.7133 -117.236 -59.285,
+                          58.5905 -110.79 -58.3922,
+                          47.1155 -113.7 -57.0145,
+                          30.2586 -121.947 -59.8529,
+                          39.0762 -116.74 -57.4523,
+                          28.7224 -119.862 -57.8594,
+                          30.2586 -121.947 -59.8529,
+                          44.7133 -117.236 -59.285,
+                          39.0762 -116.74 -57.4523,
+                          30.2586 -121.947 -59.8529,
+                          28.7224 -119.862 -57.8594,
+                          15.556 -122.704 -58.2577,
+                          -1.69787e-06 -123.17 -58.4278,
+                          4.73774e-05 -124.13 -58.6691,
+                          15.556 -122.704 -58.2577,
+                          15.3595 -125.234 -60.2086,
+                          15.556 -122.704 -58.2577,
+                          4.73774e-05 -124.13 -58.6691,
+                          15.3595 -125.234 -60.2086,
+                          30.2586 -121.947 -59.8529,
+                          15.556 -122.704 -58.2577,
+                          -22.1237 -119.491 -57.494,
+                          4.73774e-05 -124.13 -58.6691,
+                          -1.69787e-06 -123.17 -58.4278,
+                          -11.678 -123.288 -58.3637,
+                          4.73774e-05 -124.13 -58.6691,
+                          -22.1237 -119.491 -57.494,
+                          0.000557583 -126.624 -60.5453,
+                          4.73774e-05 -124.13 -58.6691,
+                          -11.678 -123.288 -58.3637,
+                          15.3595 -125.234 -60.2086,
+                          4.73774e-05 -124.13 -58.6691,
+                          0.000557583 -126.624 -60.5453,
+                          -17.993 -78.9474 -90.478,
+                          -10.706 -82.2666 -97.894,
+                          -19.3943 -79.4159 -96.2749,
+                          -9.69967 -81.7047 -92.0062,
+                          -10.706 -82.2666 -97.894,
+                          -17.993 -78.9474 -90.478,
+                          -27.7083 -73.7807 -93.821,
+                          -19.3943 -79.4159 -96.2749,
+                          -18.8011 -86.6677 -96.2154,
+                          -24.7788 -74.8717 -88.5231,
+                          -19.3943 -79.4159 -96.2749,
+                          -27.7083 -73.7807 -93.821,
+                          -24.7788 -74.8717 -88.5231,
+                          -17.993 -78.9474 -90.478,
+                          -19.3943 -79.4159 -96.2749,
+                          -33.7347 -73.1847 -93.1133,
+                          -18.8011 -86.6677 -96.2154,
+                          -18.3225 -93.2354 -96.5459,
+                          -31.7215 -69.3305 -92.4408,
+                          -27.7083 -73.7807 -93.821,
+                          -18.8011 -86.6677 -96.2154,
+                          -33.7347 -73.1847 -93.1133,
+                          -31.7215 -69.3305 -92.4408,
+                          -18.8011 -86.6677 -96.2154,
+                          -35.9296 -78.2598 -94.8869,
+                          -18.3225 -93.2354 -96.5459,
+                          -18.2652 -98.8415 -97.114,
+                          -35.9296 -78.2598 -94.8869,
+                          -33.7347 -73.1847 -93.1133,
+                          -18.3225 -93.2354 -96.5459,
+                          -38.8353 -83.5679 -96.2465,
+                          -18.2652 -98.8415 -97.114,
+                          -18.7862 -103.855 -96.629,
+                          -38.8353 -83.5679 -96.2465,
+                          -35.9296 -78.2598 -94.8869,
+                          -18.2652 -98.8415 -97.114,
+                          -42.3392 -88.9797 -95.9521,
+                          -18.7862 -103.855 -96.629,
+                          -19.9246 -108.72 -93.479,
+                          -42.3392 -88.9797 -95.9521,
+                          -38.8353 -83.5679 -96.2465,
+                          -18.7862 -103.855 -96.629,
+                          -46.3766 -94.379 -92.8375,
+                          -19.9246 -108.72 -93.479,
+                          -21.7892 -113.64 -86.6252,
+                          -46.3766 -94.379 -92.8375,
+                          -42.3392 -88.9797 -95.9521,
+                          -19.9246 -108.72 -93.479,
+                          -51.0944 -99.6621 -85.8939,
+                          -21.7892 -113.64 -86.6252,
+                          -24.4339 -118.444 -76.3007,
+                          -51.0944 -99.6621 -85.8939,
+                          -46.3766 -94.379 -92.8375,
+                          -21.7892 -113.64 -86.6252,
+                          -12.5181 -126.012 -63.3402,
+                          -27.4681 -122.929 -63.0119,
+                          -24.4339 -118.444 -76.3007,
+                          -56.4807 -104.676 -75.2156,
+                          -24.4339 -118.444 -76.3007,
+                          -27.4681 -122.929 -63.0119,
+                          -56.4807 -104.676 -75.2156,
+                          -51.0944 -99.6621 -85.8939,
+                          -24.4339 -118.444 -76.3007,
+                          -15.3588 -125.234 -60.2086,
+                          -27.4681 -122.929 -63.0119,
+                          -12.5181 -126.012 -63.3402,
+                          -56.4807 -104.676 -75.2156,
+                          -27.4681 -122.929 -63.0119,
+                          -28.441 -122.673 -62.9879,
+                          -30.2564 -121.947 -59.8537,
+                          -28.441 -122.673 -62.9879,
+                          -27.4681 -122.929 -63.0119,
+                          -15.3588 -125.234 -60.2086,
+                          -30.2564 -121.947 -59.8537,
+                          -27.4681 -122.929 -63.0119,
+                          0.000557583 -126.624 -60.5453,
+                          -15.3588 -125.234 -60.2086,
+                          -12.5181 -126.012 -63.3402,
+                          -39.9592 -119.152 -62.6133,
+                          -56.4807 -104.676 -75.2156,
+                          -28.441 -122.673 -62.9879,
+                          -30.2564 -121.947 -59.8537,
+                          -39.9592 -119.152 -62.6133,
+                          -28.441 -122.673 -62.9879,
+                          -31.7378 -67.8747 -86.1999,
+                          -27.7083 -73.7807 -93.821,
+                          -31.7215 -69.3305 -92.4408,
+                          -24.7788 -74.8717 -88.5231,
+                          -27.7083 -73.7807 -93.821,
+                          -31.7378 -67.8747 -86.1999,
+                          -42.5693 -54.8198 -89.7362,
+                          -31.7215 -69.3305 -92.4408,
+                          -33.7347 -73.1847 -93.1133,
+                          -39.5735 -53.9413 -90.1567,
+                          -35.956 -62.5056 -91.0756,
+                          -31.7215 -69.3305 -92.4408,
+                          -31.7378 -67.8747 -86.1999,
+                          -31.7215 -69.3305 -92.4408,
+                          -35.956 -62.5056 -91.0756,
+                          -42.5693 -54.8198 -89.7362,
+                          -39.5735 -53.9413 -90.1567,
+                          -31.7215 -69.3305 -92.4408,
+                          -47.2809 -57.3983 -91.8618,
+                          -33.7347 -73.1847 -93.1133,
+                          -35.9296 -78.2598 -94.8869,
+                          -47.2809 -57.3983 -91.8618,
+                          -42.5693 -54.8198 -89.7362,
+                          -33.7347 -73.1847 -93.1133,
+                          -52.9634 -60.331 -94.0116,
+                          -35.9296 -78.2598 -94.8869,
+                          -38.8353 -83.5679 -96.2465,
+                          -52.9634 -60.331 -94.0116,
+                          -47.2809 -57.3983 -91.8618,
+                          -35.9296 -78.2598 -94.8869,
+                          -58.6289 -63.4498 -94.3381,
+                          -38.8353 -83.5679 -96.2465,
+                          -42.3392 -88.9797 -95.9521,
+                          -58.6289 -63.4498 -94.3381,
+                          -52.9634 -60.331 -94.0116,
+                          -38.8353 -83.5679 -96.2465,
+                          -64.0554 -66.6094 -92.2523,
+                          -42.3392 -88.9797 -95.9521,
+                          -46.3766 -94.379 -92.8375,
+                          -64.0554 -66.6094 -92.2523,
+                          -58.6289 -63.4498 -94.3381,
+                          -42.3392 -88.9797 -95.9521,
+                          -69.363 -69.7138 -87.4109,
+                          -46.3766 -94.379 -92.8375,
+                          -51.0944 -99.6621 -85.8939,
+                          -69.363 -69.7138 -87.4109,
+                          -64.0554 -66.6094 -92.2523,
+                          -46.3766 -94.379 -92.8375,
+                          -74.7274 -72.7358 -79.6383,
+                          -51.0944 -99.6621 -85.8939,
+                          -56.4807 -104.676 -75.2156,
+                          -74.7274 -72.7358 -79.6383,
+                          -69.363 -69.7138 -87.4109,
+                          -51.0944 -99.6621 -85.8939,
+                          -51.6769 -114.499 -61.9427,
+                          -61.6101 -109.106 -61.3456,
+                          -56.4807 -104.676 -75.2156,
+                          -79.7722 -75.6519 -69.2598,
+                          -56.4807 -104.676 -75.2156,
+                          -61.6101 -109.106 -61.3456,
+                          -39.9592 -119.152 -62.6133,
+                          -51.6769 -114.499 -61.9427,
+                          -56.4807 -104.676 -75.2156,
+                          -79.7722 -75.6519 -69.2598,
+                          -74.7274 -72.7358 -79.6383,
+                          -56.4807 -104.676 -75.2156,
+                          -58.5912 -110.791 -58.3905,
+                          -61.6101 -109.106 -61.3456,
+                          -51.6769 -114.499 -61.9427,
+                          -79.7722 -75.6519 -69.2598,
+                          -61.6101 -109.106 -61.3456,
+                          -62.7007 -108.377 -61.2956,
+                          -70.7726 -101.161 -57.8426,
+                          -62.7007 -108.377 -61.2956,
+                          -61.6101 -109.106 -61.3456,
+                          -58.5912 -110.791 -58.3905,
+                          -70.7726 -101.161 -57.8426,
+                          -61.6101 -109.106 -61.3456,
+                          -44.7112 -117.236 -59.2864,
+                          -51.6769 -114.499 -61.9427,
+                          -39.9592 -119.152 -62.6133,
+                          -44.7112 -117.236 -59.2864,
+                          -58.5912 -110.791 -58.3905,
+                          -51.6769 -114.499 -61.9427,
+                          -30.2564 -121.947 -59.8537,
+                          -44.7112 -117.236 -59.2864,
+                          -39.9592 -119.152 -62.6133,
+                          -73.6561 -98.1955 -60.7026,
+                          -79.7722 -75.6519 -69.2598,
+                          -62.7007 -108.377 -61.2956,
+                          -70.7726 -101.161 -57.8426,
+                          -73.6561 -98.1955 -60.7026,
+                          -62.7007 -108.377 -61.2956,
+                          -34.8607 -60.4148 -85.2524,
+                          -35.956 -62.5056 -91.0756,
+                          -39.5735 -53.9413 -90.1567,
+                          -31.7378 -67.8747 -86.1999,
+                          -35.956 -62.5056 -91.0756,
+                          -34.8607 -60.4148 -85.2524,
+                          -43.027 -42.4516 -89.6172,
+                          -39.5735 -53.9413 -90.1567,
+                          -42.5693 -54.8198 -89.7362,
+                          -35.3414 -52.149 -86.3758,
+                          -39.5735 -53.9413 -90.1567,
+                          -43.027 -42.4516 -89.6172,
+                          -34.8607 -60.4148 -85.2524,
+                          -39.5735 -53.9413 -90.1567,
+                          -35.3414 -52.149 -86.3758,
+                          -50.3199 -36.1969 -82.7021,
+                          -42.5693 -54.8198 -89.7362,
+                          -47.2809 -57.3983 -91.8618,
+                          -45.7587 -33.818 -86.0489,
+                          -43.027 -42.4516 -89.6172,
+                          -42.5693 -54.8198 -89.7362,
+                          -50.3199 -36.1969 -82.7021,
+                          -45.7587 -33.818 -86.0489,
+                          -42.5693 -54.8198 -89.7362,
+                          -58.3593 -37.5182 -82.0964,
+                          -47.2809 -57.3983 -91.8618,
+                          -52.9634 -60.331 -94.0116,
+                          -58.3593 -37.5182 -82.0964,
+                          -50.3199 -36.1969 -82.7021,
+                          -47.2809 -57.3983 -91.8618,
+                          -66.5758 -38.5768 -80.1551,
+                          -52.9634 -60.331 -94.0116,
+                          -58.6289 -63.4498 -94.3381,
+                          -66.5758 -38.5768 -80.1551,
+                          -58.3593 -37.5182 -82.0964,
+                          -52.9634 -60.331 -94.0116,
+                          -73.7075 -39.341 -75.1373,
+                          -58.6289 -63.4498 -94.3381,
+                          -64.0554 -66.6094 -92.2523,
+                          -73.7075 -39.341 -75.1373,
+                          -66.5758 -38.5768 -80.1551,
+                          -58.6289 -63.4498 -94.3381,
+                          -79.6425 -39.9113 -67.3758,
+                          -64.0554 -66.6094 -92.2523,
+                          -69.363 -69.7138 -87.4109,
+                          -79.6425 -39.9113 -67.3758,
+                          -73.7075 -39.341 -75.1373,
+                          -64.0554 -66.6094 -92.2523,
+                          -83.9282 -40.4015 -57.276,
+                          -69.363 -69.7138 -87.4109,
+                          -74.7274 -72.7358 -79.6383,
+                          -83.9282 -40.4015 -57.276,
+                          -79.6425 -39.9113 -67.3758,
+                          -69.363 -69.7138 -87.4109,
+                          -83.9282 -40.4015 -57.276,
+                          -74.7274 -72.7358 -79.6383,
+                          -79.7722 -75.6519 -69.2598,
+                          -80.6684 -86.0395 -58.8267,
+                          -83.3786 -77.6905 -56.4813,
+                          -79.7722 -75.6519 -69.2598,
+                          -86.4742 -40.9138 -45.389,
+                          -79.7722 -75.6519 -69.2598,
+                          -83.3786 -77.6905 -56.4813,
+                          -73.6561 -98.1955 -60.7026,
+                          -80.6684 -86.0395 -58.8267,
+                          -79.7722 -75.6519 -69.2598,
+                          -86.4742 -40.9138 -45.389,
+                          -83.9282 -40.4015 -57.276,
+                          -79.7722 -75.6519 -69.2598,
+                          -83.452 -74.1634 -51.8789,
+                          -83.3786 -77.6905 -56.4813,
+                          -80.6684 -86.0395 -58.8267,
+                          -86.4742 -40.9138 -45.389,
+                          -83.3786 -77.6905 -56.4813,
+                          -85.3421 -67.6611 -52.1535,
+                          -83.452 -74.1634 -51.8789,
+                          -85.3421 -67.6611 -52.1535,
+                          -83.3786 -77.6905 -56.4813,
+                          -79.1936 -88.2585 -56.1788,
+                          -80.6684 -86.0395 -58.8267,
+                          -73.6561 -98.1955 -60.7026,
+                          -79.1936 -88.2585 -56.1788,
+                          -83.452 -74.1634 -51.8789,
+                          -80.6684 -86.0395 -58.8267,
+                          -70.7726 -101.161 -57.8426,
+                          -79.1936 -88.2585 -56.1788,
+                          -73.6561 -98.1955 -60.7026,
+                          -86.3587 -59.3764 -47.0897,
+                          -86.4742 -40.9138 -45.389,
+                          -85.3421 -67.6611 -52.1535,
+                          -85.3056 -61.1075 -44.5544,
+                          -86.3587 -59.3764 -47.0897,
+                          -85.3421 -67.6611 -52.1535,
+                          -83.452 -74.1634 -51.8789,
+                          -85.3056 -61.1075 -44.5544,
+                          -85.3421 -67.6611 -52.1535,
+                          -40.0166 -41.842 -89.3868,
+                          -43.027 -42.4516 -89.6172,
+                          -45.7587 -33.818 -86.0489,
+                          -40.0166 -41.842 -89.3868,
+                          -35.3414 -52.149 -86.3758,
+                          -43.027 -42.4516 -89.6172,
+                          -49.4383 -25.4549 -81.9331,
+                          -45.7587 -33.818 -86.0489,
+                          -50.3199 -36.1969 -82.7021,
+                          -39.5998 -33.153 -85.7624,
+                          -45.7587 -33.818 -86.0489,
+                          -49.4383 -25.4549 -81.9331,
+                          -37.1274 -41.1665 -89.1289,
+                          -45.7587 -33.818 -86.0489,
+                          -39.5998 -33.153 -85.7624,
+                          -40.0166 -41.842 -89.3868,
+                          -45.7587 -33.818 -86.0489,
+                          -37.1274 -41.1665 -89.1289,
+                          -56.8807 -17.0257 -76.962,
+                          -50.3199 -36.1969 -82.7021,
+                          -58.3593 -37.5182 -82.0964,
+                          -56.8807 -17.0257 -76.962,
+                          -49.4383 -25.4549 -81.9331,
+                          -50.3199 -36.1969 -82.7021,
+                          -65.2022 -17.7683 -73.5141,
+                          -58.3593 -37.5182 -82.0964,
+                          -66.5758 -38.5768 -80.1551,
+                          -65.2022 -17.7683 -73.5141,
+                          -56.8807 -17.0257 -76.962,
+                          -58.3593 -37.5182 -82.0964,
+                          -72.7855 -17.402 -68.3174,
+                          -66.5758 -38.5768 -80.1551,
+                          -73.7075 -39.341 -75.1373,
+                          -72.7855 -17.402 -68.3174,
+                          -65.2022 -17.7683 -73.5141,
+                          -66.5758 -38.5768 -80.1551,
+                          -78.7358 -16.5162 -60.4894,
+                          -73.7075 -39.341 -75.1373,
+                          -79.6425 -39.9113 -67.3758,
+                          -78.7358 -16.5162 -60.4894,
+                          -72.7855 -17.402 -68.3174,
+                          -73.7075 -39.341 -75.1373,
+                          -83.0872 -15.3392 -50.8441,
+                          -79.6425 -39.9113 -67.3758,
+                          -83.9282 -40.4015 -57.276,
+                          -83.0872 -15.3392 -50.8441,
+                          -78.7358 -16.5162 -60.4894,
+                          -79.6425 -39.9113 -67.3758,
+                          -86.1521 -14.044 -40.0837,
+                          -83.9282 -40.4015 -57.276,
+                          -86.4742 -40.9138 -45.389,
+                          -86.1521 -14.044 -40.0837,
+                          -83.0872 -15.3392 -50.8441,
+                          -83.9282 -40.4015 -57.276,
+                          -87.7834 -43.0644 -33.7924,
+                          -87.9471 -41.2998 -32.1938,
+                          -86.4742 -40.9138 -45.389,
+                          -89.8754 -11.5486 -16.5653,
+                          -86.4742 -40.9138 -45.389,
+                          -87.9471 -41.2998 -32.1938,
+                          -87.1758 -50.2636 -40.0755,
+                          -87.7834 -43.0644 -33.7924,
+                          -86.4742 -40.9138 -45.389,
+                          -86.3587 -59.3764 -47.0897,
+                          -87.1758 -50.2636 -40.0755,
+                          -86.4742 -40.9138 -45.389,
+                          -88.341 -12.7466 -28.5753,
+                          -86.1521 -14.044 -40.0837,
+                          -86.4742 -40.9138 -45.389,
+                          -89.8754 -11.5486 -16.5653,
+                          -88.341 -12.7466 -28.5753,
+                          -86.4742 -40.9138 -45.389,
+                          -87.4766 -38.1178 -25.0881,
+                          -87.9471 -41.2998 -32.1938,
+                          -87.7834 -43.0644 -33.7924,
+                          -89.8754 -11.5486 -16.5653,
+                          -87.9471 -41.2998 -32.1938,
+                          -88.9093 -32.2588 -23.6498,
+                          -87.4766 -38.1178 -25.0881,
+                          -88.9093 -32.2588 -23.6498,
+                          -87.9471 -41.2998 -32.1938,
+                          -86.3825 -49.304 -35.2102,
+                          -87.7834 -43.0644 -33.7924,
+                          -87.1758 -50.2636 -40.0755,
+                          -86.3825 -49.304 -35.2102,
+                          -87.4766 -38.1178 -25.0881,
+                          -87.7834 -43.0644 -33.7924,
+                          -85.3056 -61.1075 -44.5544,
+                          -87.1758 -50.2636 -40.0755,
+                          -86.3587 -59.3764 -47.0897,
+                          -85.3056 -61.1075 -44.5544,
+                          -86.3825 -49.304 -35.2102,
+                          -87.1758 -50.2636 -40.0755,
+                          -89.8123 -25.4486 -15.7343,
+                          -89.8754 -11.5486 -16.5653,
+                          -88.9093 -32.2588 -23.6498,
+                          -88.6701 -28.1433 -14.4112,
+                          -89.8123 -25.4486 -15.7343,
+                          -88.9093 -32.2588 -23.6498,
+                          -87.4766 -38.1178 -25.0881,
+                          -88.6701 -28.1433 -14.4112,
+                          -88.9093 -32.2588 -23.6498,
+                          -44.3963 -21.5523 -79.7514,
+                          -49.4383 -25.4549 -81.9331,
+                          -56.8807 -17.0257 -76.962,
+                          -39.9657 -32.0367 -85.2465,
+                          -49.4383 -25.4549 -81.9331,
+                          -44.3963 -21.5523 -79.7514,
+                          -39.5998 -33.153 -85.7624,
+                          -49.4383 -25.4549 -81.9331,
+                          -39.9657 -32.0367 -85.2465,
+                          -59.2341 -15.2917 -75.8302,
+                          -56.8807 -17.0257 -76.962,
+                          -65.2022 -17.7683 -73.5141,
+                          -48.2214 -15.8809 -76.2161,
+                          -56.8807 -17.0257 -76.962,
+                          -59.2341 -15.2917 -75.8302,
+                          -44.3963 -21.5523 -79.7514,
+                          -56.8807 -17.0257 -76.962,
+                          -48.2214 -15.8809 -76.2161,
+                          -68.1994 -7.7649 -70.336,
+                          -65.2022 -17.7683 -73.5141,
+                          -72.7855 -17.402 -68.3174,
+                          -68.1994 -7.7649 -70.336,
+                          -59.2341 -15.2917 -75.8302,
+                          -65.2022 -17.7683 -73.5141,
+                          -72.1179 1.76755 -61.8166,
+                          -72.7855 -17.402 -68.3174,
+                          -78.7358 -16.5162 -60.4894,
+                          -72.1179 1.76755 -61.8166,
+                          -68.1994 -7.7649 -70.336,
+                          -72.7855 -17.402 -68.3174,
+                          -76.3177 3.80842 -51.8609,
+                          -78.7358 -16.5162 -60.4894,
+                          -83.0872 -15.3392 -50.8441,
+                          -72.1796 2.21302 -61.365,
+                          -72.1179 1.76755 -61.8166,
+                          -78.7358 -16.5162 -60.4894,
+                          -76.3177 3.80842 -51.8609,
+                          -72.1796 2.21302 -61.365,
+                          -78.7358 -16.5162 -60.4894,
+                          -79.814 5.6256 -41.6278,
+                          -83.0872 -15.3392 -50.8441,
+                          -86.1521 -14.044 -40.0837,
+                          -79.814 5.6256 -41.6278,
+                          -76.3177 3.80842 -51.8609,
+                          -83.0872 -15.3392 -50.8441,
+                          -82.8345 7.56881 -30.9977,
+                          -86.1521 -14.044 -40.0837,
+                          -88.341 -12.7466 -28.5753,
+                          -82.8345 7.56881 -30.9977,
+                          -79.814 5.6256 -41.6278,
+                          -86.1521 -14.044 -40.0837,
+                          -85.2333 9.6033 -19.736,
+                          -88.341 -12.7466 -28.5753,
+                          -89.8754 -11.5486 -16.5653,
+                          -85.2333 9.6033 -19.736,
+                          -82.8345 7.56881 -30.9977,
+                          -88.341 -12.7466 -28.5753,
+                          -89.8123 -25.4486 -15.7343,
+                          -90.8115 -10.5622 -4.34683,
+                          -89.8754 -11.5486 -16.5653,
+                          -86.839 11.6499 -7.67597,
+                          -89.8754 -11.5486 -16.5653,
+                          -90.8115 -10.5622 -4.34683,
+                          -86.839 11.6499 -7.67597,
+                          -85.2333 9.6033 -19.736,
+                          -89.8754 -11.5486 -16.5653,
+                          -90.4308 -23.3643 -7.79088,
+                          -91.212 -9.92873 7.83787,
+                          -90.8115 -10.5622 -4.34683,
+                          -87.7572 13.4642 4.83948,
+                          -90.8115 -10.5622 -4.34683,
+                          -91.212 -9.92873 7.83787,
+                          -89.8123 -25.4486 -15.7343,
+                          -90.4308 -23.3643 -7.79088,
+                          -90.8115 -10.5622 -4.34683,
+                          -87.7572 13.4642 4.83948,
+                          -86.839 11.6499 -7.67597,
+                          -90.8115 -10.5622 -4.34683,
+                          -90.9711 -22.2772 10.2011,
+                          -91.1828 -11.1017 20.5838,
+                          -91.212 -9.92873 7.83787,
+                          -88.1617 14.7853 17.387,
+                          -91.212 -9.92873 7.83787,
+                          -91.1828 -11.1017 20.5838,
+                          -90.8787 -24.1398 7.07082,
+                          -90.9711 -22.2772 10.2011,
+                          -91.212 -9.92873 7.83787,
+                          -90.7772 -25.5682 3.95586,
+                          -90.8787 -24.1398 7.07082,
+                          -91.212 -9.92873 7.83787,
+                          -90.4308 -23.3643 -7.79088,
+                          -90.7772 -25.5682 3.95586,
+                          -91.212 -9.92873 7.83787,
+                          -88.1617 14.7853 17.387,
+                          -87.7572 13.4642 4.83948,
+                          -91.212 -9.92873 7.83787,
+                          -85.1826 -11.0342 20.6174,
+                          -91.1828 -11.1017 20.5838,
+                          -90.9711 -22.2772 10.2011,
+                          -88.4225 14.0018 18.0181,
+                          -88.1617 14.7853 17.387,
+                          -91.1828 -11.1017 20.5838,
+                          -90.4222 4.39823 22.3974,
+                          -88.4225 14.0018 18.0181,
+                          -91.1828 -11.1017 20.5838,
+                          -91.1384 -6.61546 22.1551,
+                          -90.4222 4.39823 22.3974,
+                          -91.1828 -11.1017 20.5838,
+                          -85.1422 -6.87398 22.0906,
+                          -91.1384 -6.61546 22.1551,
+                          -91.1828 -11.1017 20.5838,
+                          -85.1422 -6.87398 22.0906,
+                          -91.1828 -11.1017 20.5838,
+                          -85.1826 -11.0342 20.6174,
+                          -84.9686 -22.2762 10.1937,
+                          -90.9711 -22.2772 10.2011,
+                          -90.8787 -24.1398 7.07082,
+                          -85.1826 -11.0342 20.6174,
+                          -90.9711 -22.2772 10.2011,
+                          -84.9686 -22.2762 10.1937,
+                          -84.9686 -22.2762 10.1937,
+                          -90.8787 -24.1398 7.07082,
+                          -90.7772 -25.5682 3.95586,
+                          -89.8687 -26.8885 -0.300484,
+                          -90.7772 -25.5682 3.95586,
+                          -90.4308 -23.3643 -7.79088,
+                          -84.9686 -22.2762 10.1937,
+                          -90.7772 -25.5682 3.95586,
+                          -84.7701 -25.5834 3.9161,
+                          -89.8687 -26.8885 -0.300484,
+                          -84.7701 -25.5834 3.9161,
+                          -90.7772 -25.5682 3.95586,
+                          -89.4377 -27.1183 -1.37277,
+                          -90.4308 -23.3643 -7.79088,
+                          -89.8123 -25.4486 -15.7343,
+                          -89.8687 -26.8885 -0.300484,
+                          -90.4308 -23.3643 -7.79088,
+                          -89.4377 -27.1183 -1.37277,
+                          -88.6701 -28.1433 -14.4112,
+                          -89.4377 -27.1183 -1.37277,
+                          -89.8123 -25.4486 -15.7343,
+                          -49.088 -14.8461 -75.5286,
+                          -59.2341 -15.2917 -75.8302,
+                          -68.1994 -7.7649 -70.336,
+                          -49.088 -14.8461 -75.5286,
+                          -48.2214 -15.8809 -76.2161,
+                          -59.2341 -15.2917 -75.8302,
+                          -60.5688 -4.98799 -68.0502,
+                          -68.1994 -7.7649 -70.336,
+                          -72.1179 1.76755 -61.8166,
+                          -56.3423 -8.33011 -70.7719,
+                          -68.1994 -7.7649 -70.336,
+                          -60.5688 -4.98799 -68.0502,
+                          -49.088 -14.8461 -75.5286,
+                          -68.1994 -7.7649 -70.336,
+                          -56.3423 -8.33011 -70.7719,
+                          -63.83 -0.477376 -64.0104,
+                          -72.1179 1.76755 -61.8166,
+                          -72.1796 2.21302 -61.365,
+                          -63.3028 -1.64527 -65.0965,
+                          -72.1179 1.76755 -61.8166,
+                          -63.83 -0.477376 -64.0104,
+                          -60.5688 -4.98799 -68.0502,
+                          -72.1179 1.76755 -61.8166,
+                          -63.3028 -1.64527 -65.0965,
+                          -72.3114 7.49889 -55.6117,
+                          -72.1796 2.21302 -61.365,
+                          -76.3177 3.80842 -51.8609,
+                          -64.571 2.55538 -61.0149,
+                          -72.1796 2.21302 -61.365,
+                          -72.3114 7.49889 -55.6117,
+                          -64.571 2.55538 -61.0149,
+                          -63.83 -0.477376 -64.0104,
+                          -72.1796 2.21302 -61.365,
+                          -71.5142 13.5009 -47.9786,
+                          -76.3177 3.80842 -51.8609,
+                          -79.814 5.6256 -41.6278,
+                          -71.5142 13.5009 -47.9786,
+                          -72.3114 7.49889 -55.6117,
+                          -76.3177 3.80842 -51.8609,
+                          -70.5104 19.6444 -38.5684,
+                          -79.814 5.6256 -41.6278,
+                          -82.8345 7.56881 -30.9977,
+                          -70.5104 19.6444 -38.5684,
+                          -71.5142 13.5009 -47.9786,
+                          -79.814 5.6256 -41.6278,
+                          -70.3928 25.7887 -26.9185,
+                          -82.8345 7.56881 -30.9977,
+                          -85.2333 9.6033 -19.736,
+                          -70.3928 25.7887 -26.9185,
+                          -70.5104 19.6444 -38.5684,
+                          -82.8345 7.56881 -30.9977,
+                          -73.8869 28.4742 -14.1408,
+                          -85.2333 9.6033 -19.736,
+                          -86.839 11.6499 -7.67597,
+                          -72.3695 27.1251 -20.5612,
+                          -70.3928 25.7887 -26.9185,
+                          -85.2333 9.6033 -19.736,
+                          -73.8869 28.4742 -14.1408,
+                          -72.3695 27.1251 -20.5612,
+                          -85.2333 9.6033 -19.736,
+                          -82.6015 22.8777 0.0108459,
+                          -86.839 11.6499 -7.67597,
+                          -87.7572 13.4642 4.83948,
+                          -75.9425 31.2558 0.0167273,
+                          -73.8869 28.4742 -14.1408,
+                          -86.839 11.6499 -7.67597,
+                          -79.5135 27.2149 -0.00172324,
+                          -75.9425 31.2558 0.0167273,
+                          -86.839 11.6499 -7.67597,
+                          -82.6015 22.8777 0.0108459,
+                          -79.5135 27.2149 -0.00172324,
+                          -86.839 11.6499 -7.67597,
+                          -85.2522 20.6895 9.71249,
+                          -87.7572 13.4642 4.83948,
+                          -88.1617 14.7853 17.387,
+                          -85.2522 20.6895 9.71249,
+                          -82.6015 22.8777 0.0108459,
+                          -87.7572 13.4642 4.83948,
+                          -79.7616 18.8276 12.9439,
+                          -88.1617 14.7853 17.387,
+                          -88.4225 14.0018 18.0181,
+                          -79.7616 18.8276 12.9439,
+                          -85.2522 20.6895 9.71249,
+                          -88.1617 14.7853 17.387,
+                          -82.1698 13.8614 18.1255,
+                          -88.4225 14.0018 18.0181,
+                          -90.4222 4.39823 22.3974,
+                          -79.7616 18.8276 12.9439,
+                          -88.4225 14.0018 18.0181,
+                          -82.1698 13.8614 18.1255,
+                          -82.4934 12.9299 18.7951,
+                          -90.4222 4.39823 22.3974,
+                          -91.1384 -6.61546 22.1551,
+                          -82.1698 13.8614 18.1255,
+                          -90.4222 4.39823 22.3974,
+                          -82.4934 12.9299 18.7951,
+                          -82.4934 12.9299 18.7951,
+                          -91.1384 -6.61546 22.1551,
+                          -85.1422 -6.87398 22.0906,
+                          -63.1233 12.6951 -49.0817,
+                          -72.3114 7.49889 -55.6117,
+                          -71.5142 13.5009 -47.9786,
+                          -64.442 7.43777 -55.687,
+                          -72.3114 7.49889 -55.6117,
+                          -63.1233 12.6951 -49.0817,
+                          -64.571 2.55538 -61.0149,
+                          -72.3114 7.49889 -55.6117,
+                          -64.442 7.43777 -55.687,
+                          -61.0938 18.2203 -40.9315,
+                          -71.5142 13.5009 -47.9786,
+                          -70.5104 19.6444 -38.5684,
+                          -63.1233 12.6951 -49.0817,
+                          -71.5142 13.5009 -47.9786,
+                          -61.0938 18.2203 -40.9315,
+                          -65.6278 22.0069 -34.3951,
+                          -70.5104 19.6444 -38.5684,
+                          -70.3928 25.7887 -26.9185,
+                          -65.6278 22.0069 -34.3951,
+                          -61.0938 18.2203 -40.9315,
+                          -70.5104 19.6444 -38.5684,
+                          -68.0041 22.4187 -20.7042,
+                          -70.3928 25.7887 -26.9185,
+                          -72.3695 27.1251 -20.5612,
+                          -65.7963 20.8603 -27.6198,
+                          -70.3928 25.7887 -26.9185,
+                          -68.0041 22.4187 -20.7042,
+                          -65.6278 22.0069 -34.3951,
+                          -70.3928 25.7887 -26.9185,
+                          -65.7963 20.8603 -27.6198,
+                          -69.6251 23.9516 -13.961,
+                          -72.3695 27.1251 -20.5612,
+                          -73.8869 28.4742 -14.1408,
+                          -68.0041 22.4187 -20.7042,
+                          -72.3695 27.1251 -20.5612,
+                          -69.6251 23.9516 -13.961,
+                          -70.7978 25.481 -6.99455,
+                          -73.8869 28.4742 -14.1408,
+                          -75.9425 31.2558 0.0167273,
+                          -69.6251 23.9516 -13.961,
+                          -73.8869 28.4742 -14.1408,
+                          -70.7978 25.481 -6.99455,
+                          -75.15 22.8851 0.0180616,
+                          -75.9425 31.2558 0.0167273,
+                          -79.5135 27.2149 -0.00172324,
+                          -73.7708 29.0674 6.38373e-05,
+                          -75.9425 31.2558 0.0167273,
+                          -75.15 22.8851 0.0180616,
+                          -70.7978 25.481 -6.99455,
+                          -75.9425 31.2558 0.0167273,
+                          -71.621 26.9192 0.0239417,
+                          -73.7708 29.0674 6.38373e-05,
+                          -71.621 26.9192 0.0239417,
+                          -75.9425 31.2558 0.0167273,
+                          -75.15 22.8851 0.0180616,
+                          -79.5135 27.2149 -0.00172324,
+                          -82.6015 22.8777 0.0108459,
+                          -75.15 22.8851 0.0180616,
+                          -82.6015 22.8777 0.0108459,
+                          -85.2522 20.6895 9.71249,
+                          -77.0903 21.9541 6.39278,
+                          -85.2522 20.6895 9.71249,
+                          -79.7616 18.8276 12.9439,
+                          -75.15 22.8851 0.0180616,
+                          -85.2522 20.6895 9.71249,
+                          -77.0903 21.9541 6.39278,
+                          -24.5905 -115.594 -66.9001,
+                          -27.6932 -118.166 -57.2915,
+                          -22.1237 -119.491 -57.494,
+                          -22.2465 -121.417 -58.0653,
+                          -22.1237 -119.491 -57.494,
+                          -27.6932 -118.166 -57.2915,
+                          -22.2465 -121.417 -58.0653,
+                          -11.678 -123.288 -58.3637,
+                          -22.1237 -119.491 -57.494,
+                          -56.2714 -102.551 -65.4601,
+                          -27.6932 -118.166 -57.2915,
+                          -24.5905 -115.594 -66.9001,
+                          -44.2698 -112.811 -56.5102,
+                          -27.6932 -118.166 -57.2915,
+                          -56.2714 -102.551 -65.4601,
+                          -31.1057 -119.216 -57.776,
+                          -27.6932 -118.166 -57.2915,
+                          -44.2698 -112.811 -56.5102,
+                          -31.1057 -119.216 -57.776,
+                          -22.2465 -121.417 -58.0653,
+                          -27.6932 -118.166 -57.2915,
+                          -52.9618 -99.45 -73.9676,
+                          -24.5905 -115.594 -66.9001,
+                          -22.4753 -112.59 -75.1889,
+                          -56.2714 -102.551 -65.4601,
+                          -24.5905 -115.594 -66.9001,
+                          -52.9618 -99.45 -73.9676,
+                          -49.531 -96.2805 -80.8226,
+                          -22.4753 -112.59 -75.1889,
+                          -20.5773 -109.542 -81.9354,
+                          -52.9618 -99.45 -73.9676,
+                          -22.4753 -112.59 -75.1889,
+                          -49.531 -96.2805 -80.8226,
+                          -46.4432 -93.2208 -85.7597,
+                          -20.5773 -109.542 -81.9354,
+                          -19.0581 -106.615 -86.8925,
+                          -49.531 -96.2805 -80.8226,
+                          -20.5773 -109.542 -81.9354,
+                          -46.4432 -93.2208 -85.7597,
+                          -43.9521 -90.5427 -88.6597,
+                          -19.0581 -106.615 -86.8925,
+                          -18.0558 -104.131 -89.8139,
+                          -46.4432 -93.2208 -85.7597,
+                          -19.0581 -106.615 -86.8925,
+                          -43.9521 -90.5427 -88.6597,
+                          -42.0282 -88.2063 -89.9868,
+                          -18.0558 -104.131 -89.8139,
+                          -17.7571 -102.393 -90.8888,
+                          -43.9521 -90.5427 -88.6597,
+                          -18.0558 -104.131 -89.8139,
+                          -42.0282 -88.2063 -89.9868,
+                          -40.4239 -85.8467 -90.3915,
+                          -17.7571 -102.393 -90.8888,
+                          -18.0121 -100.755 -91.1525,
+                          -42.0282 -88.2063 -89.9868,
+                          -17.7571 -102.393 -90.8888,
+                          -40.4239 -85.8467 -90.3915,
+                          -38.9063 -83.1874 -90.1189,
+                          -18.0121 -100.755 -91.1525,
+                          -18.2824 -98.1636 -91.0399,
+                          -40.4239 -85.8467 -90.3915,
+                          -18.0121 -100.755 -91.1525,
+                          -38.9063 -83.1874 -90.1189,
+                          -37.3473 -80.187 -89.2781,
+                          -18.2824 -98.1636 -91.0399,
+                          -18.2544 -94.3054 -90.6195,
+                          -38.9063 -83.1874 -90.1189,
+                          -18.2824 -98.1636 -91.0399,
+                          -37.3473 -80.187 -89.2781,
+                          -35.6577 -76.9085 -88.0756,
+                          -18.2544 -94.3054 -90.6195,
+                          -17.9817 -89.453 -90.3265,
+                          -37.3473 -80.187 -89.2781,
+                          -18.2544 -94.3054 -90.6195,
+                          -35.6577 -76.9085 -88.0756,
+                          -33.6553 -73.2901 -86.8743,
+                          -17.9817 -89.453 -90.3265,
+                          -17.8832 -84.3336 -90.3235,
+                          -35.6577 -76.9085 -88.0756,
+                          -17.9817 -89.453 -90.3265,
+                          -33.6553 -73.2901 -86.8743,
+                          -24.7788 -74.8717 -88.5231,
+                          -17.8832 -84.3336 -90.3235,
+                          -17.993 -78.9474 -90.478,
+                          -24.7788 -74.8717 -88.5231,
+                          -33.6553 -73.2901 -86.8743,
+                          -17.8832 -84.3336 -90.3235,
+                          -85.1099 -10.2225 3.06012,
+                          -84.4133 -27.436 -4.80214,
+                          -84.309 -27.428 -6.90859,
+                          -85.3086 -27.4701 -6.95846,
+                          -84.309 -27.428 -6.90859,
+                          -84.4133 -27.436 -4.80214,
+                          -84.741 -10.801 -5.44172,
+                          -85.1099 -10.2225 3.06012,
+                          -84.309 -27.428 -6.90859,
+                          -83.7803 -29.4727 -14.0047,
+                          -84.741 -10.801 -5.44172,
+                          -84.309 -27.428 -6.90859,
+                          -85.5673 -31.0281 -16.0046,
+                          -83.7803 -29.4727 -14.0047,
+                          -84.309 -27.428 -6.90859,
+                          -85.5673 -31.0281 -16.0046,
+                          -84.309 -27.428 -6.90859,
+                          -85.3086 -27.4701 -6.95846,
+                          -85.1099 -10.2225 3.06012,
+                          -84.5029 -27.3678 -2.77934,
+                          -84.4133 -27.436 -4.80214,
+                          -87.6219 -27.5756 -4.55886,
+                          -84.4133 -27.436 -4.80214,
+                          -84.5029 -27.3678 -2.77934,
+                          -86.9938 -27.5607 -5.78288,
+                          -84.4133 -27.436 -4.80214,
+                          -87.6219 -27.5756 -4.55886,
+                          -86.3027 -27.5147 -7.01095,
+                          -85.3086 -27.4701 -6.95846,
+                          -84.4133 -27.436 -4.80214,
+                          -86.9938 -27.5607 -5.78288,
+                          -86.3027 -27.5147 -7.01095,
+                          -84.4133 -27.436 -4.80214,
+                          -85.2494 -9.87472 11.517,
+                          -84.7701 -25.5834 3.9161,
+                          -84.5029 -27.3678 -2.77934,
+                          -89.4377 -27.1183 -1.37277,
+                          -84.5029 -27.3678 -2.77934,
+                          -84.7701 -25.5834 3.9161,
+                          -85.1099 -10.2225 3.06012,
+                          -85.2494 -9.87472 11.517,
+                          -84.5029 -27.3678 -2.77934,
+                          -86.1407 -27.4802 -3.6367,
+                          -87.6219 -27.5756 -4.55886,
+                          -84.5029 -27.3678 -2.77934,
+                          -89.4377 -27.1183 -1.37277,
+                          -86.1407 -27.4802 -3.6367,
+                          -84.5029 -27.3678 -2.77934,
+                          -85.2494 -9.87472 11.517,
+                          -84.9686 -22.2762 10.1937,
+                          -84.7701 -25.5834 3.9161,
+                          -89.8687 -26.8885 -0.300484,
+                          -89.4377 -27.1183 -1.37277,
+                          -84.7701 -25.5834 3.9161,
+                          -85.2494 -9.87472 11.517,
+                          -85.1826 -11.0342 20.6174,
+                          -84.9686 -22.2762 10.1937,
+                          -82.4934 12.9299 18.7951,
+                          -85.1826 -11.0342 20.6174,
+                          -85.2494 -9.87472 11.517,
+                          -82.4934 12.9299 18.7951,
+                          -85.1422 -6.87398 22.0906,
+                          -85.1826 -11.0342 20.6174,
+                          -82.282 12.0573 9.79247,
+                          -85.2494 -9.87472 11.517,
+                          -85.1099 -10.2225 3.06012,
+                          -82.282 12.0573 9.79247,
+                          -82.4934 12.9299 18.7951,
+                          -85.2494 -9.87472 11.517,
+                          -81.882 10.8256 1.05018,
+                          -85.1099 -10.2225 3.06012,
+                          -84.741 -10.801 -5.44172,
+                          -81.882 10.8256 1.05018,
+                          -82.282 12.0573 9.79247,
+                          -85.1099 -10.2225 3.06012,
+                          -82.462 -41.1476 -25.7626,
+                          -84.1036 -11.5665 -13.9099,
+                          -84.741 -10.801 -5.44172,
+                          -81.2174 9.33985 -7.60365,
+                          -84.741 -10.801 -5.44172,
+                          -84.1036 -11.5665 -13.9099,
+                          -83.028 -35.8509 -20.8458,
+                          -82.462 -41.1476 -25.7626,
+                          -84.741 -10.801 -5.44172,
+                          -83.7803 -29.4727 -14.0047,
+                          -83.028 -35.8509 -20.8458,
+                          -84.741 -10.801 -5.44172,
+                          -81.2174 9.33985 -7.60365,
+                          -81.882 10.8256 1.05018,
+                          -84.741 -10.801 -5.44172,
+                          -81.5229 -41.2467 -35.3653,
+                          -83.1786 -12.4784 -22.2484,
+                          -84.1036 -11.5665 -13.9099,
+                          -80.2264 7.73506 -15.9558,
+                          -84.1036 -11.5665 -13.9099,
+                          -83.1786 -12.4784 -22.2484,
+                          -82.462 -41.1476 -25.7626,
+                          -81.5229 -41.2467 -35.3653,
+                          -84.1036 -11.5665 -13.9099,
+                          -80.2264 7.73506 -15.9558,
+                          -81.2174 9.33985 -7.60365,
+                          -84.1036 -11.5665 -13.9099,
+                          -80.4095 -40.9972 -44.2169,
+                          -81.9484 -13.5067 -30.3309,
+                          -83.1786 -12.4784 -22.2484,
+                          -78.865 6.10312 -23.8613,
+                          -83.1786 -12.4784 -22.2484,
+                          -81.9484 -13.5067 -30.3309,
+                          -81.5229 -41.2467 -35.3653,
+                          -80.4095 -40.9972 -44.2169,
+                          -83.1786 -12.4784 -22.2484,
+                          -78.865 6.10312 -23.8613,
+                          -80.2264 7.73506 -15.9558,
+                          -83.1786 -12.4784 -22.2484,
+                          -78.8419 -40.9004 -52.3734,
+                          -80.4022 -14.5971 -38.084,
+                          -81.9484 -13.5067 -30.3309,
+                          -77.1269 4.51132 -31.4254,
+                          -81.9484 -13.5067 -30.3309,
+                          -80.4022 -14.5971 -38.084,
+                          -80.4095 -40.9972 -44.2169,
+                          -78.8419 -40.9004 -52.3734,
+                          -81.9484 -13.5067 -30.3309,
+                          -77.1269 4.51132 -31.4254,
+                          -78.865 6.10312 -23.8613,
+                          -81.9484 -13.5067 -30.3309,
+                          -76.6379 -40.9733 -59.6071,
+                          -78.4852 -15.6852 -45.4213,
+                          -80.4022 -14.5971 -38.084,
+                          -75.0726 3.01852 -38.7925,
+                          -80.4022 -14.5971 -38.084,
+                          -78.4852 -15.6852 -45.4213,
+                          -78.8419 -40.9004 -52.3734,
+                          -76.6379 -40.9733 -59.6071,
+                          -80.4022 -14.5971 -38.084,
+                          -75.0726 3.01852 -38.7925,
+                          -77.1269 4.51132 -31.4254,
+                          -80.4022 -14.5971 -38.084,
+                          -73.7985 -41.2068 -65.6967,
+                          -76.0787 -16.6922 -52.2069,
+                          -78.4852 -15.6852 -45.4213,
+                          -72.7221 1.68912 -46.0158,
+                          -78.4852 -15.6852 -45.4213,
+                          -76.0787 -16.6922 -52.2069,
+                          -76.6379 -40.9733 -59.6071,
+                          -73.7985 -41.2068 -65.6967,
+                          -78.4852 -15.6852 -45.4213,
+                          -72.7221 1.68912 -46.0158,
+                          -75.0726 3.01852 -38.7925,
+                          -78.4852 -15.6852 -45.4213,
+                          -70.4854 -41.52 -70.4956,
+                          -73.1248 -17.5605 -58.1736,
+                          -76.0787 -16.6922 -52.2069,
+                          -70.0791 0.597946 -52.9116,
+                          -76.0787 -16.6922 -52.2069,
+                          -73.1248 -17.5605 -58.1736,
+                          -73.7985 -41.2068 -65.6967,
+                          -70.4854 -41.52 -70.4956,
+                          -76.0787 -16.6922 -52.2069,
+                          -70.0791 0.597946 -52.9116,
+                          -72.7221 1.68912 -46.0158,
+                          -76.0787 -16.6922 -52.2069,
+                          -66.8623 -41.7409 -73.9893,
+                          -69.6392 -18.2155 -63.0108,
+                          -73.1248 -17.5605 -58.1736,
+                          -67.0917 -0.152173 -59.068,
+                          -73.1248 -17.5605 -58.1736,
+                          -69.6392 -18.2155 -63.0108,
+                          -70.4854 -41.52 -70.4956,
+                          -66.8623 -41.7409 -73.9893,
+                          -73.1248 -17.5605 -58.1736,
+                          -67.0917 -0.152173 -59.068,
+                          -70.0791 0.597946 -52.9116,
+                          -73.1248 -17.5605 -58.1736,
+                          -62.9073 -41.6561 -76.1863,
+                          -65.7443 -18.5761 -66.5004,
+                          -69.6392 -18.2155 -63.0108,
+                          -63.83 -0.477376 -64.0104,
+                          -69.6392 -18.2155 -63.0108,
+                          -65.7443 -18.5761 -66.5004,
+                          -66.8623 -41.7409 -73.9893,
+                          -62.9073 -41.6561 -76.1863,
+                          -69.6392 -18.2155 -63.0108,
+                          -63.83 -0.477376 -64.0104,
+                          -67.0917 -0.152173 -59.068,
+                          -69.6392 -18.2155 -63.0108,
+                          -58.236 -41.0221 -77.045,
+                          -61.1415 -18.4675 -68.8265,
+                          -65.7443 -18.5761 -66.5004,
+                          -63.3028 -1.64527 -65.0965,
+                          -65.7443 -18.5761 -66.5004,
+                          -61.1415 -18.4675 -68.8265,
+                          -62.9073 -41.6561 -76.1863,
+                          -58.236 -41.0221 -77.045,
+                          -65.7443 -18.5761 -66.5004,
+                          -63.3028 -1.64527 -65.0965,
+                          -63.83 -0.477376 -64.0104,
+                          -65.7443 -18.5761 -66.5004,
+                          -52.2972 -39.5808 -77.0931,
+                          -55.0268 -17.5531 -71.2585,
+                          -61.1415 -18.4675 -68.8265,
+                          -60.5688 -4.98799 -68.0502,
+                          -61.1415 -18.4675 -68.8265,
+                          -55.0268 -17.5531 -71.2585,
+                          -58.236 -41.0221 -77.045,
+                          -52.2972 -39.5808 -77.0931,
+                          -61.1415 -18.4675 -68.8265,
+                          -60.5688 -4.98799 -68.0502,
+                          -63.3028 -1.64527 -65.0965,
+                          -61.1415 -18.4675 -68.8265,
+                          -45.1784 -36.8854 -78.3925,
+                          -48.2214 -15.8809 -76.2161,
+                          -55.0268 -17.5531 -71.2585,
+                          -49.088 -14.8461 -75.5286,
+                          -55.0268 -17.5531 -71.2585,
+                          -48.2214 -15.8809 -76.2161,
+                          -52.2972 -39.5808 -77.0931,
+                          -45.1784 -36.8854 -78.3925,
+                          -55.0268 -17.5531 -71.2585,
+                          -56.3423 -8.33011 -70.7719,
+                          -60.5688 -4.98799 -68.0502,
+                          -55.0268 -17.5531 -71.2585,
+                          -49.088 -14.8461 -75.5286,
+                          -56.3423 -8.33011 -70.7719,
+                          -55.0268 -17.5531 -71.2585,
+                          -39.5998 -33.153 -85.7624,
+                          -44.3963 -21.5523 -79.7514,
+                          -48.2214 -15.8809 -76.2161,
+                          -45.1784 -36.8854 -78.3925,
+                          -39.5998 -33.153 -85.7624,
+                          -48.2214 -15.8809 -76.2161,
+                          -39.5998 -33.153 -85.7624,
+                          -39.9657 -32.0367 -85.2465,
+                          -44.3963 -21.5523 -79.7514,
+                          -41.9923 -55.5627 -83.6099,
+                          -39.5998 -33.153 -85.7624,
+                          -45.1784 -36.8854 -78.3925,
+                          -35.3414 -52.149 -86.3758,
+                          -37.1274 -41.1665 -89.1289,
+                          -39.5998 -33.153 -85.7624,
+                          -41.9923 -55.5627 -83.6099,
+                          -35.3414 -52.149 -86.3758,
+                          -39.5998 -33.153 -85.7624,
+                          -46.243 -58.0356 -85.0329,
+                          -45.1784 -36.8854 -78.3925,
+                          -52.2972 -39.5808 -77.0931,
+                          -46.243 -58.0356 -85.0329,
+                          -41.9923 -55.5627 -83.6099,
+                          -45.1784 -36.8854 -78.3925,
+                          -49.8669 -60.0696 -86.7919,
+                          -52.2972 -39.5808 -77.0931,
+                          -58.236 -41.0221 -77.045,
+                          -49.8669 -60.0696 -86.7919,
+                          -46.243 -58.0356 -85.0329,
+                          -52.2972 -39.5808 -77.0931,
+                          -53.2414 -61.9632 -88.1436,
+                          -58.236 -41.0221 -77.045,
+                          -62.9073 -41.6561 -76.1863,
+                          -53.2414 -61.9632 -88.1436,
+                          -49.8669 -60.0696 -86.7919,
+                          -58.236 -41.0221 -77.045,
+                          -56.0539 -63.6465 -88.6673,
+                          -62.9073 -41.6561 -76.1863,
+                          -66.8623 -41.7409 -73.9893,
+                          -56.0539 -63.6465 -88.6673,
+                          -53.2414 -61.9632 -88.1436,
+                          -62.9073 -41.6561 -76.1863,
+                          -58.5657 -65.2067 -88.389,
+                          -66.8623 -41.7409 -73.9893,
+                          -70.4854 -41.52 -70.4956,
+                          -58.5657 -65.2067 -88.389,
+                          -56.0539 -63.6465 -88.6673,
+                          -66.8623 -41.7409 -73.9893,
+                          -61.0857 -66.7328 -87.254,
+                          -70.4854 -41.52 -70.4956,
+                          -73.7985 -41.2068 -65.6967,
+                          -61.0857 -66.7328 -87.254,
+                          -58.5657 -65.2067 -88.389,
+                          -70.4854 -41.52 -70.4956,
+                          -63.8709 -68.3318 -84.9482,
+                          -73.7985 -41.2068 -65.6967,
+                          -76.6379 -40.9733 -59.6071,
+                          -63.8709 -68.3318 -84.9482,
+                          -61.0857 -66.7328 -87.254,
+                          -73.7985 -41.2068 -65.6967,
+                          -70.4008 -72.0222 -75.569,
+                          -76.6379 -40.9733 -59.6071,
+                          -78.8419 -40.9004 -52.3734,
+                          -67.0177 -70.0946 -81.085,
+                          -63.8709 -68.3318 -84.9482,
+                          -76.6379 -40.9733 -59.6071,
+                          -70.4008 -72.0222 -75.569,
+                          -67.0177 -70.0946 -81.085,
+                          -76.6379 -40.9733 -59.6071,
+                          -73.6249 -74.0094 -68.5997,
+                          -78.8419 -40.9004 -52.3734,
+                          -80.4095 -40.9972 -44.2169,
+                          -73.6249 -74.0094 -68.5997,
+                          -70.4008 -72.0222 -75.569,
+                          -78.8419 -40.9004 -52.3734,
+                          -76.1748 -75.991 -60.402,
+                          -80.4095 -40.9972 -44.2169,
+                          -81.5229 -41.2467 -35.3653,
+                          -76.1748 -75.991 -60.402,
+                          -73.6249 -74.0094 -68.5997,
+                          -80.4095 -40.9972 -44.2169,
+                          -81.9716 -46.0203 -30.1534,
+                          -81.5229 -41.2467 -35.3653,
+                          -82.462 -41.1476 -25.7626,
+                          -80.4399 -61.5194 -42.7474,
+                          -81.5229 -41.2467 -35.3653,
+                          -81.9716 -46.0203 -30.1534,
+                          -78.024 -76.7293 -50.9165,
+                          -76.1748 -75.991 -60.402,
+                          -81.5229 -41.2467 -35.3653,
+                          -80.4399 -61.5194 -42.7474,
+                          -78.024 -76.7293 -50.9165,
+                          -81.5229 -41.2467 -35.3653,
+                          -84.472 -40.8076 -25.6263,
+                          -82.462 -41.1476 -25.7626,
+                          -83.028 -35.8509 -20.8458,
+                          -83.7788 -47.6652 -31.8117,
+                          -81.9716 -46.0203 -30.1534,
+                          -82.462 -41.1476 -25.7626,
+                          -84.472 -40.8076 -25.6263,
+                          -83.7788 -47.6652 -31.8117,
+                          -82.462 -41.1476 -25.7626,
+                          -85.5673 -31.0281 -16.0046,
+                          -83.028 -35.8509 -20.8458,
+                          -83.7803 -29.4727 -14.0047,
+                          -85.5673 -31.0281 -16.0046,
+                          -84.472 -40.8076 -25.6263,
+                          -83.028 -35.8509 -20.8458,
+                          -82.9679 -56.26 -39.042,
+                          -80.4399 -61.5194 -42.7474,
+                          -81.9716 -46.0203 -30.1534,
+                          -83.7788 -47.6652 -31.8117,
+                          -82.9679 -56.26 -39.042,
+                          -81.9716 -46.0203 -30.1534,
+                          -40.0166 -41.842 -89.3868,
+                          -37.1274 -41.1665 -89.1289,
+                          -35.3414 -52.149 -86.3758,
+                          -31.7378 -67.8747 -86.1999,
+                          -35.3414 -52.149 -86.3758,
+                          -41.9923 -55.5627 -83.6099,
+                          -31.7378 -67.8747 -86.1999,
+                          -34.8607 -60.4148 -85.2524,
+                          -35.3414 -52.149 -86.3758,
+                          -33.6553 -73.2901 -86.8743,
+                          -41.9923 -55.5627 -83.6099,
+                          -46.243 -58.0356 -85.0329,
+                          -33.6553 -73.2901 -86.8743,
+                          -31.7378 -67.8747 -86.1999,
+                          -41.9923 -55.5627 -83.6099,
+                          -35.6577 -76.9085 -88.0756,
+                          -46.243 -58.0356 -85.0329,
+                          -49.8669 -60.0696 -86.7919,
+                          -35.6577 -76.9085 -88.0756,
+                          -33.6553 -73.2901 -86.8743,
+                          -46.243 -58.0356 -85.0329,
+                          -37.3473 -80.187 -89.2781,
+                          -49.8669 -60.0696 -86.7919,
+                          -53.2414 -61.9632 -88.1436,
+                          -37.3473 -80.187 -89.2781,
+                          -35.6577 -76.9085 -88.0756,
+                          -49.8669 -60.0696 -86.7919,
+                          -38.9063 -83.1874 -90.1189,
+                          -53.2414 -61.9632 -88.1436,
+                          -56.0539 -63.6465 -88.6673,
+                          -38.9063 -83.1874 -90.1189,
+                          -37.3473 -80.187 -89.2781,
+                          -53.2414 -61.9632 -88.1436,
+                          -40.4239 -85.8467 -90.3915,
+                          -56.0539 -63.6465 -88.6673,
+                          -58.5657 -65.2067 -88.389,
+                          -40.4239 -85.8467 -90.3915,
+                          -38.9063 -83.1874 -90.1189,
+                          -56.0539 -63.6465 -88.6673,
+                          -42.0282 -88.2063 -89.9868,
+                          -58.5657 -65.2067 -88.389,
+                          -61.0857 -66.7328 -87.254,
+                          -42.0282 -88.2063 -89.9868,
+                          -40.4239 -85.8467 -90.3915,
+                          -58.5657 -65.2067 -88.389,
+                          -43.9521 -90.5427 -88.6597,
+                          -61.0857 -66.7328 -87.254,
+                          -63.8709 -68.3318 -84.9482,
+                          -43.9521 -90.5427 -88.6597,
+                          -42.0282 -88.2063 -89.9868,
+                          -61.0857 -66.7328 -87.254,
+                          -46.4432 -93.2208 -85.7597,
+                          -63.8709 -68.3318 -84.9482,
+                          -67.0177 -70.0946 -81.085,
+                          -46.4432 -93.2208 -85.7597,
+                          -43.9521 -90.5427 -88.6597,
+                          -63.8709 -68.3318 -84.9482,
+                          -49.531 -96.2805 -80.8226,
+                          -67.0177 -70.0946 -81.085,
+                          -70.4008 -72.0222 -75.569,
+                          -49.531 -96.2805 -80.8226,
+                          -46.4432 -93.2208 -85.7597,
+                          -67.0177 -70.0946 -81.085,
+                          -52.9618 -99.45 -73.9676,
+                          -70.4008 -72.0222 -75.569,
+                          -73.6249 -74.0094 -68.5997,
+                          -52.9618 -99.45 -73.9676,
+                          -49.531 -96.2805 -80.8226,
+                          -70.4008 -72.0222 -75.569,
+                          -56.2714 -102.551 -65.4601,
+                          -73.6249 -74.0094 -68.5997,
+                          -76.1748 -75.991 -60.402,
+                          -56.2714 -102.551 -65.4601,
+                          -52.9618 -99.45 -73.9676,
+                          -73.6249 -74.0094 -68.5997,
+                          -74.882 -86.4869 -53.7165,
+                          -76.1748 -75.991 -60.402,
+                          -78.024 -76.7293 -50.9165,
+                          -58.8357 -105.508 -55.5005,
+                          -76.1748 -75.991 -60.402,
+                          -74.882 -86.4869 -53.7165,
+                          -58.8357 -105.508 -55.5005,
+                          -56.2714 -102.551 -65.4601,
+                          -76.1748 -75.991 -60.402,
+                          -81.6924 -67.735 -46.928,
+                          -78.024 -76.7293 -50.9165,
+                          -80.4399 -61.5194 -42.7474,
+                          -78.6911 -81.9128 -52.9324,
+                          -74.882 -86.4869 -53.7165,
+                          -78.024 -76.7293 -50.9165,
+                          -81.6924 -67.735 -46.928,
+                          -78.6911 -81.9128 -52.9324,
+                          -78.024 -76.7293 -50.9165,
+                          -82.9679 -56.26 -39.042,
+                          -81.6924 -67.735 -46.928,
+                          -80.4399 -61.5194 -42.7474,
+                          -68.181 -97.3419 -55.108,
+                          -58.8357 -105.508 -55.5005,
+                          -74.882 -86.4869 -53.7165,
+                          -72.8907 -94.3627 -55.3388,
+                          -68.181 -97.3419 -55.108,
+                          -74.882 -86.4869 -53.7165,
+                          -78.6911 -81.9128 -52.9324,
+                          -72.8907 -94.3627 -55.3388,
+                          -74.882 -86.4869 -53.7165,
+                          -24.7788 -74.8717 -88.5231,
+                          -31.7378 -67.8747 -86.1999,
+                          -33.6553 -73.2901 -86.8743,
+                          -44.2698 -112.811 -56.5102,
+                          -56.2714 -102.551 -65.4601,
+                          -58.8357 -105.508 -55.5005,
+                          -68.181 -97.3419 -55.108,
+                          -60.4168 -104.417 -55.4429,
+                          -58.8357 -105.508 -55.5005,
+                          -57.5409 -108.613 -56.2627,
+                          -58.8357 -105.508 -55.5005,
+                          -60.4168 -104.417 -55.4429,
+                          -44.2698 -112.811 -56.5102,
+                          -58.8357 -105.508 -55.5005,
+                          -51.5498 -109.626 -55.9698,
+                          -57.5409 -108.613 -56.2627,
+                          -51.5498 -109.626 -55.9698,
+                          -58.8357 -105.508 -55.5005,
+                          -65.0958 -103.2 -55.9755,
+                          -60.4168 -104.417 -55.4429,
+                          -68.181 -97.3419 -55.108,
+                          -65.0958 -103.2 -55.9755,
+                          -57.5409 -108.613 -56.2627,
+                          -60.4168 -104.417 -55.4429,
+                          -72.8907 -94.3627 -55.3388,
+                          -65.0958 -103.2 -55.9755,
+                          -68.181 -97.3419 -55.108,
+                          -49.9802 -112.465 -56.8133,
+                          -44.2698 -112.811 -56.5102,
+                          -51.5498 -109.626 -55.9698,
+                          -57.5409 -108.613 -56.2627,
+                          -49.9802 -112.465 -56.8133,
+                          -51.5498 -109.626 -55.9698,
+                          -41.7683 -115.785 -57.3222,
+                          -31.1057 -119.216 -57.776,
+                          -44.2698 -112.811 -56.5102,
+                          -49.9802 -112.465 -56.8133,
+                          -41.7683 -115.785 -57.3222,
+                          -44.2698 -112.811 -56.5102,
+                          -82.1698 13.8614 18.1255,
+                          -82.4934 12.9299 18.7951,
+                          -82.282 12.0573 9.79247,
+                          -77.0903 21.9541 6.39278,
+                          -82.282 12.0573 9.79247,
+                          -81.882 10.8256 1.05018,
+                          -79.7616 18.8276 12.9439,
+                          -82.1698 13.8614 18.1255,
+                          -82.282 12.0573 9.79247,
+                          -77.0903 21.9541 6.39278,
+                          -79.7616 18.8276 12.9439,
+                          -82.282 12.0573 9.79247,
+                          -75.15 22.8851 0.0180616,
+                          -81.882 10.8256 1.05018,
+                          -81.2174 9.33985 -7.60365,
+                          -75.15 22.8851 0.0180616,
+                          -77.0903 21.9541 6.39278,
+                          -81.882 10.8256 1.05018,
+                          -70.7978 25.481 -6.99455,
+                          -81.2174 9.33985 -7.60365,
+                          -80.2264 7.73506 -15.9558,
+                          -73.4649 24.9236 -0.00261418,
+                          -75.15 22.8851 0.0180616,
+                          -81.2174 9.33985 -7.60365,
+                          -71.621 26.9192 0.0239417,
+                          -73.4649 24.9236 -0.00261418,
+                          -81.2174 9.33985 -7.60365,
+                          -70.7978 25.481 -6.99455,
+                          -71.621 26.9192 0.0239417,
+                          -81.2174 9.33985 -7.60365,
+                          -68.0041 22.4187 -20.7042,
+                          -80.2264 7.73506 -15.9558,
+                          -78.865 6.10312 -23.8613,
+                          -69.6251 23.9516 -13.961,
+                          -70.7978 25.481 -6.99455,
+                          -80.2264 7.73506 -15.9558,
+                          -68.0041 22.4187 -20.7042,
+                          -69.6251 23.9516 -13.961,
+                          -80.2264 7.73506 -15.9558,
+                          -65.7963 20.8603 -27.6198,
+                          -78.865 6.10312 -23.8613,
+                          -77.1269 4.51132 -31.4254,
+                          -65.7963 20.8603 -27.6198,
+                          -68.0041 22.4187 -20.7042,
+                          -78.865 6.10312 -23.8613,
+                          -63.3942 19.4491 -34.3132,
+                          -77.1269 4.51132 -31.4254,
+                          -75.0726 3.01852 -38.7925,
+                          -63.3942 19.4491 -34.3132,
+                          -65.7963 20.8603 -27.6198,
+                          -77.1269 4.51132 -31.4254,
+                          -61.0938 18.2203 -40.9315,
+                          -75.0726 3.01852 -38.7925,
+                          -72.7221 1.68912 -46.0158,
+                          -61.0938 18.2203 -40.9315,
+                          -63.3942 19.4491 -34.3132,
+                          -75.0726 3.01852 -38.7925,
+                          -63.1233 12.6951 -49.0817,
+                          -72.7221 1.68912 -46.0158,
+                          -70.0791 0.597946 -52.9116,
+                          -63.1233 12.6951 -49.0817,
+                          -61.0938 18.2203 -40.9315,
+                          -72.7221 1.68912 -46.0158,
+                          -64.442 7.43777 -55.687,
+                          -70.0791 0.597946 -52.9116,
+                          -67.0917 -0.152173 -59.068,
+                          -64.442 7.43777 -55.687,
+                          -63.1233 12.6951 -49.0817,
+                          -70.0791 0.597946 -52.9116,
+                          -64.571 2.55538 -61.0149,
+                          -67.0917 -0.152173 -59.068,
+                          -63.83 -0.477376 -64.0104,
+                          -64.571 2.55538 -61.0149,
+                          -64.442 7.43777 -55.687,
+                          -67.0917 -0.152173 -59.068,
+                          -73.7708 29.0674 6.38373e-05,
+                          -75.15 22.8851 0.0180616,
+                          -73.4649 24.9236 -0.00261418,
+                          -73.7708 29.0674 6.38373e-05,
+                          -73.4649 24.9236 -0.00261418,
+                          -71.621 26.9192 0.0239417,
+                          -65.6278 22.0069 -34.3951,
+                          -65.7963 20.8603 -27.6198,
+                          -63.3942 19.4491 -34.3132,
+                          -65.6278 22.0069 -34.3951,
+                          -63.3942 19.4491 -34.3132,
+                          -61.0938 18.2203 -40.9315,
+                          -89.4377 -27.1183 -1.37277,
+                          -87.6219 -27.5756 -4.55886,
+                          -86.1407 -27.4802 -3.6367,
+                          -88.6701 -28.1433 -14.4112,
+                          -86.9938 -27.5607 -5.78288,
+                          -87.6219 -27.5756 -4.55886,
+                          -88.6701 -28.1433 -14.4112,
+                          -87.6219 -27.5756 -4.55886,
+                          -89.4377 -27.1183 -1.37277,
+                          -85.5673 -31.0281 -16.0046,
+                          -85.3086 -27.4701 -6.95846,
+                          -86.3027 -27.5147 -7.01095,
+                          -88.6701 -28.1433 -14.4112,
+                          -86.3027 -27.5147 -7.01095,
+                          -86.9938 -27.5607 -5.78288,
+                          -88.6701 -28.1433 -14.4112,
+                          -85.5673 -31.0281 -16.0046,
+                          -86.3027 -27.5147 -7.01095,
+                          -15.3588 -125.234 -60.2086,
+                          -11.678 -123.288 -58.3637,
+                          -22.2465 -121.417 -58.0653,
+                          0.000557583 -126.624 -60.5453,
+                          -11.678 -123.288 -58.3637,
+                          -15.3588 -125.234 -60.2086,
+                          -30.2564 -121.947 -59.8537,
+                          -22.2465 -121.417 -58.0653,
+                          -31.1057 -119.216 -57.776,
+                          -15.3588 -125.234 -60.2086,
+                          -22.2465 -121.417 -58.0653,
+                          -30.2564 -121.947 -59.8537,
+                          -30.2564 -121.947 -59.8537,
+                          -31.1057 -119.216 -57.776,
+                          -41.7683 -115.785 -57.3222,
+                          -44.7112 -117.236 -59.2864,
+                          -41.7683 -115.785 -57.3222,
+                          -49.9802 -112.465 -56.8133,
+                          -30.2564 -121.947 -59.8537,
+                          -41.7683 -115.785 -57.3222,
+                          -44.7112 -117.236 -59.2864,
+                          -58.5912 -110.791 -58.3905,
+                          -49.9802 -112.465 -56.8133,
+                          -57.5409 -108.613 -56.2627,
+                          -44.7112 -117.236 -59.2864,
+                          -49.9802 -112.465 -56.8133,
+                          -58.5912 -110.791 -58.3905,
+                          -58.5912 -110.791 -58.3905,
+                          -57.5409 -108.613 -56.2627,
+                          -65.0958 -103.2 -55.9755,
+                          -70.7726 -101.161 -57.8426,
+                          -65.0958 -103.2 -55.9755,
+                          -72.8907 -94.3627 -55.3388,
+                          -58.5912 -110.791 -58.3905,
+                          -65.0958 -103.2 -55.9755,
+                          -70.7726 -101.161 -57.8426,
+                          -79.1936 -88.2585 -56.1788,
+                          -72.8907 -94.3627 -55.3388,
+                          -78.6911 -81.9128 -52.9324,
+                          -70.7726 -101.161 -57.8426,
+                          -72.8907 -94.3627 -55.3388,
+                          -79.1936 -88.2585 -56.1788,
+                          -83.452 -74.1634 -51.8789,
+                          -78.6911 -81.9128 -52.9324,
+                          -81.6924 -67.735 -46.928,
+                          -79.1936 -88.2585 -56.1788,
+                          -78.6911 -81.9128 -52.9324,
+                          -83.452 -74.1634 -51.8789,
+                          -85.3056 -61.1075 -44.5544,
+                          -81.6924 -67.735 -46.928,
+                          -82.9679 -56.26 -39.042,
+                          -83.452 -74.1634 -51.8789,
+                          -81.6924 -67.735 -46.928,
+                          -85.3056 -61.1075 -44.5544,
+                          -86.3825 -49.304 -35.2102,
+                          -82.9679 -56.26 -39.042,
+                          -83.7788 -47.6652 -31.8117,
+                          -85.3056 -61.1075 -44.5544,
+                          -82.9679 -56.26 -39.042,
+                          -86.3825 -49.304 -35.2102,
+                          -86.3825 -49.304 -35.2102,
+                          -83.7788 -47.6652 -31.8117,
+                          -84.472 -40.8076 -25.6263,
+                          -87.4766 -38.1178 -25.0881,
+                          -84.472 -40.8076 -25.6263,
+                          -85.5673 -31.0281 -16.0046,
+                          -86.3825 -49.304 -35.2102,
+                          -84.472 -40.8076 -25.6263,
+                          -87.4766 -38.1178 -25.0881,
+                          -87.4766 -38.1178 -25.0881,
+                          -85.5673 -31.0281 -16.0046,
+                          -88.6701 -28.1433 -14.4112 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/left_arm/elbow_link_l.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/left_arm/elbow_link_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..8ab162a7bc5c8dfb1f8e50d40e11c1df8798ca3a
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/left_arm/elbow_link_l.iv
@@ -0,0 +1,1298 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+    Separator {
+        Normal {
+            vector      [ -4.29946e-17 -1 -5.55112e-17,
+                          -4.29946e-17 -1 -5.55112e-17,
+                          -4.29946e-17 -1 -5.55112e-17,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          -4.29946e-17 -1 -5.55112e-17,
+                          -4.29946e-17 -1 -5.55112e-17,
+                          -4.29946e-17 -1 -5.55112e-17,
+                          -8.70494e-17 -0.817349 -0.576143,
+                          -8.70494e-17 -0.817349 -0.576143,
+                          -8.70494e-17 -0.817349 -0.576143,
+                          -8.70494e-17 -0.817349 -0.576143,
+                          -8.70494e-17 -0.817349 -0.576143,
+                          -8.70494e-17 -0.817349 -0.576143,
+                          -4.29946e-17 -1 -5.55112e-17,
+                          -4.29946e-17 -1 -5.55112e-17,
+                          -4.29946e-17 -1 -5.55112e-17,
+                          -9.00954e-17 0 -1,
+                          -9.00954e-17 0 -1,
+                          -9.00954e-17 0 -1,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -4.29946e-17 -1 -5.55112e-17,
+                          -4.29946e-17 -1 -5.55112e-17,
+                          -4.29946e-17 -1 -5.55112e-17,
+                          -5.45342e-17 -0.991213 -0.132275,
+                          -5.45342e-17 -0.991213 -0.132275,
+                          -5.45342e-17 -0.991213 -0.132275,
+                          -4.29946e-17 -1 -5.55112e-17,
+                          -4.29946e-17 -1 -5.55112e-17,
+                          -4.29946e-17 -1 -5.55112e-17,
+                          -9.00954e-17 0 -1,
+                          -9.00954e-17 0 -1,
+                          -9.00954e-17 0 -1,
+                          -9.00954e-17 0 -1,
+                          -9.00954e-17 0 -1,
+                          -9.00954e-17 0 -1,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          -5.45342e-17 -0.991213 -0.132275,
+                          -5.45342e-17 -0.991213 -0.132275,
+                          -5.45342e-17 -0.991213 -0.132275,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -4.29946e-17 -1 -5.55112e-17,
+                          -4.29946e-17 -1 -5.55112e-17,
+                          -4.29946e-17 -1 -5.55112e-17,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          4.29946e-17 1 5.55112e-17,
+                          4.29946e-17 1 5.55112e-17,
+                          4.29946e-17 1 5.55112e-17,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          4.29946e-17 1 5.55112e-17,
+                          4.29946e-17 1 5.55112e-17,
+                          4.29946e-17 1 5.55112e-17,
+                          -9.00954e-17 0 -1,
+                          -9.00954e-17 0 -1,
+                          -9.00954e-17 0 -1,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.96265e-17 0.487179 0.873302,
+                          9.14426e-17 0.756574 0.653908,
+                          8.39126e-17 0.85091 0.525312,
+                          7.77227e-17 0.901695 0.432372,
+                          8.39126e-17 0.85091 0.525312,
+                          9.14426e-17 0.756574 0.653908,
+                          9.94931e-17 0.50314 0.864205,
+                          9.14426e-17 0.756574 0.653908,
+                          9.96265e-17 0.487179 0.873302,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          4.29946e-17 1 6.02083e-16,
+                          4.29946e-17 1 6.02083e-16,
+                          4.29946e-17 1 6.02083e-16,
+                          4.29946e-17 1 6.02083e-16,
+                          4.29946e-17 1 6.02083e-16,
+                          4.29946e-17 1 6.02083e-16,
+                          -9.00954e-17 0 -1,
+                          -9.00954e-17 0 -1,
+                          -9.41088e-17 -0.707107 -0.707107,
+                          -3.33053e-17 0.707107 -0.707107,
+                          -3.33053e-17 0.707107 -0.707107,
+                          -9.00954e-17 0 -1,
+                          -3.33053e-17 0.707107 -0.707107,
+                          -9.00954e-17 0 -1,
+                          -9.00954e-17 0 -1,
+                          -9.41088e-17 -0.707107 -0.707107,
+                          -9.41088e-17 -0.707107 -0.707107,
+                          -4.29946e-17 -1 -1.16741e-16,
+                          -9.41088e-17 -0.707107 -0.707107,
+                          -9.00954e-17 0 -1,
+                          -9.41088e-17 -0.707107 -0.707107,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -4.29946e-17 -1 -5.60831e-16,
+                          -4.29946e-17 -1 -1.16741e-16,
+                          3.33053e-17 -0.707107 0.707107,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -9.41088e-17 -0.707107 -0.707107,
+                          -4.29946e-17 -1 -1.16741e-16,
+                          -4.29946e-17 -1 -5.60831e-16,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          3.33053e-17 -0.707107 0.707107,
+                          3.33053e-17 -0.707107 0.707107,
+                          9.00954e-17 -1.22461e-16 1,
+                          -4.29946e-17 -1 -5.60831e-16,
+                          3.33053e-17 -0.707107 0.707107,
+                          3.33053e-17 -0.707107 0.707107,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          9.00954e-17 1.22461e-16 1,
+                          9.00954e-17 1.22461e-16 1,
+                          9.41088e-17 0.707107 0.707107,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          3.33053e-17 -0.707107 0.707107,
+                          9.00954e-17 -1.22461e-16 1,
+                          9.00954e-17 -1.22461e-16 1,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          9.41088e-17 0.707107 0.707107,
+                          9.41088e-17 0.707107 0.707107,
+                          4.29946e-17 1 -5.71917e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          9.00954e-17 1.22461e-16 1,
+                          9.41088e-17 0.707107 0.707107,
+                          9.41088e-17 0.707107 0.707107,
+                          4.29946e-17 1 4.3837e-16,
+                          4.29946e-17 1 -5.71917e-18,
+                          -3.33053e-17 0.707107 -0.707107,
+                          9.41088e-17 0.707107 0.707107,
+                          4.29946e-17 1 -5.71917e-18,
+                          4.29946e-17 1 4.3837e-16,
+                          4.29946e-17 1 4.3837e-16,
+                          -3.33053e-17 0.707107 -0.707107,
+                          -3.33053e-17 0.707107 -0.707107,
+                          -8.70494e-17 -0.817349 -0.576143,
+                          -8.70494e-17 -0.817349 -0.576143,
+                          -9.91062e-17 -0.319211 -0.947684,
+                          -9.91062e-17 -0.319211 -0.947684,
+                          -9.91062e-17 -0.319211 -0.947684,
+                          -7.28899e-17 0.302201 -0.953244,
+                          -8.70494e-17 -0.817349 -0.576143,
+                          -9.91062e-17 -0.319211 -0.947684,
+                          -9.91062e-17 -0.319211 -0.947684,
+                          -7.28899e-17 0.302201 -0.953244,
+                          -7.28899e-17 0.302201 -0.953244,
+                          -1.85246e-17 0.806908 -0.590677,
+                          -9.91062e-17 -0.319211 -0.947684,
+                          -7.28899e-17 0.302201 -0.953244,
+                          -7.28899e-17 0.302201 -0.953244,
+                          -1.85246e-17 0.806908 -0.590677,
+                          -1.85246e-17 0.806908 -0.590677,
+                          4.29946e-17 1 1.77972e-16,
+                          -7.28899e-17 0.302201 -0.953244,
+                          -1.85246e-17 0.806908 -0.590677,
+                          -1.85246e-17 0.806908 -0.590677,
+                          -1.85246e-17 0.806908 -0.590677,
+                          4.29946e-17 1 1.77972e-16,
+                          4.29946e-17 1 1.77972e-16,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          4.29946e-17 1 6.02083e-16,
+                          4.29946e-17 1 6.02083e-16,
+                          4.29946e-17 1 6.02083e-16,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          0.707107 0.707107 3.73288e-17,
+                          0.707107 0.707107 3.73288e-17,
+                          0.707107 0.707107 3.73288e-17,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          4.29946e-17 1 5.55112e-17,
+                          4.29946e-17 1 5.55112e-17,
+                          4.29946e-17 1 5.55112e-17,
+                          4.29946e-17 1 5.55112e-17,
+                          4.29946e-17 1 5.55112e-17,
+                          4.29946e-17 1 5.55112e-17,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          0.707107 0.707107 3.73288e-17,
+                          0.707107 0.707107 3.73288e-17,
+                          0.707107 0.707107 3.73288e-17,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          0.707107 -0.707107 -4.11758e-17,
+                          0.707107 -0.707107 -4.11758e-17,
+                          0.707107 -0.707107 -4.11758e-17,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          -4.29946e-17 -1 -5.55112e-17,
+                          -4.29946e-17 -1 -5.55112e-17,
+                          -4.29946e-17 -1 -5.55112e-17,
+                          0.707107 -0.707107 -4.11758e-17,
+                          0.707107 -0.707107 -4.11758e-17,
+                          0.707107 -0.707107 -4.11758e-17,
+                          -0.707107 -0.707107 -3.73288e-17,
+                          -0.707107 -0.707107 -3.73288e-17,
+                          -0.707107 -0.707107 -3.73288e-17,
+                          -4.29946e-17 -1 -5.55112e-17,
+                          -4.29946e-17 -1 -5.55112e-17,
+                          -4.29946e-17 -1 -5.55112e-17,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -0.707107 -0.707107 -3.73288e-17,
+                          -0.707107 -0.707107 -3.73288e-17,
+                          -0.707107 -0.707107 -3.73288e-17,
+                          -0.707107 0.707107 4.11758e-17,
+                          -0.707107 0.707107 4.11758e-17,
+                          -0.707107 0.707107 4.11758e-17,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -0.707107 0.707107 4.11758e-17,
+                          -0.707107 0.707107 4.11758e-17,
+                          -0.707107 0.707107 4.11758e-17,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -9.00954e-17 0 -1,
+                          -9.00954e-17 0 -1,
+                          -9.41088e-17 -0.707107 -0.707107,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -3.33053e-17 0.707107 -0.707107,
+                          -3.33053e-17 0.707107 -0.707107,
+                          -9.00954e-17 0 -1,
+                          -3.33053e-17 0.707107 -0.707107,
+                          -9.00954e-17 0 -1,
+                          -9.00954e-17 0 -1,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -9.41088e-17 -0.707107 -0.707107,
+                          -9.41088e-17 -0.707107 -0.707107,
+                          -4.29946e-17 -1 -5.60831e-16,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -9.41088e-17 -0.707107 -0.707107,
+                          -9.00954e-17 0 -1,
+                          -9.41088e-17 -0.707107 -0.707107,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -4.29946e-17 -1 -1.16741e-16,
+                          -4.29946e-17 -1 -5.60831e-16,
+                          3.33053e-17 -0.707107 0.707107,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -9.41088e-17 -0.707107 -0.707107,
+                          -4.29946e-17 -1 -5.60831e-16,
+                          -4.29946e-17 -1 -1.16741e-16,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          3.33053e-17 -0.707107 0.707107,
+                          3.33053e-17 -0.707107 0.707107,
+                          9.00954e-17 -1.22461e-16 1,
+                          -4.29946e-17 -1 -1.16741e-16,
+                          3.33053e-17 -0.707107 0.707107,
+                          3.33053e-17 -0.707107 0.707107,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          9.00954e-17 1.22461e-16 1,
+                          9.00954e-17 1.22461e-16 1,
+                          9.41088e-17 0.707107 0.707107,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          3.33053e-17 -0.707107 0.707107,
+                          9.00954e-17 -1.22461e-16 1,
+                          9.00954e-17 -1.22461e-16 1,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          9.41088e-17 0.707107 0.707107,
+                          9.41088e-17 0.707107 0.707107,
+                          4.29946e-17 1 4.3837e-16,
+                          9.00954e-17 1.22461e-16 1,
+                          9.41088e-17 0.707107 0.707107,
+                          9.41088e-17 0.707107 0.707107,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          4.29946e-17 1 -5.71917e-18,
+                          4.29946e-17 1 4.3837e-16,
+                          -3.33053e-17 0.707107 -0.707107,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          9.41088e-17 0.707107 0.707107,
+                          4.29946e-17 1 4.3837e-16,
+                          4.29946e-17 1 -5.71917e-18,
+                          4.29946e-17 1 -5.71917e-18,
+                          -3.33053e-17 0.707107 -0.707107,
+                          -3.33053e-17 0.707107 -0.707107,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          9.67536e-17 0.195154 0.980773,
+                          9.96265e-17 0.487179 0.873302,
+                          9.00954e-17 3.06152e-16 1,
+                          9.38796e-17 0.0981315 0.995173,
+                          9.00954e-17 3.06152e-16 1,
+                          9.00954e-17 3.06152e-16 1,
+                          9.38796e-17 0.0981315 0.995173,
+                          9.67536e-17 0.195154 0.980773,
+                          9.00954e-17 3.06152e-16 1,
+                          -5.45342e-17 -0.991213 -0.132275,
+                          -5.45342e-17 -0.991213 -0.132275,
+                          -8.83611e-17 -0.801185 -0.598416,
+                          -8.94005e-17 -0.78729 -0.616583,
+                          -8.83611e-17 -0.801185 -0.598416,
+                          -9.97976e-17 -0.408139 -0.91292,
+                          -7.45881e-17 -0.921632 -0.388066,
+                          -5.45342e-17 -0.991213 -0.132275,
+                          -8.83611e-17 -0.801185 -0.598416,
+                          -7.45881e-17 -0.921632 -0.388066,
+                          -8.83611e-17 -0.801185 -0.598416,
+                          -8.94005e-17 -0.78729 -0.616583,
+                          -9.95799e-17 -0.36598 -0.930623,
+                          -9.97976e-17 -0.408139 -0.91292,
+                          -8.59456e-17 0.0883282 -0.996091,
+                          -9.79308e-17 -0.59763 -0.801772,
+                          -9.97976e-17 -0.408139 -0.91292,
+                          -9.95799e-17 -0.36598 -0.930623,
+                          -8.94005e-17 -0.78729 -0.616583,
+                          -9.97976e-17 -0.408139 -0.91292,
+                          -9.79308e-17 -0.59763 -0.801772,
+                          -8.22638e-17 0.156373 -0.987698,
+                          -8.59456e-17 0.0883282 -0.996091,
+                          -5.03152e-17 0.562414 -0.826856,
+                          -9.42323e-17 -0.108618 -0.994084,
+                          -8.59456e-17 0.0883282 -0.996091,
+                          -8.22638e-17 0.156373 -0.987698,
+                          -9.95799e-17 -0.36598 -0.930623,
+                          -8.59456e-17 0.0883282 -0.996091,
+                          -9.42323e-17 -0.108618 -0.994084,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -4.22347e-17 0.635542 -0.772066,
+                          -5.03152e-17 0.562414 -0.826856,
+                          -1.935e-18 0.893985 -0.448097,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -6.45156e-17 0.410375 -0.911917,
+                          -5.03152e-17 0.562414 -0.826856,
+                          -4.22347e-17 0.635542 -0.772066,
+                          -8.22638e-17 0.156373 -0.987698,
+                          -5.03152e-17 0.562414 -0.826856,
+                          -6.45156e-17 0.410375 -0.911917,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          -1 1.13132e-18 2.72025e-18,
+                          9.45456e-18 0.939235 -0.343274,
+                          -1.935e-18 0.893985 -0.448097,
+                          4.69355e-17 0.999022 0.0442083,
+                          -1.69867e-17 0.816056 -0.577973,
+                          -1.935e-18 0.893985 -0.448097,
+                          9.45456e-18 0.939235 -0.343274,
+                          -4.22347e-17 0.635542 -0.772066,
+                          -1.935e-18 0.893985 -0.448097,
+                          -1.69867e-17 0.816056 -0.577973,
+                          5.85331e-17 0.983614 0.180288,
+                          4.69355e-17 0.999022 0.0442083,
+                          8.39126e-17 0.85091 0.525312,
+                          3.52315e-17 0.996427 -0.0844598,
+                          4.69355e-17 0.999022 0.0442083,
+                          5.85331e-17 0.983614 0.180288,
+                          9.45456e-18 0.939235 -0.343274,
+                          4.69355e-17 0.999022 0.0442083,
+                          3.52315e-17 0.996427 -0.0844598,
+                          5.85331e-17 0.983614 0.180288,
+                          8.39126e-17 0.85091 0.525312,
+                          7.77227e-17 0.901695 0.432372,
+                          9.94931e-17 0.50314 0.864205,
+                          9.96265e-17 0.487179 0.873302,
+                          9.67536e-17 0.195154 0.980773,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          9.00954e-17 0 1,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18,
+                          1 -1.13132e-18 -2.72025e-18 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -30.5 -28.5 25.5,
+                          36.5 -28.5 17,
+                          36.5 -28.5 25.5,
+                          36.5 -11.0342 -7.77794,
+                          36.5 -28.5 25.5,
+                          36.5 -28.5 17,
+                          -11.3909 -27.5 25.5,
+                          -30.5 -28.5 25.5,
+                          36.5 -28.5 25.5,
+                          36.5 -6.01041 6.01041,
+                          36.5 -7.46483e-14 8.5,
+                          36.5 -28.5 25.5,
+                          36.5 6.01041 6.01041,
+                          36.5 -28.5 25.5,
+                          36.5 -7.46483e-14 8.5,
+                          36.5 -8.5 8.52651e-14,
+                          36.5 -6.01041 6.01041,
+                          36.5 -28.5 25.5,
+                          36.5 -11.0342 -7.77794,
+                          36.5 -8.5 8.52651e-14,
+                          36.5 -28.5 25.5,
+                          36.5 13.5 25.5,
+                          36.5 -28.5 25.5,
+                          36.5 6.01041 6.01041,
+                          30.5 13.5 25.5,
+                          36.5 -28.5 25.5,
+                          36.5 13.5 25.5,
+                          27.5 11.3909 25.5,
+                          36.5 -28.5 25.5,
+                          30.5 13.5 25.5,
+                          11.3909 -27.5 25.5,
+                          -11.3909 -27.5 25.5,
+                          36.5 -28.5 25.5,
+                          27.5 -11.3909 25.5,
+                          11.3909 -27.5 25.5,
+                          36.5 -28.5 25.5,
+                          27.5 11.3909 25.5,
+                          27.5 -11.3909 25.5,
+                          36.5 -28.5 25.5,
+                          -30.5 -28.5 25.5,
+                          30.5 -28.5 17,
+                          36.5 -28.5 17,
+                          30.5 -11.0342 -7.77794,
+                          36.5 -28.5 17,
+                          30.5 -28.5 17,
+                          36.5 -11.0342 -7.77794,
+                          36.5 -28.5 17,
+                          30.5 -11.0342 -7.77794,
+                          -30.5 -28.5 25.5,
+                          -30.5 -28.5 17,
+                          30.5 -28.5 17,
+                          30.5 13.5 17,
+                          30.5 -28.5 17,
+                          -30.5 -28.5 17,
+                          30.5 -6.01041 6.01041,
+                          30.5 -28.5 17,
+                          30.5 13.5 17,
+                          30.5 -6.01041 6.01041,
+                          30.5 -8.5 8.88178e-14,
+                          30.5 -28.5 17,
+                          30.5 -11.0342 -7.77794,
+                          30.5 -28.5 17,
+                          30.5 -8.5 8.88178e-14,
+                          -36.5 -28.5 26,
+                          -36.5 -28.5 17,
+                          -30.5 -28.5 17,
+                          -36.5 -25.7717 -3.44439,
+                          -30.5 -28.5 17,
+                          -36.5 -28.5 17,
+                          -30.5 -28.5 25.5,
+                          -36.5 -28.5 26,
+                          -30.5 -28.5 17,
+                          -30.5 19.6788 17,
+                          30.5 28.5 17,
+                          -30.5 -28.5 17,
+                          30.5 13.5 17,
+                          -30.5 -28.5 17,
+                          30.5 28.5 17,
+                          -30.5 -7.45725e-14 8.5,
+                          -30.5 19.6788 17,
+                          -30.5 -28.5 17,
+                          -30.5 -25.7717 -3.44439,
+                          -30.5 -28.5 17,
+                          -36.5 -25.7717 -3.44439,
+                          -30.5 -6.01041 6.01041,
+                          -30.5 -7.45725e-14 8.5,
+                          -30.5 -28.5 17,
+                          -30.5 -8.5 8.52651e-14,
+                          -30.5 -6.01041 6.01041,
+                          -30.5 -28.5 17,
+                          -30.5 -9.51392 -24.2046,
+                          -30.5 -8.5 8.52651e-14,
+                          -30.5 -28.5 17,
+                          -30.5 -23.9616 -10.0973,
+                          -30.5 -28.5 17,
+                          -30.5 -25.7717 -3.44439,
+                          -30.5 -15.5374 -20.8536,
+                          -30.5 -9.51392 -24.2046,
+                          -30.5 -28.5 17,
+                          -30.5 -20.4683 -16.0388,
+                          -30.5 -15.5374 -20.8536,
+                          -30.5 -28.5 17,
+                          -30.5 -23.9616 -10.0973,
+                          -30.5 -20.4683 -16.0388,
+                          -30.5 -28.5 17,
+                          -36.5 0.00876132 26,
+                          -36.5 -28.5 17,
+                          -36.5 -28.5 26,
+                          -36.5 -25.7717 -3.44439,
+                          -36.5 -28.5 17,
+                          -36.5 0.00876132 26,
+                          -30.5 -28.5 25.5,
+                          -30.5 -28.5 26,
+                          -36.5 -28.5 26,
+                          -30.5 0.00438816 26,
+                          -36.5 -28.5 26,
+                          -30.5 -28.5 26,
+                          -30.5 0.00438816 26,
+                          -36.5 0.00876132 26,
+                          -36.5 -28.5 26,
+                          -30.5 5.07928 25.5,
+                          -30.5 -28.5 26,
+                          -30.5 -28.5 25.5,
+                          -30.5 5.07928 25.5,
+                          -30.5 0.00438816 26,
+                          -30.5 -28.5 26,
+                          -27.5 -11.3909 25.5,
+                          -30.5 5.07928 25.5,
+                          -30.5 -28.5 25.5,
+                          -27.5 -11.3909 25.5,
+                          -30.5 -28.5 25.5,
+                          -11.3909 -27.5 25.5,
+                          30.5 28.5 25.5,
+                          -30.5 28.5 17,
+                          -30.5 28.5 25.5,
+                          -30.5 19.6788 17,
+                          -30.5 28.5 25.5,
+                          -30.5 28.5 17,
+                          11.3909 27.5 25.5,
+                          30.5 28.5 25.5,
+                          -30.5 28.5 25.5,
+                          -30.5 13.0883 22.4685,
+                          -30.5 28.5 25.5,
+                          -30.5 19.6788 17,
+                          -30.5 13.0883 22.4685,
+                          -30.5 5.07928 25.5,
+                          -30.5 28.5 25.5,
+                          -27.5 -11.3909 25.5,
+                          -30.5 28.5 25.5,
+                          -30.5 5.07928 25.5,
+                          -11.3909 27.5 25.5,
+                          11.3909 27.5 25.5,
+                          -30.5 28.5 25.5,
+                          -27.5 11.3909 25.5,
+                          -11.3909 27.5 25.5,
+                          -30.5 28.5 25.5,
+                          -27.5 -11.3909 25.5,
+                          -27.5 11.3909 25.5,
+                          -30.5 28.5 25.5,
+                          30.5 28.5 25.5,
+                          30.5 28.5 17,
+                          -30.5 28.5 17,
+                          -30.5 19.6788 17,
+                          -30.5 28.5 17,
+                          30.5 28.5 17,
+                          30.5 13.5 25.5,
+                          30.5 28.5 17,
+                          30.5 28.5 25.5,
+                          30.5 13.5 25.5,
+                          30.5 13.5 17,
+                          30.5 28.5 17,
+                          11.3909 27.5 25.5,
+                          30.5 13.5 25.5,
+                          30.5 28.5 25.5,
+                          -36.5 12.6722 22.7056,
+                          -30.5 19.6788 17,
+                          -36.5 22.1323 13.6548,
+                          -30.5 23.4531 11.2377,
+                          -36.5 22.1323 13.6548,
+                          -30.5 19.6788 17,
+                          -30.5 13.0883 22.4685,
+                          -30.5 19.6788 17,
+                          -36.5 12.6722 22.7056,
+                          -30.5 6.01041 6.01041,
+                          -30.5 19.6788 17,
+                          -30.5 -7.45725e-14 8.5,
+                          -30.5 6.01041 6.01041,
+                          -30.5 8.5 8.88178e-14,
+                          -30.5 19.6788 17,
+                          -30.5 16.5303 -20.0826,
+                          -30.5 19.6788 17,
+                          -30.5 8.5 8.88178e-14,
+                          -30.5 21.2251 -15.0352,
+                          -30.5 23.4531 11.2377,
+                          -30.5 19.6788 17,
+                          -30.5 16.5303 -20.0826,
+                          -30.5 21.2251 -15.0352,
+                          -30.5 19.6788 17,
+                          30.5 6.01041 6.01041,
+                          30.5 -7.46415e-14 8.5,
+                          30.5 13.5 17,
+                          30.5 -6.01041 6.01041,
+                          30.5 13.5 17,
+                          30.5 -7.46415e-14 8.5,
+                          30.5 8.5 9.23706e-14,
+                          30.5 6.01041 6.01041,
+                          30.5 13.5 17,
+                          30.5 10.893 -7.97394,
+                          30.5 8.5 9.23706e-14,
+                          30.5 13.5 17,
+                          30.5 13.5 9.23706e-14,
+                          30.5 10.893 -7.97394,
+                          30.5 13.5 17,
+                          36.5 13.5 8.88178e-14,
+                          30.5 13.5 9.23706e-14,
+                          30.5 13.5 17,
+                          30.5 13.5 25.5,
+                          36.5 13.5 8.88178e-14,
+                          30.5 13.5 17,
+                          36.5 -7.46483e-14 8.5,
+                          30.5 -7.46415e-14 8.5,
+                          30.5 6.01041 6.01041,
+                          36.5 -6.01041 6.01041,
+                          30.5 -6.01041 6.01041,
+                          30.5 -7.46415e-14 8.5,
+                          36.5 -6.01041 6.01041,
+                          30.5 -7.46415e-14 8.5,
+                          36.5 -7.46483e-14 8.5,
+                          36.5 6.01041 6.01041,
+                          30.5 6.01041 6.01041,
+                          30.5 8.5 9.23706e-14,
+                          36.5 6.01041 6.01041,
+                          36.5 -7.46483e-14 8.5,
+                          30.5 6.01041 6.01041,
+                          30.5 4.07972 -12.8688,
+                          30.5 6.01041 -6.01041,
+                          30.5 8.5 9.23706e-14,
+                          36.5 8.5 8.88178e-14,
+                          30.5 8.5 9.23706e-14,
+                          30.5 6.01041 -6.01041,
+                          30.5 10.893 -7.97394,
+                          30.5 4.07972 -12.8688,
+                          30.5 8.5 9.23706e-14,
+                          36.5 6.01041 6.01041,
+                          30.5 8.5 9.23706e-14,
+                          36.5 8.5 8.88178e-14,
+                          30.5 4.07972 -12.8688,
+                          30.5 -7.46415e-14 -8.5,
+                          30.5 6.01041 -6.01041,
+                          36.5 6.01041 -6.01041,
+                          30.5 6.01041 -6.01041,
+                          30.5 -7.46415e-14 -8.5,
+                          36.5 8.5 8.88178e-14,
+                          30.5 6.01041 -6.01041,
+                          36.5 6.01041 -6.01041,
+                          30.5 -4.30924 -12.7934,
+                          30.5 -6.01041 -6.01041,
+                          30.5 -7.46415e-14 -8.5,
+                          36.5 -7.46483e-14 -8.5,
+                          30.5 -7.46415e-14 -8.5,
+                          30.5 -6.01041 -6.01041,
+                          30.5 4.07972 -12.8688,
+                          30.5 -4.30924 -12.7934,
+                          30.5 -7.46415e-14 -8.5,
+                          36.5 6.01041 -6.01041,
+                          30.5 -7.46415e-14 -8.5,
+                          36.5 -7.46483e-14 -8.5,
+                          30.5 -11.0342 -7.77794,
+                          30.5 -8.5 8.88178e-14,
+                          30.5 -6.01041 -6.01041,
+                          36.5 -6.01041 -6.01041,
+                          30.5 -6.01041 -6.01041,
+                          30.5 -8.5 8.88178e-14,
+                          30.5 -4.30924 -12.7934,
+                          30.5 -11.0342 -7.77794,
+                          30.5 -6.01041 -6.01041,
+                          36.5 -7.46483e-14 -8.5,
+                          30.5 -6.01041 -6.01041,
+                          36.5 -6.01041 -6.01041,
+                          36.5 -8.5 8.52651e-14,
+                          30.5 -8.5 8.88178e-14,
+                          30.5 -6.01041 6.01041,
+                          36.5 -6.01041 -6.01041,
+                          30.5 -8.5 8.88178e-14,
+                          36.5 -8.5 8.52651e-14,
+                          36.5 -8.5 8.52651e-14,
+                          30.5 -6.01041 6.01041,
+                          36.5 -6.01041 6.01041,
+                          36.5 -11.0342 -7.77794,
+                          30.5 -11.0342 -7.77794,
+                          30.5 -4.30924 -12.7934,
+                          36.5 -4.30924 -12.7934,
+                          30.5 -4.30924 -12.7934,
+                          30.5 4.07972 -12.8688,
+                          36.5 -11.0342 -7.77794,
+                          30.5 -4.30924 -12.7934,
+                          36.5 -4.30924 -12.7934,
+                          36.5 4.07972 -12.8688,
+                          30.5 4.07972 -12.8688,
+                          30.5 10.893 -7.97394,
+                          36.5 -4.30924 -12.7934,
+                          30.5 4.07972 -12.8688,
+                          36.5 4.07972 -12.8688,
+                          36.5 10.893 -7.97394,
+                          30.5 10.893 -7.97394,
+                          30.5 13.5 9.23706e-14,
+                          36.5 4.07972 -12.8688,
+                          30.5 10.893 -7.97394,
+                          36.5 10.893 -7.97394,
+                          36.5 10.893 -7.97394,
+                          30.5 13.5 9.23706e-14,
+                          36.5 13.5 8.88178e-14,
+                          36.5 -4.30924 -12.7934,
+                          36.5 -6.01041 -6.01041,
+                          36.5 -8.5 8.52651e-14,
+                          36.5 -11.0342 -7.77794,
+                          36.5 -4.30924 -12.7934,
+                          36.5 -8.5 8.52651e-14,
+                          36.5 -4.30924 -12.7934,
+                          36.5 -7.46483e-14 -8.5,
+                          36.5 -6.01041 -6.01041,
+                          36.5 4.07972 -12.8688,
+                          36.5 6.01041 -6.01041,
+                          36.5 -7.46483e-14 -8.5,
+                          36.5 -4.30924 -12.7934,
+                          36.5 4.07972 -12.8688,
+                          36.5 -7.46483e-14 -8.5,
+                          36.5 10.893 -7.97394,
+                          36.5 8.5 8.88178e-14,
+                          36.5 6.01041 -6.01041,
+                          36.5 4.07972 -12.8688,
+                          36.5 10.893 -7.97394,
+                          36.5 6.01041 -6.01041,
+                          36.5 13.5 8.88178e-14,
+                          36.5 6.01041 6.01041,
+                          36.5 8.5 8.88178e-14,
+                          36.5 10.893 -7.97394,
+                          36.5 13.5 8.88178e-14,
+                          36.5 8.5 8.88178e-14,
+                          36.5 13.5 8.88178e-14,
+                          36.5 13.5 25.5,
+                          36.5 6.01041 6.01041,
+                          30.5 13.5 25.5,
+                          36.5 13.5 25.5,
+                          36.5 13.5 8.88178e-14,
+                          -27.5 11.3909 46.5,
+                          27.5 11.3909 46.5,
+                          11.3909 27.5 46.5,
+                          11.3909 27.5 25.5,
+                          11.3909 27.5 46.5,
+                          27.5 11.3909 46.5,
+                          -11.3909 27.5 46.5,
+                          -27.5 11.3909 46.5,
+                          11.3909 27.5 46.5,
+                          -11.3909 27.5 25.5,
+                          -11.3909 27.5 46.5,
+                          11.3909 27.5 46.5,
+                          -11.3909 27.5 25.5,
+                          11.3909 27.5 46.5,
+                          11.3909 27.5 25.5,
+                          -27.5 -11.3909 46.5,
+                          27.5 -11.3909 46.5,
+                          27.5 11.3909 46.5,
+                          27.5 11.3909 25.5,
+                          27.5 11.3909 46.5,
+                          27.5 -11.3909 46.5,
+                          -27.5 11.3909 46.5,
+                          -27.5 -11.3909 46.5,
+                          27.5 11.3909 46.5,
+                          11.3909 27.5 25.5,
+                          27.5 11.3909 46.5,
+                          27.5 11.3909 25.5,
+                          -11.3909 -27.5 46.5,
+                          11.3909 -27.5 46.5,
+                          27.5 -11.3909 46.5,
+                          27.5 -11.3909 25.5,
+                          27.5 -11.3909 46.5,
+                          11.3909 -27.5 46.5,
+                          -27.5 -11.3909 46.5,
+                          -11.3909 -27.5 46.5,
+                          27.5 -11.3909 46.5,
+                          27.5 11.3909 25.5,
+                          27.5 -11.3909 46.5,
+                          27.5 -11.3909 25.5,
+                          11.3909 -27.5 25.5,
+                          11.3909 -27.5 46.5,
+                          -11.3909 -27.5 46.5,
+                          27.5 -11.3909 25.5,
+                          11.3909 -27.5 46.5,
+                          11.3909 -27.5 25.5,
+                          -11.3909 -27.5 25.5,
+                          -11.3909 -27.5 46.5,
+                          -27.5 -11.3909 46.5,
+                          11.3909 -27.5 25.5,
+                          -11.3909 -27.5 46.5,
+                          -11.3909 -27.5 25.5,
+                          -27.5 -11.3909 25.5,
+                          -27.5 -11.3909 46.5,
+                          -27.5 11.3909 46.5,
+                          -27.5 -11.3909 25.5,
+                          -11.3909 -27.5 25.5,
+                          -27.5 -11.3909 46.5,
+                          -27.5 11.3909 25.5,
+                          -27.5 11.3909 46.5,
+                          -11.3909 27.5 46.5,
+                          -27.5 -11.3909 25.5,
+                          -27.5 11.3909 46.5,
+                          -27.5 11.3909 25.5,
+                          -27.5 11.3909 25.5,
+                          -11.3909 27.5 46.5,
+                          -11.3909 27.5 25.5,
+                          -36.5 0.00876132 26,
+                          -36.5 6.01041 6.01041,
+                          -36.5 -7.45657e-14 8.5,
+                          -30.5 -7.45725e-14 8.5,
+                          -36.5 -7.45657e-14 8.5,
+                          -36.5 6.01041 6.01041,
+                          -36.5 0.00876132 26,
+                          -36.5 -7.45657e-14 8.5,
+                          -36.5 -6.01041 6.01041,
+                          -30.5 -6.01041 6.01041,
+                          -36.5 -6.01041 6.01041,
+                          -36.5 -7.45657e-14 8.5,
+                          -30.5 -6.01041 6.01041,
+                          -36.5 -7.45657e-14 8.5,
+                          -30.5 -7.45725e-14 8.5,
+                          -36.5 12.6722 22.7056,
+                          -36.5 8.5 9.23706e-14,
+                          -36.5 6.01041 6.01041,
+                          -30.5 6.01041 6.01041,
+                          -36.5 6.01041 6.01041,
+                          -36.5 8.5 9.23706e-14,
+                          -36.5 12.6722 22.7056,
+                          -36.5 6.01041 6.01041,
+                          -36.5 0.00876132 26,
+                          -30.5 6.01041 6.01041,
+                          -30.5 -7.45725e-14 8.5,
+                          -36.5 6.01041 6.01041,
+                          -36.5 2.30132 -25.9076,
+                          -36.5 6.01041 -6.01041,
+                          -36.5 8.5 9.23706e-14,
+                          -30.5 8.5 8.88178e-14,
+                          -36.5 8.5 9.23706e-14,
+                          -36.5 6.01041 -6.01041,
+                          -36.5 14.6286 -21.5071,
+                          -36.5 2.30132 -25.9076,
+                          -36.5 8.5 9.23706e-14,
+                          -36.5 12.6722 22.7056,
+                          -36.5 14.6286 -21.5071,
+                          -36.5 8.5 9.23706e-14,
+                          -30.5 6.01041 6.01041,
+                          -36.5 8.5 9.23706e-14,
+                          -30.5 8.5 8.88178e-14,
+                          -36.5 2.30132 -25.9076,
+                          -36.5 -7.45657e-14 -8.5,
+                          -36.5 6.01041 -6.01041,
+                          -30.5 6.01041 -6.01041,
+                          -36.5 6.01041 -6.01041,
+                          -36.5 -7.45657e-14 -8.5,
+                          -30.5 8.5 8.88178e-14,
+                          -36.5 6.01041 -6.01041,
+                          -30.5 6.01041 -6.01041,
+                          -36.5 -10.608 -23.745,
+                          -36.5 -6.01041 -6.01041,
+                          -36.5 -7.45657e-14 -8.5,
+                          -30.5 -7.45725e-14 -8.5,
+                          -36.5 -7.45657e-14 -8.5,
+                          -36.5 -6.01041 -6.01041,
+                          -36.5 2.30132 -25.9076,
+                          -36.5 -10.608 -23.745,
+                          -36.5 -7.45657e-14 -8.5,
+                          -30.5 6.01041 -6.01041,
+                          -36.5 -7.45657e-14 -8.5,
+                          -30.5 -7.45725e-14 -8.5,
+                          -36.5 -10.608 -23.745,
+                          -36.5 -8.5 8.88178e-14,
+                          -36.5 -6.01041 -6.01041,
+                          -30.5 -6.01041 -6.01041,
+                          -36.5 -6.01041 -6.01041,
+                          -36.5 -8.5 8.88178e-14,
+                          -30.5 -7.45725e-14 -8.5,
+                          -36.5 -6.01041 -6.01041,
+                          -30.5 -6.01041 -6.01041,
+                          -36.5 0.00876132 26,
+                          -36.5 -6.01041 6.01041,
+                          -36.5 -8.5 8.88178e-14,
+                          -30.5 -8.5 8.52651e-14,
+                          -36.5 -8.5 8.88178e-14,
+                          -36.5 -6.01041 6.01041,
+                          -36.5 -20.8306 -15.5651,
+                          -36.5 0.00876132 26,
+                          -36.5 -8.5 8.88178e-14,
+                          -36.5 -10.608 -23.745,
+                          -36.5 -20.8306 -15.5651,
+                          -36.5 -8.5 8.88178e-14,
+                          -30.5 -6.01041 -6.01041,
+                          -36.5 -8.5 8.88178e-14,
+                          -30.5 -8.5 8.52651e-14,
+                          -30.5 -8.5 8.52651e-14,
+                          -36.5 -6.01041 6.01041,
+                          -30.5 -6.01041 6.01041,
+                          -36.5 -20.8306 -15.5651,
+                          -36.5 -25.7717 -3.44439,
+                          -36.5 0.00876132 26,
+                          -30.5 5.07928 25.5,
+                          -36.5 12.6722 22.7056,
+                          -36.5 0.00876132 26,
+                          -30.5 2.55625 25.8745,
+                          -36.5 0.00876132 26,
+                          -30.5 0.00438816 26,
+                          -30.5 2.55625 25.8745,
+                          -30.5 5.07928 25.5,
+                          -36.5 0.00876132 26,
+                          -30.5 -25.7717 -3.44439,
+                          -36.5 -25.7717 -3.44439,
+                          -36.5 -20.8306 -15.5651,
+                          -30.5 -20.4683 -16.0388,
+                          -36.5 -20.8306 -15.5651,
+                          -36.5 -10.608 -23.745,
+                          -30.5 -23.9616 -10.0973,
+                          -30.5 -25.7717 -3.44439,
+                          -36.5 -20.8306 -15.5651,
+                          -30.5 -23.9616 -10.0973,
+                          -36.5 -20.8306 -15.5651,
+                          -30.5 -20.4683 -16.0388,
+                          -30.5 -9.51392 -24.2046,
+                          -36.5 -10.608 -23.745,
+                          -36.5 2.30132 -25.9076,
+                          -30.5 -15.5374 -20.8536,
+                          -36.5 -10.608 -23.745,
+                          -30.5 -9.51392 -24.2046,
+                          -30.5 -20.4683 -16.0388,
+                          -36.5 -10.608 -23.745,
+                          -30.5 -15.5374 -20.8536,
+                          -30.5 4.07201 -25.6889,
+                          -36.5 2.30132 -25.9076,
+                          -36.5 14.6286 -21.5071,
+                          -30.5 -2.81937 -25.8555,
+                          -36.5 2.30132 -25.9076,
+                          -30.5 4.07201 -25.6889,
+                          -30.5 -9.51392 -24.2046,
+                          -36.5 2.30132 -25.9076,
+                          -30.5 -2.81937 -25.8555,
+                          -36.5 22.1323 13.6548,
+                          -36.5 23.2524 -11.6561,
+                          -36.5 14.6286 -21.5071,
+                          -30.5 16.5303 -20.0826,
+                          -36.5 14.6286 -21.5071,
+                          -36.5 23.2524 -11.6561,
+                          -36.5 12.6722 22.7056,
+                          -36.5 22.1323 13.6548,
+                          -36.5 14.6286 -21.5071,
+                          -30.5 10.6759 -23.7184,
+                          -36.5 14.6286 -21.5071,
+                          -30.5 16.5303 -20.0826,
+                          -30.5 4.07201 -25.6889,
+                          -36.5 14.6286 -21.5071,
+                          -30.5 10.6759 -23.7184,
+                          -36.5 22.1323 13.6548,
+                          -36.5 25.9836 1.145,
+                          -36.5 23.2524 -11.6561,
+                          -30.5 24.4292 -8.93014,
+                          -36.5 23.2524 -11.6561,
+                          -36.5 25.9836 1.145,
+                          -30.5 21.2251 -15.0352,
+                          -36.5 23.2524 -11.6561,
+                          -30.5 24.4292 -8.93014,
+                          -30.5 16.5303 -20.0826,
+                          -36.5 23.2524 -11.6561,
+                          -30.5 21.2251 -15.0352,
+                          -30.5 25.5827 4.68315,
+                          -36.5 25.9836 1.145,
+                          -36.5 22.1323 13.6548,
+                          -30.5 25.9159 -2.20001,
+                          -36.5 25.9836 1.145,
+                          -30.5 25.5827 4.68315,
+                          -30.5 24.4292 -8.93014,
+                          -36.5 25.9836 1.145,
+                          -30.5 25.9159 -2.20001,
+                          -30.5 25.5827 4.68315,
+                          -36.5 22.1323 13.6548,
+                          -30.5 23.4531 11.2377,
+                          -30.5 13.0883 22.4685,
+                          -36.5 12.6722 22.7056,
+                          -30.5 5.07928 25.5,
+                          -30.5 -2.81937 -25.8555,
+                          -30.5 -6.01041 -6.01041,
+                          -30.5 -8.5 8.52651e-14,
+                          -30.5 -9.51392 -24.2046,
+                          -30.5 -2.81937 -25.8555,
+                          -30.5 -8.5 8.52651e-14,
+                          -30.5 -2.81937 -25.8555,
+                          -30.5 -7.45725e-14 -8.5,
+                          -30.5 -6.01041 -6.01041,
+                          -30.5 4.07201 -25.6889,
+                          -30.5 6.01041 -6.01041,
+                          -30.5 -7.45725e-14 -8.5,
+                          -30.5 -2.81937 -25.8555,
+                          -30.5 4.07201 -25.6889,
+                          -30.5 -7.45725e-14 -8.5,
+                          -30.5 10.6759 -23.7184,
+                          -30.5 8.5 8.88178e-14,
+                          -30.5 6.01041 -6.01041,
+                          -30.5 4.07201 -25.6889,
+                          -30.5 10.6759 -23.7184,
+                          -30.5 6.01041 -6.01041,
+                          -30.5 10.6759 -23.7184,
+                          -30.5 16.5303 -20.0826,
+                          -30.5 8.5 8.88178e-14,
+                          -30.5 24.4292 -8.93014,
+                          -30.5 25.5827 4.68315,
+                          -30.5 23.4531 11.2377,
+                          -30.5 21.2251 -15.0352,
+                          -30.5 24.4292 -8.93014,
+                          -30.5 23.4531 11.2377,
+                          -30.5 24.4292 -8.93014,
+                          -30.5 25.9159 -2.20001,
+                          -30.5 25.5827 4.68315,
+                          11.3909 27.5 25.5,
+                          27.5 11.3909 25.5,
+                          30.5 13.5 25.5,
+                          -30.5 2.55625 25.8745,
+                          -30.5 0.00438816 26,
+                          -30.5 5.07928 25.5 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/left_arm/shoulder_l.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/left_arm/shoulder_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..059ac900c84be364360623682aadb82e22c01623
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/left_arm/shoulder_l.iv
@@ -0,0 +1,3407 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.392 0.437 0.49
+    }
+    Separator {
+        Normal {
+            vector      [ -0.258819 0.965926 8.96278e-05,
+                          0.707107 0.707107 6.56121e-05,
+                          0.707107 0.707107 6.56121e-05,
+                          0.965926 -0.258819 -2.40157e-05,
+                          0.707107 0.707107 6.56121e-05,
+                          0.707107 0.707107 6.56121e-05,
+                          -0.258819 0.965926 8.96278e-05,
+                          -0.258819 0.965926 8.96278e-05,
+                          0.707107 0.707107 6.56121e-05,
+                          -0.258819 0.965926 8.96278e-05,
+                          0.707107 0.707107 6.56121e-05,
+                          0.707107 0.707107 6.56121e-05,
+                          0.965926 -0.258819 -2.40157e-05,
+                          0.707107 0.707107 6.56121e-05,
+                          0.707107 0.707107 6.56121e-05,
+                          0.965926 -0.258819 -2.40157e-05,
+                          0.965926 -0.258819 -2.40157e-05,
+                          0.707107 0.707107 6.56121e-05,
+                          -0.258819 0.965926 8.96278e-05,
+                          -0.258819 0.965926 8.96278e-05,
+                          0.707107 0.707107 6.56121e-05,
+                          0.707107 0.707107 6.56121e-05,
+                          0.707107 0.707107 6.56121e-05,
+                          -0.258819 0.965926 8.96278e-05,
+                          0.965926 -0.258819 -2.40157e-05,
+                          0.707107 0.707107 6.56121e-05,
+                          0.707107 0.707107 6.56121e-05,
+                          0.965926 -0.258819 -2.40157e-05,
+                          0.707107 0.707107 6.56121e-05,
+                          0.965926 -0.258819 -2.40157e-05,
+                          -0.965926 0.258819 2.40157e-05,
+                          -0.965926 0.258819 2.40157e-05,
+                          -0.258819 0.965926 8.96278e-05,
+                          -0.258819 0.965926 8.96278e-05,
+                          -0.258819 0.965926 8.96278e-05,
+                          -0.965926 0.258819 2.40157e-05,
+                          -0.258819 0.965926 8.96278e-05,
+                          -0.965926 0.258819 2.40157e-05,
+                          -0.258819 0.965926 8.96278e-05,
+                          -0.258819 0.965926 8.96278e-05,
+                          0.707107 0.707107 6.56121e-05,
+                          -0.258819 0.965926 8.96278e-05,
+                          -0.707107 -0.707107 -6.56121e-05,
+                          -0.707107 -0.707107 -6.56121e-05,
+                          -0.965926 0.258819 2.40157e-05,
+                          -0.965926 0.258819 2.40157e-05,
+                          -0.965926 0.258819 2.40157e-05,
+                          -0.707107 -0.707107 -6.56121e-05,
+                          -0.965926 0.258819 2.40157e-05,
+                          -0.707107 -0.707107 -6.56121e-05,
+                          -0.965926 0.258819 2.40157e-05,
+                          -0.965926 0.258819 2.40157e-05,
+                          -0.258819 0.965926 8.96278e-05,
+                          -0.965926 0.258819 2.40157e-05,
+                          0.258819 -0.965926 -8.96278e-05,
+                          -0.707107 -0.707107 -6.56121e-05,
+                          -0.707107 -0.707107 -6.56121e-05,
+                          -0.707107 -0.707107 -6.56121e-05,
+                          -0.965926 0.258819 2.40157e-05,
+                          -0.707107 -0.707107 -6.56121e-05,
+                          0.258819 -0.965926 -8.96278e-05,
+                          -0.707107 -0.707107 -6.56121e-05,
+                          -0.707107 -0.707107 -6.56121e-05,
+                          0.258819 -0.965926 -8.96278e-05,
+                          -0.707107 -0.707107 -6.56121e-05,
+                          0.258819 -0.965926 -8.96278e-05,
+                          -0.707107 -0.707107 -6.56121e-05,
+                          -0.707107 -0.707107 -6.56121e-05,
+                          -0.965926 0.258819 2.40157e-05,
+                          0.258819 -0.965926 -8.96278e-05,
+                          -0.707107 -0.707107 -6.56121e-05,
+                          -0.707107 -0.707107 -6.56121e-05,
+                          0.258819 -0.965926 -8.96278e-05,
+                          -0.707107 -0.707107 -6.56121e-05,
+                          0.258819 -0.965926 -8.96278e-05,
+                          -0.965926 0.258819 2.40157e-05,
+                          -0.965926 0.258819 2.40157e-05,
+                          -0.258819 0.965926 8.96278e-05,
+                          -0.707107 -0.707107 -6.56121e-05,
+                          -0.965926 0.258819 2.40157e-05,
+                          -0.965926 0.258819 2.40157e-05,
+                          -0.965926 0.258819 2.40157e-05,
+                          -0.258819 0.965926 8.96278e-05,
+                          -0.258819 0.965926 8.96278e-05,
+                          4.32247e-17 -9.27896e-05 1,
+                          4.32247e-17 -9.27896e-05 1,
+                          4.32247e-17 -9.27896e-05 1,
+                          4.32247e-17 -9.27896e-05 1,
+                          4.32247e-17 -9.27896e-05 1,
+                          4.32247e-17 -9.27896e-05 1,
+                          4.32247e-17 -9.27896e-05 1,
+                          4.32247e-17 -9.27896e-05 1,
+                          4.32247e-17 -9.27896e-05 1,
+                          4.32247e-17 -9.27896e-05 1,
+                          4.32247e-17 -9.27896e-05 1,
+                          4.32247e-17 -9.27896e-05 1,
+                          0.258819 -0.965926 -8.96278e-05,
+                          0.258819 -0.965926 -8.96278e-05,
+                          -0.707107 -0.707107 -6.56121e-05,
+                          0.965926 -0.258819 -2.40157e-05,
+                          0.965926 -0.258819 -2.40157e-05,
+                          0.258819 -0.965926 -8.96278e-05,
+                          0.965926 -0.258819 -2.40157e-05,
+                          0.258819 -0.965926 -8.96278e-05,
+                          0.258819 -0.965926 -8.96278e-05,
+                          -4.32247e-17 9.27896e-05 -1,
+                          -4.32247e-17 9.27896e-05 -1,
+                          -4.32247e-17 9.27896e-05 -1,
+                          -4.32247e-17 9.27896e-05 -1,
+                          -4.32247e-17 9.27896e-05 -1,
+                          -4.32247e-17 9.27896e-05 -1,
+                          -4.32247e-17 9.27896e-05 -1,
+                          -4.32247e-17 9.27896e-05 -1,
+                          -4.32247e-17 9.27896e-05 -1,
+                          0.965926 -0.258819 -2.40157e-05,
+                          0.965926 -0.258819 -2.40157e-05,
+                          0.707107 0.707107 6.56121e-05,
+                          -4.32247e-17 9.27896e-05 -1,
+                          -4.32247e-17 9.27896e-05 -1,
+                          -4.32247e-17 9.27896e-05 -1,
+                          0.258819 -0.965926 -8.96278e-05,
+                          0.258819 -0.965926 -8.96278e-05,
+                          0.965926 -0.258819 -2.40157e-05,
+                          0.258819 -0.965926 -8.96278e-05,
+                          0.965926 -0.258819 -2.40157e-05,
+                          0.965926 -0.258819 -2.40157e-05,
+                          0.258819 -0.965926 -8.96278e-05,
+                          0.258819 -0.965926 -8.96278e-05,
+                          0.965926 -0.258819 -2.40157e-05,
+                          0.965926 -0.258819 -2.40157e-05,
+                          0.258819 -0.965926 -8.96278e-05,
+                          0.965926 -0.258819 -2.40157e-05 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 109.454 2.90195 -44.9997,
+                          112.351 2.11863 29.0002,
+                          112.351 2.1255 -44.9998,
+                          113.128 -0.779148 28.9999,
+                          112.351 2.1255 -44.9998,
+                          112.351 2.11863 29.0002,
+                          109.453 2.9034 -66.7997,
+                          109.454 2.90195 -44.9997,
+                          112.351 2.1255 -44.9998,
+                          109.453 2.9034 -66.7997,
+                          112.351 2.1255 -44.9998,
+                          112.351 2.12752 -66.7998,
+                          113.128 -0.772282 -45.0001,
+                          112.351 2.12752 -66.7998,
+                          112.351 2.1255 -44.9998,
+                          113.128 -0.779148 28.9999,
+                          113.128 -0.772282 -45.0001,
+                          112.351 2.1255 -44.9998,
+                          109.454 2.90195 -44.9997,
+                          109.454 2.89509 29.0003,
+                          112.351 2.11863 29.0002,
+                          112.351 2.11512 66.8002,
+                          112.351 2.11863 29.0002,
+                          109.454 2.89509 29.0003,
+                          113.127 -0.783399 66.7999,
+                          112.351 2.11863 29.0002,
+                          112.351 2.11512 66.8002,
+                          113.128 -0.779148 28.9999,
+                          112.351 2.11863 29.0002,
+                          113.127 -0.783399 66.7999,
+                          107.332 0.780633 -44.9999,
+                          107.332 0.773766 29.0001,
+                          109.454 2.89509 29.0003,
+                          109.453 2.891 66.8003,
+                          109.454 2.89509 29.0003,
+                          107.332 0.773766 29.0001,
+                          109.454 2.90195 -44.9997,
+                          107.332 0.780633 -44.9999,
+                          109.454 2.89509 29.0003,
+                          109.453 2.891 66.8003,
+                          112.351 2.11512 66.8002,
+                          109.454 2.89509 29.0003,
+                          108.109 -2.11714 -45.0002,
+                          108.109 -2.12401 28.9998,
+                          107.332 0.773766 29.0001,
+                          107.333 0.771003 66.8001,
+                          107.332 0.773766 29.0001,
+                          108.109 -2.12401 28.9998,
+                          107.332 0.780633 -44.9999,
+                          108.109 -2.11714 -45.0002,
+                          107.332 0.773766 29.0001,
+                          107.333 0.771003 66.8001,
+                          109.453 2.891 66.8003,
+                          107.332 0.773766 29.0001,
+                          111.007 -2.8936 -45.0003,
+                          108.109 -2.12401 28.9998,
+                          108.109 -2.11714 -45.0002,
+                          108.109 -2.12752 66.7998,
+                          107.333 0.771003 66.8001,
+                          108.109 -2.12401 28.9998,
+                          111.007 -2.90047 28.9997,
+                          108.109 -2.12752 66.7998,
+                          108.109 -2.12401 28.9998,
+                          111.007 -2.90047 28.9997,
+                          108.109 -2.12401 28.9998,
+                          111.007 -2.8936 -45.0003,
+                          108.109 -2.11512 -66.8002,
+                          108.109 -2.11714 -45.0002,
+                          107.332 0.780633 -44.9999,
+                          111.007 -2.891 -66.8003,
+                          108.109 -2.11714 -45.0002,
+                          108.109 -2.11512 -66.8002,
+                          111.007 -2.8936 -45.0003,
+                          108.109 -2.11714 -45.0002,
+                          111.007 -2.891 -66.8003,
+                          107.333 0.783399 -66.7999,
+                          107.332 0.780633 -44.9999,
+                          109.454 2.90195 -44.9997,
+                          108.109 -2.11512 -66.8002,
+                          107.332 0.780633 -44.9999,
+                          107.333 0.783399 -66.7999,
+                          107.333 0.783399 -66.7999,
+                          109.454 2.90195 -44.9997,
+                          109.453 2.9034 -66.7997,
+                          108.109 -2.12752 66.7998,
+                          112.351 2.11512 66.8002,
+                          109.453 2.891 66.8003,
+                          111.007 -2.9034 66.7997,
+                          112.351 2.11512 66.8002,
+                          108.109 -2.12752 66.7998,
+                          111.007 -2.9034 66.7997,
+                          113.127 -0.783399 66.7999,
+                          112.351 2.11512 66.8002,
+                          108.109 -2.12752 66.7998,
+                          109.453 2.891 66.8003,
+                          107.333 0.771003 66.8001,
+                          111.007 -2.90047 28.9997,
+                          111.007 -2.9034 66.7997,
+                          108.109 -2.12752 66.7998,
+                          113.128 -0.779148 28.9999,
+                          113.127 -0.783399 66.7999,
+                          111.007 -2.9034 66.7997,
+                          113.128 -0.779148 28.9999,
+                          111.007 -2.9034 66.7997,
+                          111.007 -2.90047 28.9997,
+                          107.333 0.783399 -66.7999,
+                          109.453 2.9034 -66.7997,
+                          112.351 2.12752 -66.7998,
+                          108.109 -2.11512 -66.8002,
+                          107.333 0.783399 -66.7999,
+                          112.351 2.12752 -66.7998,
+                          113.127 -0.771003 -66.8001,
+                          108.109 -2.11512 -66.8002,
+                          112.351 2.12752 -66.7998,
+                          113.128 -0.772282 -45.0001,
+                          113.127 -0.771003 -66.8001,
+                          112.351 2.12752 -66.7998,
+                          113.127 -0.771003 -66.8001,
+                          111.007 -2.891 -66.8003,
+                          108.109 -2.11512 -66.8002,
+                          111.007 -2.8936 -45.0003,
+                          111.007 -2.891 -66.8003,
+                          113.127 -0.771003 -66.8001,
+                          111.007 -2.8936 -45.0003,
+                          113.127 -0.771003 -66.8001,
+                          113.128 -0.772282 -45.0001,
+                          111.007 -2.90047 28.9997,
+                          111.007 -2.8936 -45.0003,
+                          113.128 -0.772282 -45.0001,
+                          113.128 -0.779148 28.9999,
+                          111.007 -2.90047 28.9997,
+                          113.128 -0.772282 -45.0001 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    1 0 0
+    }
+    Separator {
+        Normal {
+            vector      [ -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          0.866025 0.5 4.63948e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          0.866025 -0.5 -4.63948e-05,
+                          0.866025 -0.5 -4.63948e-05,
+                          1 -3.00432e-16 9.19651e-17,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          0.866025 -0.5 -4.63948e-05,
+                          1 -3.00432e-16 9.19651e-17,
+                          1 -3.00432e-16 9.19651e-17,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          0.866025 0.5 4.63948e-05,
+                          0.866025 0.5 4.63948e-05,
+                          0.5 0.866025 8.03581e-05,
+                          0.866025 0.5 4.63948e-05,
+                          1 -5.55112e-17 9.19878e-17,
+                          0.866025 0.5 4.63948e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          0.5 0.866025 8.03581e-05,
+                          0.5 0.866025 8.03581e-05,
+                          2.83275e-16 1 9.27896e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          0.866025 0.5 4.63948e-05,
+                          0.5 0.866025 8.03581e-05,
+                          0.5 0.866025 8.03581e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          2.83275e-16 1 9.27896e-05,
+                          2.83275e-16 1 9.27896e-05,
+                          -0.5 0.866025 8.03581e-05,
+                          0.5 0.866025 8.03581e-05,
+                          2.83275e-16 1 9.27896e-05,
+                          2.83275e-16 1 9.27896e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -0.5 0.866025 8.03581e-05,
+                          -0.5 0.866025 8.03581e-05,
+                          -0.866025 0.5 4.63948e-05,
+                          2.83275e-16 1 9.27896e-05,
+                          -0.5 0.866025 8.03581e-05,
+                          -0.5 0.866025 8.03581e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -0.866025 0.5 4.63948e-05,
+                          -0.866025 0.5 4.63948e-05,
+                          -1 1.77972e-16 -9.19764e-17,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -0.5 0.866025 8.03581e-05,
+                          -0.866025 0.5 4.63948e-05,
+                          -0.866025 0.5 4.63948e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -1 1.77972e-16 -9.19764e-17,
+                          -1 1.77972e-16 -9.19764e-17,
+                          -0.866025 -0.5 -4.63948e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -0.866025 0.5 4.63948e-05,
+                          -1 1.77972e-16 -9.19764e-17,
+                          -1 1.77972e-16 -9.19764e-17,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -0.866025 -0.5 -4.63948e-05,
+                          -0.866025 -0.5 -4.63948e-05,
+                          -0.5 -0.866025 -8.03581e-05,
+                          -1 1.77972e-16 -9.19764e-17,
+                          -0.866025 -0.5 -4.63948e-05,
+                          -0.866025 -0.5 -4.63948e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -0.5 -0.866025 -8.03581e-05,
+                          -0.5 -0.866025 -8.03581e-05,
+                          -4.05736e-16 -1 -9.27896e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -0.866025 -0.5 -4.63948e-05,
+                          -0.5 -0.866025 -8.03581e-05,
+                          -0.5 -0.866025 -8.03581e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.05736e-16 -1 -9.27896e-05,
+                          -4.05736e-16 -1 -9.27896e-05,
+                          0.5 -0.866025 -8.03581e-05,
+                          -0.5 -0.866025 -8.03581e-05,
+                          -4.05736e-16 -1 -9.27896e-05,
+                          -4.05736e-16 -1 -9.27896e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          0.5 -0.866025 -8.03581e-05,
+                          0.5 -0.866025 -8.03581e-05,
+                          0.866025 -0.5 -4.63948e-05,
+                          -4.05736e-16 -1 -9.27896e-05,
+                          0.5 -0.866025 -8.03581e-05,
+                          0.5 -0.866025 -8.03581e-05,
+                          0.5 -0.866025 -8.03581e-05,
+                          0.866025 -0.5 -4.63948e-05,
+                          0.866025 -0.5 -4.63948e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          0.43315 -0.901322 -8.36332e-05,
+                          0.43315 -0.901322 -8.36332e-05,
+                          0.43315 -0.901322 -8.36332e-05,
+                          0.43315 -0.901322 -8.36332e-05,
+                          0.43315 -0.901322 -8.36332e-05,
+                          0.43315 -0.901322 -8.36332e-05,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          0.40252 0.915411 8.49406e-05,
+                          0.40252 0.915411 8.49406e-05,
+                          0.40252 0.915411 8.49406e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          0.40252 0.915411 8.49406e-05,
+                          0.40252 0.915411 8.49406e-05,
+                          0.764417 0.644723 5.98235e-05,
+                          0.40252 0.915411 8.49406e-05,
+                          0.40252 0.915411 8.49406e-05,
+                          0.40252 0.915411 8.49406e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          0.764417 0.644723 5.98235e-05,
+                          0.764417 0.644723 5.98235e-05,
+                          0.970188 0.242355 2.2488e-05,
+                          0.40252 0.915411 8.49406e-05,
+                          0.764417 0.644723 5.98235e-05,
+                          0.764417 0.644723 5.98235e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          0.970188 0.242355 2.2488e-05,
+                          0.970188 0.242355 2.2488e-05,
+                          0.977806 -0.209512 -1.94405e-05,
+                          0.764417 0.644723 5.98235e-05,
+                          0.970188 0.242355 2.2488e-05,
+                          0.970188 0.242355 2.2488e-05,
+                          0.977806 -0.209512 -1.94405e-05,
+                          0.977806 -0.209512 -1.94405e-05,
+                          0.785716 -0.618587 -5.73984e-05,
+                          0.970188 0.242355 2.2488e-05,
+                          0.977806 -0.209512 -1.94405e-05,
+                          0.977806 -0.209512 -1.94405e-05,
+                          0.785716 -0.618587 -5.73984e-05,
+                          0.785716 -0.618587 -5.73984e-05,
+                          0.43315 -0.901322 -8.36332e-05,
+                          0.977806 -0.209512 -1.94405e-05,
+                          0.785716 -0.618587 -5.73984e-05,
+                          0.785716 -0.618587 -5.73984e-05,
+                          0.785716 -0.618587 -5.73984e-05,
+                          0.43315 -0.901322 -8.36332e-05,
+                          0.43315 -0.901322 -8.36332e-05,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 70.23 -57.5055 58.9947,
+                          92.045 -10.5069 58.999,
+                          89.23 -0.00547458 59,
+                          89.23 -0.00491785 53,
+                          89.23 -0.00547458 59,
+                          92.045 -10.5069 58.999,
+                          82.23 49.9945 59.0046,
+                          89.23 -0.00547458 59,
+                          92.045 10.4959 59.001,
+                          92.045 10.4965 53.001,
+                          92.045 10.4959 59.001,
+                          89.23 -0.00547458 59,
+                          82.23 49.9945 59.0046,
+                          70.23 -57.5055 58.9947,
+                          89.23 -0.00547458 59,
+                          92.045 10.4965 53.001,
+                          89.23 -0.00547458 59,
+                          89.23 -0.00491785 53,
+                          70.23 -57.5055 58.9947,
+                          99.7286 -18.1905 58.9983,
+                          92.045 -10.5069 58.999,
+                          92.045 -10.5063 52.999,
+                          92.045 -10.5069 58.999,
+                          99.7286 -18.1905 58.9983,
+                          92.045 -10.5063 52.999,
+                          89.23 -0.00491785 53,
+                          92.045 -10.5069 58.999,
+                          125.174 -31.1011 58.9971,
+                          110.23 -21.0055 58.9981,
+                          99.7286 -18.1905 58.9983,
+                          99.7286 -18.19 52.9983,
+                          99.7286 -18.1905 58.9983,
+                          110.23 -21.0055 58.9981,
+                          125.174 -31.1011 58.9971,
+                          99.7286 -18.1905 58.9983,
+                          70.23 -57.5055 58.9947,
+                          92.045 -10.5063 52.999,
+                          99.7286 -18.1905 58.9983,
+                          99.7286 -18.19 52.9983,
+                          125.174 -31.1011 58.9971,
+                          120.731 -18.1905 58.9983,
+                          110.23 -21.0055 58.9981,
+                          110.23 -21.0049 52.9981,
+                          110.23 -21.0055 58.9981,
+                          120.731 -18.1905 58.9983,
+                          99.7286 -18.19 52.9983,
+                          110.23 -21.0055 58.9981,
+                          110.23 -21.0049 52.9981,
+                          125.174 -31.1011 58.9971,
+                          128.415 -10.5069 58.999,
+                          120.731 -18.1905 58.9983,
+                          120.731 -18.19 52.9983,
+                          120.731 -18.1905 58.9983,
+                          128.415 -10.5069 58.999,
+                          110.23 -21.0049 52.9981,
+                          120.731 -18.1905 58.9983,
+                          120.731 -18.19 52.9983,
+                          137.339 -21.3447 58.998,
+                          131.23 -0.00547458 59,
+                          128.415 -10.5069 58.999,
+                          128.415 -10.5063 52.999,
+                          128.415 -10.5069 58.999,
+                          131.23 -0.00547458 59,
+                          125.174 -31.1011 58.9971,
+                          137.339 -21.3447 58.998,
+                          128.415 -10.5069 58.999,
+                          120.731 -18.19 52.9983,
+                          128.415 -10.5069 58.999,
+                          128.415 -10.5063 52.999,
+                          124.117 31.5762 59.0029,
+                          128.415 10.4959 59.001,
+                          131.23 -0.00547458 59,
+                          131.23 -0.00491785 53,
+                          131.23 -0.00547458 59,
+                          128.415 10.4959 59.001,
+                          136.604 22.2355 59.0021,
+                          124.117 31.5762 59.0029,
+                          131.23 -0.00547458 59,
+                          137.339 -21.3447 58.998,
+                          136.604 22.2355 59.0021,
+                          131.23 -0.00547458 59,
+                          128.415 -10.5063 52.999,
+                          131.23 -0.00547458 59,
+                          131.23 -0.00491785 53,
+                          124.117 31.5762 59.0029,
+                          120.731 18.1796 59.0017,
+                          128.415 10.4959 59.001,
+                          128.415 10.4965 53.001,
+                          128.415 10.4959 59.001,
+                          120.731 18.1796 59.0017,
+                          131.23 -0.00491785 53,
+                          128.415 10.4959 59.001,
+                          128.415 10.4965 53.001,
+                          82.23 49.9945 59.0046,
+                          110.23 20.9945 59.0019,
+                          120.731 18.1796 59.0017,
+                          120.731 18.1801 53.0017,
+                          120.731 18.1796 59.0017,
+                          110.23 20.9945 59.0019,
+                          124.117 31.5762 59.0029,
+                          82.23 49.9945 59.0046,
+                          120.731 18.1796 59.0017,
+                          128.415 10.4965 53.001,
+                          120.731 18.1796 59.0017,
+                          120.731 18.1801 53.0017,
+                          82.23 49.9945 59.0046,
+                          99.7286 18.1796 59.0017,
+                          110.23 20.9945 59.0019,
+                          110.23 20.9951 53.0019,
+                          110.23 20.9945 59.0019,
+                          99.7286 18.1796 59.0017,
+                          120.731 18.1801 53.0017,
+                          110.23 20.9945 59.0019,
+                          110.23 20.9951 53.0019,
+                          82.23 49.9945 59.0046,
+                          92.045 10.4959 59.001,
+                          99.7286 18.1796 59.0017,
+                          99.7286 18.1801 53.0017,
+                          99.7286 18.1796 59.0017,
+                          92.045 10.4959 59.001,
+                          110.23 20.9951 53.0019,
+                          99.7286 18.1796 59.0017,
+                          99.7286 18.1801 53.0017,
+                          99.7286 18.1801 53.0017,
+                          92.045 10.4959 59.001,
+                          92.045 10.4965 53.001,
+                          0.230049 49.9945 59.0046,
+                          0.230049 -57.5055 58.9947,
+                          70.23 -57.5055 58.9947,
+                          70.23 -57.5049 52.9947,
+                          70.23 -57.5055 58.9947,
+                          0.230049 -57.5055 58.9947,
+                          82.23 49.9945 59.0046,
+                          0.230049 49.9945 59.0046,
+                          70.23 -57.5055 58.9947,
+                          125.174 -31.1005 52.9971,
+                          125.174 -31.1011 58.9971,
+                          70.23 -57.5055 58.9947,
+                          125.174 -31.1005 52.9971,
+                          70.23 -57.5055 58.9947,
+                          70.23 -57.5049 52.9947,
+                          0.230049 -57.5049 52.9947,
+                          0.230049 -57.5055 58.9947,
+                          0.230049 49.9945 59.0046,
+                          0.230049 -57.5049 52.9947,
+                          70.23 -57.5049 52.9947,
+                          0.230049 -57.5055 58.9947,
+                          0.230049 49.9951 53.0046,
+                          0.230049 49.9945 59.0046,
+                          82.23 49.9945 59.0046,
+                          0.230049 -57.5049 52.9947,
+                          0.230049 49.9945 59.0046,
+                          0.230049 49.9951 53.0046,
+                          82.23 49.9951 53.0046,
+                          82.23 49.9945 59.0046,
+                          124.117 31.5762 59.0029,
+                          0.230049 49.9951 53.0046,
+                          82.23 49.9945 59.0046,
+                          82.23 49.9951 53.0046,
+                          124.117 31.5768 53.0029,
+                          124.117 31.5762 59.0029,
+                          136.604 22.2355 59.0021,
+                          82.23 49.9951 53.0046,
+                          124.117 31.5762 59.0029,
+                          124.117 31.5768 53.0029,
+                          137.339 -21.3447 58.998,
+                          143.701 8.35448 59.0008,
+                          136.604 22.2355 59.0021,
+                          136.604 22.236 53.0021,
+                          136.604 22.2355 59.0021,
+                          143.701 8.35448 59.0008,
+                          124.117 31.5768 53.0029,
+                          136.604 22.2355 59.0021,
+                          136.604 22.236 53.0021,
+                          137.339 -21.3447 58.998,
+                          143.964 -7.23235 58.9993,
+                          143.701 8.35448 59.0008,
+                          143.701 8.35504 53.0008,
+                          143.701 8.35448 59.0008,
+                          143.964 -7.23235 58.9993,
+                          136.604 22.236 53.0021,
+                          143.701 8.35448 59.0008,
+                          143.701 8.35504 53.0008,
+                          143.964 -7.2318 52.9993,
+                          143.964 -7.23235 58.9993,
+                          137.339 -21.3447 58.998,
+                          143.701 8.35504 53.0008,
+                          143.964 -7.23235 58.9993,
+                          143.964 -7.2318 52.9993,
+                          137.339 -21.3442 52.998,
+                          137.339 -21.3447 58.998,
+                          125.174 -31.1011 58.9971,
+                          143.964 -7.2318 52.9993,
+                          137.339 -21.3447 58.998,
+                          137.339 -21.3442 52.998,
+                          137.339 -21.3442 52.998,
+                          125.174 -31.1011 58.9971,
+                          125.174 -31.1005 52.9971,
+                          82.23 49.9951 53.0046,
+                          92.045 10.4965 53.001,
+                          89.23 -0.00491785 53,
+                          70.23 -57.5049 52.9947,
+                          89.23 -0.00491785 53,
+                          92.045 -10.5063 52.999,
+                          82.23 49.9951 53.0046,
+                          89.23 -0.00491785 53,
+                          70.23 -57.5049 52.9947,
+                          82.23 49.9951 53.0046,
+                          99.7286 18.1801 53.0017,
+                          92.045 10.4965 53.001,
+                          124.117 31.5768 53.0029,
+                          110.23 20.9951 53.0019,
+                          99.7286 18.1801 53.0017,
+                          82.23 49.9951 53.0046,
+                          124.117 31.5768 53.0029,
+                          99.7286 18.1801 53.0017,
+                          124.117 31.5768 53.0029,
+                          120.731 18.1801 53.0017,
+                          110.23 20.9951 53.0019,
+                          124.117 31.5768 53.0029,
+                          128.415 10.4965 53.001,
+                          120.731 18.1801 53.0017,
+                          136.604 22.236 53.0021,
+                          131.23 -0.00491785 53,
+                          128.415 10.4965 53.001,
+                          124.117 31.5768 53.0029,
+                          136.604 22.236 53.0021,
+                          128.415 10.4965 53.001,
+                          125.174 -31.1005 52.9971,
+                          128.415 -10.5063 52.999,
+                          131.23 -0.00491785 53,
+                          136.604 22.236 53.0021,
+                          125.174 -31.1005 52.9971,
+                          131.23 -0.00491785 53,
+                          125.174 -31.1005 52.9971,
+                          120.731 -18.19 52.9983,
+                          128.415 -10.5063 52.999,
+                          70.23 -57.5049 52.9947,
+                          110.23 -21.0049 52.9981,
+                          120.731 -18.19 52.9983,
+                          125.174 -31.1005 52.9971,
+                          70.23 -57.5049 52.9947,
+                          120.731 -18.19 52.9983,
+                          70.23 -57.5049 52.9947,
+                          99.7286 -18.19 52.9983,
+                          110.23 -21.0049 52.9981,
+                          70.23 -57.5049 52.9947,
+                          92.045 -10.5063 52.999,
+                          99.7286 -18.19 52.9983,
+                          0.230049 -57.5049 52.9947,
+                          82.23 49.9951 53.0046,
+                          70.23 -57.5049 52.9947,
+                          136.604 22.236 53.0021,
+                          137.339 -21.3442 52.998,
+                          125.174 -31.1005 52.9971,
+                          143.701 8.35504 53.0008,
+                          143.964 -7.2318 52.9993,
+                          137.339 -21.3442 52.998,
+                          136.604 22.236 53.0021,
+                          143.701 8.35504 53.0008,
+                          137.339 -21.3442 52.998,
+                          0.230049 -57.5049 52.9947,
+                          0.230049 49.9951 53.0046,
+                          82.23 49.9951 53.0046 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.386933 0.500748 0.62
+    }
+    Separator {
+        Normal {
+            vector      [ 4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          1 -5.55456e-17 4.63219e-16,
+                          1 -5.55456e-17 4.63219e-16,
+                          0.809017 -0.587785 -5.45403e-05,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          0.809017 0.587785 5.45403e-05,
+                          0.809017 0.587785 5.45403e-05,
+                          1 1.89376e-16 4.63241e-16,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          0.809017 0.587785 5.45403e-05,
+                          1 1.89376e-16 4.63241e-16,
+                          1 1.89376e-16 4.63241e-16,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          0.809017 -0.587785 -5.45403e-05,
+                          0.809017 -0.587785 -5.45403e-05,
+                          0.309017 -0.951057 -8.82481e-05,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          0.809017 -0.587785 -5.45403e-05,
+                          1 -5.55456e-17 4.63219e-16,
+                          0.809017 -0.587785 -5.45403e-05,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          0.309017 -0.951057 -8.82481e-05,
+                          0.309017 -0.951057 -8.82481e-05,
+                          -0.309017 -0.951057 -8.82481e-05,
+                          0.809017 -0.587785 -5.45403e-05,
+                          0.309017 -0.951057 -8.82481e-05,
+                          0.309017 -0.951057 -8.82481e-05,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          -0.309017 -0.951057 -8.82481e-05,
+                          -0.309017 -0.951057 -8.82481e-05,
+                          -0.809017 -0.587785 -5.45403e-05,
+                          0.309017 -0.951057 -8.82481e-05,
+                          -0.309017 -0.951057 -8.82481e-05,
+                          -0.309017 -0.951057 -8.82481e-05,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          -0.809017 -0.587785 -5.45403e-05,
+                          -0.809017 -0.587785 -5.45403e-05,
+                          -1 -6.6915e-17 -4.6323e-16,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          -0.309017 -0.951057 -8.82481e-05,
+                          -0.809017 -0.587785 -5.45403e-05,
+                          -0.809017 -0.587785 -5.45403e-05,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          -1 -6.6915e-17 -4.6323e-16,
+                          -1 -6.6915e-17 -4.6323e-16,
+                          -0.809017 0.587785 5.45403e-05,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          -0.809017 -0.587785 -5.45403e-05,
+                          -1 -6.6915e-17 -4.6323e-16,
+                          -1 -6.6915e-17 -4.6323e-16,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          -0.809017 0.587785 5.45403e-05,
+                          -0.809017 0.587785 5.45403e-05,
+                          -0.309017 0.951057 8.82481e-05,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          -1 -6.6915e-17 -4.6323e-16,
+                          -0.809017 0.587785 5.45403e-05,
+                          -0.809017 0.587785 5.45403e-05,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          -0.309017 0.951057 8.82481e-05,
+                          -0.309017 0.951057 8.82481e-05,
+                          0.309017 0.951057 8.82481e-05,
+                          -0.809017 0.587785 5.45403e-05,
+                          -0.309017 0.951057 8.82481e-05,
+                          -0.309017 0.951057 8.82481e-05,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          0.309017 0.951057 8.82481e-05,
+                          0.309017 0.951057 8.82481e-05,
+                          0.809017 0.587785 5.45403e-05,
+                          -0.309017 0.951057 8.82481e-05,
+                          0.309017 0.951057 8.82481e-05,
+                          0.309017 0.951057 8.82481e-05,
+                          0.309017 0.951057 8.82481e-05,
+                          0.809017 0.587785 5.45403e-05,
+                          0.809017 0.587785 5.45403e-05,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          0.43315 -0.901322 -8.36332e-05,
+                          0.43315 -0.901322 -8.36332e-05,
+                          0.785716 -0.618587 -5.73984e-05,
+                          0.43315 -0.901322 -8.36332e-05,
+                          0.43315 -0.901322 -8.36332e-05,
+                          0.43315 -0.901322 -8.36332e-05,
+                          0.43315 -0.901322 -8.36332e-05,
+                          0.43315 -0.901322 -8.36332e-05,
+                          0.43315 -0.901322 -8.36332e-05,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          0.785716 -0.618587 -5.73984e-05,
+                          0.785716 -0.618587 -5.73984e-05,
+                          0.977806 -0.209512 -1.94405e-05,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          0.785716 -0.618587 -5.73984e-05,
+                          0.43315 -0.901322 -8.36332e-05,
+                          0.785716 -0.618587 -5.73984e-05,
+                          0.977806 -0.209512 -1.94405e-05,
+                          0.977806 -0.209512 -1.94405e-05,
+                          0.970188 0.242355 2.2488e-05,
+                          0.785716 -0.618587 -5.73984e-05,
+                          0.977806 -0.209512 -1.94405e-05,
+                          0.977806 -0.209512 -1.94405e-05,
+                          0.970188 0.242355 2.2488e-05,
+                          0.970188 0.242355 2.2488e-05,
+                          0.764417 0.644723 5.98235e-05,
+                          0.977806 -0.209512 -1.94405e-05,
+                          0.970188 0.242355 2.2488e-05,
+                          0.970188 0.242355 2.2488e-05,
+                          0.764417 0.644723 5.98235e-05,
+                          0.764417 0.644723 5.98235e-05,
+                          0.40252 0.915411 8.49406e-05,
+                          0.970188 0.242355 2.2488e-05,
+                          0.764417 0.644723 5.98235e-05,
+                          0.764417 0.644723 5.98235e-05,
+                          0.40252 0.915411 8.49406e-05,
+                          0.40252 0.915411 8.49406e-05,
+                          0.40252 0.915411 8.49406e-05,
+                          0.764417 0.644723 5.98235e-05,
+                          0.40252 0.915411 8.49406e-05,
+                          0.40252 0.915411 8.49406e-05,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          0.40252 0.915411 8.49406e-05,
+                          0.40252 0.915411 8.49406e-05,
+                          0.40252 0.915411 8.49406e-05,
+                          -1 5.55456e-17 -4.63219e-16,
+                          -1 5.55456e-17 -4.63219e-16,
+                          -1 5.55456e-17 -4.63219e-16,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -1 5.55456e-17 -4.63219e-16,
+                          -1 5.55456e-17 -4.63219e-16,
+                          -1 5.55456e-17 -4.63219e-16,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 82.23 50.0054 -57.9954,
+                          95.6667 10.5836 -57.999,
+                          92.23 0.00538179 -58,
+                          92.23 0.00482506 -52,
+                          92.23 0.00538179 -58,
+                          95.6667 10.5836 -57.999,
+                          70.23 -57.4946 -58.0053,
+                          92.23 0.00538179 -58,
+                          95.6667 -10.5728 -58.001,
+                          95.6667 -10.5734 -52.001,
+                          95.6667 -10.5728 -58.001,
+                          92.23 0.00538179 -58,
+                          70.23 -57.4946 -58.0053,
+                          82.23 50.0054 -57.9954,
+                          92.23 0.00538179 -58,
+                          95.6667 -10.5734 -52.001,
+                          92.23 0.00538179 -58,
+                          92.23 0.00482506 -52,
+                          124.117 31.5871 -57.9971,
+                          104.667 17.1235 -57.9984,
+                          95.6667 10.5836 -57.999,
+                          95.6667 10.583 -51.999,
+                          95.6667 10.5836 -57.999,
+                          104.667 17.1235 -57.9984,
+                          82.23 50.0054 -57.9954,
+                          124.117 31.5871 -57.9971,
+                          95.6667 10.5836 -57.999,
+                          95.6667 10.583 -51.999,
+                          92.23 0.00482506 -52,
+                          95.6667 10.5836 -57.999,
+                          124.117 31.5871 -57.9971,
+                          115.793 17.1235 -57.9984,
+                          104.667 17.1235 -57.9984,
+                          104.667 17.123 -51.9984,
+                          104.667 17.1235 -57.9984,
+                          115.793 17.1235 -57.9984,
+                          95.6667 10.583 -51.999,
+                          104.667 17.1235 -57.9984,
+                          104.667 17.123 -51.9984,
+                          124.117 31.5871 -57.9971,
+                          124.793 10.5836 -57.999,
+                          115.793 17.1235 -57.9984,
+                          115.793 17.123 -51.9984,
+                          115.793 17.1235 -57.9984,
+                          124.793 10.5836 -57.999,
+                          104.667 17.123 -51.9984,
+                          115.793 17.1235 -57.9984,
+                          115.793 17.123 -51.9984,
+                          136.604 22.2463 -57.9979,
+                          128.23 0.00538179 -58,
+                          124.793 10.5836 -57.999,
+                          124.793 10.583 -51.999,
+                          124.793 10.5836 -57.999,
+                          128.23 0.00538179 -58,
+                          124.117 31.5871 -57.9971,
+                          136.604 22.2463 -57.9979,
+                          124.793 10.5836 -57.999,
+                          115.793 17.123 -51.9984,
+                          124.793 10.5836 -57.999,
+                          124.793 10.583 -51.999,
+                          125.174 -31.0902 -58.0029,
+                          124.793 -10.5728 -58.001,
+                          128.23 0.00538179 -58,
+                          128.23 0.00482506 -52,
+                          128.23 0.00538179 -58,
+                          124.793 -10.5728 -58.001,
+                          136.604 22.2463 -57.9979,
+                          125.174 -31.0902 -58.0029,
+                          128.23 0.00538179 -58,
+                          124.793 10.583 -51.999,
+                          128.23 0.00538179 -58,
+                          128.23 0.00482506 -52,
+                          70.23 -57.4946 -58.0053,
+                          115.793 -17.1127 -58.0016,
+                          124.793 -10.5728 -58.001,
+                          124.793 -10.5734 -52.001,
+                          124.793 -10.5728 -58.001,
+                          115.793 -17.1127 -58.0016,
+                          70.23 -57.4946 -58.0053,
+                          124.793 -10.5728 -58.001,
+                          125.174 -31.0902 -58.0029,
+                          128.23 0.00482506 -52,
+                          124.793 -10.5728 -58.001,
+                          124.793 -10.5734 -52.001,
+                          70.23 -57.4946 -58.0053,
+                          104.667 -17.1127 -58.0016,
+                          115.793 -17.1127 -58.0016,
+                          115.793 -17.1133 -52.0016,
+                          115.793 -17.1127 -58.0016,
+                          104.667 -17.1127 -58.0016,
+                          124.793 -10.5734 -52.001,
+                          115.793 -17.1127 -58.0016,
+                          115.793 -17.1133 -52.0016,
+                          70.23 -57.4946 -58.0053,
+                          95.6667 -10.5728 -58.001,
+                          104.667 -17.1127 -58.0016,
+                          104.667 -17.1133 -52.0016,
+                          104.667 -17.1127 -58.0016,
+                          95.6667 -10.5728 -58.001,
+                          115.793 -17.1133 -52.0016,
+                          104.667 -17.1127 -58.0016,
+                          104.667 -17.1133 -52.0016,
+                          104.667 -17.1133 -52.0016,
+                          95.6667 -10.5728 -58.001,
+                          95.6667 -10.5734 -52.001,
+                          136.604 22.2463 -57.9979,
+                          137.339 -21.3339 -58.002,
+                          125.174 -31.0902 -58.0029,
+                          125.174 -31.0908 -52.0029,
+                          125.174 -31.0902 -58.0029,
+                          137.339 -21.3339 -58.002,
+                          70.23 -57.4952 -52.0053,
+                          70.23 -57.4946 -58.0053,
+                          125.174 -31.0902 -58.0029,
+                          70.23 -57.4952 -52.0053,
+                          125.174 -31.0902 -58.0029,
+                          125.174 -31.0908 -52.0029,
+                          143.701 8.36534 -57.9992,
+                          143.964 -7.2215 -58.0007,
+                          137.339 -21.3339 -58.002,
+                          137.339 -21.3344 -52.002,
+                          137.339 -21.3339 -58.002,
+                          143.964 -7.2215 -58.0007,
+                          136.604 22.2463 -57.9979,
+                          143.701 8.36534 -57.9992,
+                          137.339 -21.3339 -58.002,
+                          137.339 -21.3344 -52.002,
+                          125.174 -31.0908 -52.0029,
+                          137.339 -21.3339 -58.002,
+                          143.964 -7.22205 -52.0007,
+                          143.964 -7.2215 -58.0007,
+                          143.701 8.36534 -57.9992,
+                          137.339 -21.3344 -52.002,
+                          143.964 -7.2215 -58.0007,
+                          143.964 -7.22205 -52.0007,
+                          143.701 8.36478 -51.9992,
+                          143.701 8.36534 -57.9992,
+                          136.604 22.2463 -57.9979,
+                          143.964 -7.22205 -52.0007,
+                          143.701 8.36534 -57.9992,
+                          143.701 8.36478 -51.9992,
+                          136.604 22.2458 -51.9979,
+                          136.604 22.2463 -57.9979,
+                          124.117 31.5871 -57.9971,
+                          143.701 8.36478 -51.9992,
+                          136.604 22.2463 -57.9979,
+                          136.604 22.2458 -51.9979,
+                          124.117 31.5865 -51.9971,
+                          124.117 31.5871 -57.9971,
+                          82.23 50.0054 -57.9954,
+                          136.604 22.2458 -51.9979,
+                          124.117 31.5871 -57.9971,
+                          124.117 31.5865 -51.9971,
+                          0.230049 -57.4946 -58.0053,
+                          0.230049 50.0054 -57.9954,
+                          82.23 50.0054 -57.9954,
+                          82.23 50.0048 -51.9954,
+                          82.23 50.0054 -57.9954,
+                          0.230049 50.0054 -57.9954,
+                          70.23 -57.4946 -58.0053,
+                          0.230049 -57.4946 -58.0053,
+                          82.23 50.0054 -57.9954,
+                          124.117 31.5865 -51.9971,
+                          82.23 50.0054 -57.9954,
+                          82.23 50.0048 -51.9954,
+                          0.230049 50.0048 -51.9954,
+                          0.230049 50.0054 -57.9954,
+                          0.230049 -57.4946 -58.0053,
+                          82.23 50.0048 -51.9954,
+                          0.230049 50.0054 -57.9954,
+                          0.230049 50.0048 -51.9954,
+                          0.230049 -57.4952 -52.0053,
+                          0.230049 -57.4946 -58.0053,
+                          70.23 -57.4946 -58.0053,
+                          0.230049 50.0048 -51.9954,
+                          0.230049 -57.4946 -58.0053,
+                          0.230049 -57.4952 -52.0053,
+                          0.230049 -57.4952 -52.0053,
+                          70.23 -57.4946 -58.0053,
+                          70.23 -57.4952 -52.0053,
+                          70.23 -57.4952 -52.0053,
+                          95.6667 -10.5734 -52.001,
+                          92.23 0.00482506 -52,
+                          82.23 50.0048 -51.9954,
+                          92.23 0.00482506 -52,
+                          95.6667 10.583 -51.999,
+                          82.23 50.0048 -51.9954,
+                          70.23 -57.4952 -52.0053,
+                          92.23 0.00482506 -52,
+                          70.23 -57.4952 -52.0053,
+                          104.667 -17.1133 -52.0016,
+                          95.6667 -10.5734 -52.001,
+                          125.174 -31.0908 -52.0029,
+                          115.793 -17.1133 -52.0016,
+                          104.667 -17.1133 -52.0016,
+                          70.23 -57.4952 -52.0053,
+                          125.174 -31.0908 -52.0029,
+                          104.667 -17.1133 -52.0016,
+                          125.174 -31.0908 -52.0029,
+                          124.793 -10.5734 -52.001,
+                          115.793 -17.1133 -52.0016,
+                          125.174 -31.0908 -52.0029,
+                          128.23 0.00482506 -52,
+                          124.793 -10.5734 -52.001,
+                          124.117 31.5865 -51.9971,
+                          124.793 10.583 -51.999,
+                          128.23 0.00482506 -52,
+                          137.339 -21.3344 -52.002,
+                          128.23 0.00482506 -52,
+                          125.174 -31.0908 -52.0029,
+                          136.604 22.2458 -51.9979,
+                          124.117 31.5865 -51.9971,
+                          128.23 0.00482506 -52,
+                          137.339 -21.3344 -52.002,
+                          136.604 22.2458 -51.9979,
+                          128.23 0.00482506 -52,
+                          124.117 31.5865 -51.9971,
+                          115.793 17.123 -51.9984,
+                          124.793 10.583 -51.999,
+                          82.23 50.0048 -51.9954,
+                          104.667 17.123 -51.9984,
+                          115.793 17.123 -51.9984,
+                          124.117 31.5865 -51.9971,
+                          82.23 50.0048 -51.9954,
+                          115.793 17.123 -51.9984,
+                          82.23 50.0048 -51.9954,
+                          95.6667 10.583 -51.999,
+                          104.667 17.123 -51.9984,
+                          0.230049 50.0048 -51.9954,
+                          0.230049 -57.4952 -52.0053,
+                          70.23 -57.4952 -52.0053,
+                          82.23 50.0048 -51.9954,
+                          0.230049 50.0048 -51.9954,
+                          70.23 -57.4952 -52.0053,
+                          137.339 -21.3344 -52.002,
+                          143.701 8.36478 -51.9992,
+                          136.604 22.2458 -51.9979,
+                          137.339 -21.3344 -52.002,
+                          143.964 -7.22205 -52.0007,
+                          143.701 8.36478 -51.9992 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    1 0 0
+    }
+    Separator {
+        Normal {
+            vector      [ 1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.50175e-16 0.707172 -0.707041,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          1.36156e-16 -0.707041 -0.707172,
+                          1.36156e-16 -0.707041 -0.707172,
+                          4.14599e-16 9.27896e-05 -1,
+                          1.36156e-16 -0.707041 -0.707172,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          4.50175e-16 0.707172 -0.707041,
+                          4.50175e-16 0.707172 -0.707041,
+                          2.22045e-16 1 9.27896e-05,
+                          4.50175e-16 0.707172 -0.707041,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.50175e-16 0.707172 -0.707041,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          -1.36156e-16 0.707041 0.707172,
+                          4.50175e-16 0.707172 -0.707041,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          -1.36156e-16 0.707041 0.707172,
+                          -1.36156e-16 0.707041 0.707172,
+                          -4.14599e-16 -9.27896e-05 1,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          2.22045e-16 1 9.27896e-05,
+                          -1.36156e-16 0.707041 0.707172,
+                          -1.36156e-16 0.707041 0.707172,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.50175e-16 -0.707172 0.707041,
+                          -1.36156e-16 0.707041 0.707172,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          -4.50175e-16 -0.707172 0.707041,
+                          -4.50175e-16 -0.707172 0.707041,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.50175e-16 -0.707172 0.707041,
+                          -4.50175e-16 -0.707172 0.707041,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          1.36156e-16 -0.707041 -0.707172,
+                          -4.50175e-16 -0.707172 0.707041,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          1.36156e-16 -0.707041 -0.707172,
+                          1.36156e-16 -0.707041 -0.707172,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          1 -5.55112e-17 4.63219e-16,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          -4.14599e-16 -9.27896e-05 1,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          4.14599e-16 9.27896e-05 -1,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16,
+                          -1 5.55112e-17 -4.63219e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 6.23005 -57.5049 52.9947,
+                          6.23005 -6.01061 6.00949,
+                          6.23005 -0.000788711 8.5,
+                          0.230049 -0.000788711 8.5,
+                          6.23005 -0.000788711 8.5,
+                          6.23005 -6.01061 6.00949,
+                          6.23005 -57.5049 52.9947,
+                          6.23005 -0.000788711 8.5,
+                          6.23005 6.00949 6.01061,
+                          0.230049 6.00949 6.01061,
+                          6.23005 6.00949 6.01061,
+                          6.23005 -0.000788711 8.5,
+                          0.230049 6.00949 6.01061,
+                          6.23005 -0.000788711 8.5,
+                          0.230049 -0.000788711 8.5,
+                          6.23005 -57.5049 52.9947,
+                          6.23005 -8.5 -0.000788711,
+                          6.23005 -6.01061 6.00949,
+                          0.230049 -6.01061 6.00949,
+                          6.23005 -6.01061 6.00949,
+                          6.23005 -8.5 -0.000788711,
+                          0.230049 -6.01061 6.00949,
+                          0.230049 -0.000788711 8.5,
+                          6.23005 -6.01061 6.00949,
+                          6.23005 -57.5049 52.9947,
+                          6.23005 -6.00949 -6.01061,
+                          6.23005 -8.5 -0.000788711,
+                          0.230049 -8.5 -0.000788711,
+                          6.23005 -8.5 -0.000788711,
+                          6.23005 -6.00949 -6.01061,
+                          0.230049 -6.01061 6.00949,
+                          6.23005 -8.5 -0.000788711,
+                          0.230049 -8.5 -0.000788711,
+                          6.23005 50.0048 -51.9954,
+                          6.23005 0.000788711 -8.5,
+                          6.23005 -6.00949 -6.01061,
+                          0.230049 -6.00949 -6.01061,
+                          6.23005 -6.00949 -6.01061,
+                          6.23005 0.000788711 -8.5,
+                          6.23005 -57.5049 52.9947,
+                          6.23005 -57.4952 -52.0053,
+                          6.23005 -6.00949 -6.01061,
+                          6.23005 50.0048 -51.9954,
+                          6.23005 -6.00949 -6.01061,
+                          6.23005 -57.4952 -52.0053,
+                          0.230049 -8.5 -0.000788711,
+                          6.23005 -6.00949 -6.01061,
+                          0.230049 -6.00949 -6.01061,
+                          6.23005 50.0048 -51.9954,
+                          6.23005 6.01061 -6.00949,
+                          6.23005 0.000788711 -8.5,
+                          0.230049 0.000788711 -8.5,
+                          6.23005 0.000788711 -8.5,
+                          6.23005 6.01061 -6.00949,
+                          0.230049 -6.00949 -6.01061,
+                          6.23005 0.000788711 -8.5,
+                          0.230049 0.000788711 -8.5,
+                          6.23005 50.0048 -51.9954,
+                          6.23005 8.5 0.000788711,
+                          6.23005 6.01061 -6.00949,
+                          0.230049 6.01061 -6.00949,
+                          6.23005 6.01061 -6.00949,
+                          6.23005 8.5 0.000788711,
+                          0.230049 0.000788711 -8.5,
+                          6.23005 6.01061 -6.00949,
+                          0.230049 6.01061 -6.00949,
+                          6.23005 50.0048 -51.9954,
+                          6.23005 6.00949 6.01061,
+                          6.23005 8.5 0.000788711,
+                          0.230049 8.5 0.000788711,
+                          6.23005 8.5 0.000788711,
+                          6.23005 6.00949 6.01061,
+                          0.230049 6.01061 -6.00949,
+                          6.23005 8.5 0.000788711,
+                          0.230049 8.5 0.000788711,
+                          6.23005 50.0007 -7.99536,
+                          6.23005 -57.5049 52.9947,
+                          6.23005 6.00949 6.01061,
+                          6.23005 50.0048 -51.9954,
+                          6.23005 50.0007 -7.99536,
+                          6.23005 6.00949 6.01061,
+                          0.230049 8.5 0.000788711,
+                          6.23005 6.00949 6.01061,
+                          0.230049 6.00949 6.01061,
+                          0.230049 -57.4952 -52.0053,
+                          6.23005 -57.4952 -52.0053,
+                          6.23005 -57.5049 52.9947,
+                          0.230049 50.0048 -51.9954,
+                          6.23005 50.0048 -51.9954,
+                          6.23005 -57.4952 -52.0053,
+                          0.230049 50.0048 -51.9954,
+                          6.23005 -57.4952 -52.0053,
+                          0.230049 -57.4952 -52.0053,
+                          6.23005 50.0007 -7.99536,
+                          6.23005 49.9951 53.0046,
+                          6.23005 -57.5049 52.9947,
+                          0.230049 -57.5049 52.9947,
+                          6.23005 -57.5049 52.9947,
+                          6.23005 49.9951 53.0046,
+                          0.230049 -57.5049 52.9947,
+                          0.230049 -57.4952 -52.0053,
+                          6.23005 -57.5049 52.9947,
+                          0.230049 49.9951 53.0046,
+                          6.23005 49.9951 53.0046,
+                          6.23005 50.0007 -7.99536,
+                          0.230049 -57.5049 52.9947,
+                          6.23005 49.9951 53.0046,
+                          0.230049 49.9951 53.0046,
+                          6.23005 64.7548 -51.994,
+                          6.23005 64.7507 -7.99399,
+                          6.23005 50.0007 -7.99536,
+                          0.230049 50.0007 -7.99536,
+                          6.23005 50.0007 -7.99536,
+                          6.23005 64.7507 -7.99399,
+                          6.23005 50.0048 -51.9954,
+                          6.23005 64.7548 -51.994,
+                          6.23005 50.0007 -7.99536,
+                          0.230049 49.9951 53.0046,
+                          6.23005 50.0007 -7.99536,
+                          0.230049 50.0007 -7.99536,
+                          0.230049 64.7507 -7.99399,
+                          6.23005 64.7507 -7.99399,
+                          6.23005 64.7548 -51.994,
+                          0.230049 50.0007 -7.99536,
+                          6.23005 64.7507 -7.99399,
+                          0.230049 64.7507 -7.99399,
+                          0.230049 64.7548 -51.994,
+                          6.23005 64.7548 -51.994,
+                          6.23005 50.0048 -51.9954,
+                          0.230049 64.7507 -7.99399,
+                          6.23005 64.7548 -51.994,
+                          0.230049 64.7548 -51.994,
+                          0.230049 64.7548 -51.994,
+                          6.23005 50.0048 -51.9954,
+                          0.230049 50.0048 -51.9954,
+                          0.230049 49.9951 53.0046,
+                          0.230049 6.00949 6.01061,
+                          0.230049 -0.000788711 8.5,
+                          0.230049 49.9951 53.0046,
+                          0.230049 -0.000788711 8.5,
+                          0.230049 -6.01061 6.00949,
+                          0.230049 49.9951 53.0046,
+                          0.230049 8.5 0.000788711,
+                          0.230049 6.00949 6.01061,
+                          0.230049 49.9951 53.0046,
+                          0.230049 6.01061 -6.00949,
+                          0.230049 8.5 0.000788711,
+                          0.230049 -57.4952 -52.0053,
+                          0.230049 0.000788711 -8.5,
+                          0.230049 6.01061 -6.00949,
+                          0.230049 50.0007 -7.99536,
+                          0.230049 -57.4952 -52.0053,
+                          0.230049 6.01061 -6.00949,
+                          0.230049 49.9951 53.0046,
+                          0.230049 50.0007 -7.99536,
+                          0.230049 6.01061 -6.00949,
+                          0.230049 -57.4952 -52.0053,
+                          0.230049 -6.00949 -6.01061,
+                          0.230049 0.000788711 -8.5,
+                          0.230049 -57.4952 -52.0053,
+                          0.230049 -8.5 -0.000788711,
+                          0.230049 -6.00949 -6.01061,
+                          0.230049 -57.4952 -52.0053,
+                          0.230049 -6.01061 6.00949,
+                          0.230049 -8.5 -0.000788711,
+                          0.230049 -57.5049 52.9947,
+                          0.230049 -6.01061 6.00949,
+                          0.230049 -57.4952 -52.0053,
+                          0.230049 -57.5049 52.9947,
+                          0.230049 49.9951 53.0046,
+                          0.230049 -6.01061 6.00949,
+                          0.230049 50.0007 -7.99536,
+                          0.230049 50.0048 -51.9954,
+                          0.230049 -57.4952 -52.0053,
+                          0.230049 64.7507 -7.99399,
+                          0.230049 64.7548 -51.994,
+                          0.230049 50.0048 -51.9954,
+                          0.230049 50.0007 -7.99536,
+                          0.230049 64.7507 -7.99399,
+                          0.230049 50.0048 -51.9954 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.666667 0.208556 0.221419
+    }
+    Separator {
+        Normal {
+            vector      [ 2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          0.5 8.03581e-05 -0.866025,
+                          0.5 8.03581e-05 -0.866025,
+                          0.5 8.03581e-05 -0.866025,
+                          0.5 8.03581e-05 -0.866025,
+                          0.5 8.03581e-05 -0.866025,
+                          0.5 8.03581e-05 -0.866025,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 0.230049 -57.5055 58.9947,
+                          70.23 -57.5055 58.9947,
+                          70.23 -57.5022 23.9947,
+                          70.23 -60.5022 23.9944,
+                          70.23 -57.5022 23.9947,
+                          70.23 -57.5055 58.9947,
+                          50.23 -57.5012 12.4477,
+                          0.230049 -57.5055 58.9947,
+                          70.23 -57.5022 23.9947,
+                          50.23 -60.5012 12.4474,
+                          50.23 -57.5012 12.4477,
+                          70.23 -57.5022 23.9947,
+                          50.23 -60.5012 12.4474,
+                          70.23 -57.5022 23.9947,
+                          70.23 -60.5022 23.9944,
+                          70.23 -60.5055 58.9944,
+                          70.23 -57.5055 58.9947,
+                          0.230049 -57.5055 58.9947,
+                          70.23 -60.5055 58.9944,
+                          70.23 -60.5022 23.9944,
+                          70.23 -57.5055 58.9947,
+                          50.23 -57.4946 -58.0053,
+                          0.230049 -57.4946 -58.0053,
+                          0.230049 -57.5055 58.9947,
+                          0.230049 -60.5055 58.9944,
+                          0.230049 -57.5055 58.9947,
+                          0.230049 -57.4946 -58.0053,
+                          50.23 -57.5012 12.4477,
+                          50.23 -57.4946 -58.0053,
+                          0.230049 -57.5055 58.9947,
+                          70.23 -60.5055 58.9944,
+                          0.230049 -57.5055 58.9947,
+                          0.230049 -60.5055 58.9944,
+                          0.230049 -60.4946 -58.0056,
+                          0.230049 -57.4946 -58.0053,
+                          50.23 -57.4946 -58.0053,
+                          0.230049 -60.5055 58.9944,
+                          0.230049 -57.4946 -58.0053,
+                          0.230049 -60.4946 -58.0056,
+                          50.23 -60.4946 -58.0056,
+                          50.23 -57.4946 -58.0053,
+                          50.23 -57.5012 12.4477,
+                          0.230049 -60.4946 -58.0056,
+                          50.23 -57.4946 -58.0053,
+                          50.23 -60.4946 -58.0056,
+                          50.23 -60.4946 -58.0056,
+                          50.23 -57.5012 12.4477,
+                          50.23 -60.5012 12.4474,
+                          70.23 -60.5055 58.9944,
+                          50.23 -60.5012 12.4474,
+                          70.23 -60.5022 23.9944,
+                          0.230049 -60.4946 -58.0056,
+                          50.23 -60.4946 -58.0056,
+                          50.23 -60.5012 12.4474,
+                          70.23 -60.5055 58.9944,
+                          0.230049 -60.4946 -58.0056,
+                          50.23 -60.5012 12.4474,
+                          70.23 -60.5055 58.9944,
+                          0.230049 -60.5055 58.9944,
+                          0.230049 -60.4946 -58.0056 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.6 0.6 0.6
+    }
+    Separator {
+        Normal {
+            vector      [ -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          2.39635e-17 0.29448 0.955658,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          7.34644e-17 0.49992 0.866072,
+                          -4.33681e-17 -9.27896e-05 1,
+                          2.39635e-17 0.29448 0.955658,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          0.62488 0.780721 7.24428e-05,
+                          0.62488 0.780721 7.24428e-05,
+                          0.62488 0.780721 7.24428e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          0.62488 0.780721 7.24428e-05,
+                          0.62488 0.780721 7.24428e-05,
+                          0.62488 0.780721 7.24428e-05,
+                          0.62488 0.780721 7.24428e-05,
+                          0.62488 0.780721 7.24428e-05,
+                          0.62488 0.780721 7.24428e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          0.62488 0.780721 7.24428e-05,
+                          0.62488 0.780721 7.24428e-05,
+                          0.882652 0.470027 4.36136e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          0.62488 0.780721 7.24428e-05,
+                          0.62488 0.780721 7.24428e-05,
+                          0.62488 0.780721 7.24428e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          0.882652 0.470027 4.36136e-05,
+                          0.882652 0.470027 4.36136e-05,
+                          0.996572 0.0827302 7.67649e-06,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          0.62488 0.780721 7.24428e-05,
+                          0.882652 0.470027 4.36136e-05,
+                          0.882652 0.470027 4.36136e-05,
+                          0.996572 0.0827302 7.67649e-06,
+                          0.996572 0.0827302 7.67649e-06,
+                          0.948074 -0.31805 -2.95117e-05,
+                          0.882652 0.470027 4.36136e-05,
+                          0.996572 0.0827302 7.67649e-06,
+                          0.996572 0.0827302 7.67649e-06,
+                          0.948074 -0.31805 -2.95117e-05,
+                          0.948074 -0.31805 -2.95117e-05,
+                          0.745061 -0.666996 -6.18902e-05,
+                          0.996572 0.0827302 7.67649e-06,
+                          0.948074 -0.31805 -2.95117e-05,
+                          0.948074 -0.31805 -2.95117e-05,
+                          0.745061 -0.666996 -6.18902e-05,
+                          0.745061 -0.666996 -6.18902e-05,
+                          0.420621 -0.907236 -8.41821e-05,
+                          0.948074 -0.31805 -2.95117e-05,
+                          0.745061 -0.666996 -6.18902e-05,
+                          0.745061 -0.666996 -6.18902e-05,
+                          0.420621 -0.907236 -8.41821e-05,
+                          0.420621 -0.907236 -8.41821e-05,
+                          0.420621 -0.907236 -8.41821e-05,
+                          0.745061 -0.666996 -6.18902e-05,
+                          0.420621 -0.907236 -8.41821e-05,
+                          0.420621 -0.907236 -8.41821e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          0.420621 -0.907236 -8.41821e-05,
+                          0.420621 -0.907236 -8.41821e-05,
+                          0.420621 -0.907236 -8.41821e-05,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          -7.34644e-17 -0.49992 -0.866072,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          -7.34644e-17 -0.49992 -0.866072,
+                          -3.83843e-17 -0.35534 -0.934737,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          0.62488 0.780721 7.24428e-05,
+                          0.62488 0.780721 7.24428e-05,
+                          0.62488 0.780721 7.24428e-05,
+                          7.34644e-17 0.49992 0.866072,
+                          2.39635e-17 0.29448 0.955658,
+                          8.42e-17 0.543112 0.83966,
+                          0.62488 0.780721 7.24428e-05,
+                          0.62488 0.780721 7.24428e-05,
+                          0.62488 0.780721 7.24428e-05,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1.70612e-16 0.865979 0.50008,
+                          8.42e-17 0.543112 0.83966,
+                          1.74317e-16 0.878356 0.478006,
+                          1.70612e-16 0.865979 0.50008,
+                          7.34644e-17 0.49992 0.866072,
+                          8.42e-17 0.543112 0.83966,
+                          -7.34644e-17 -0.49992 -0.866072,
+                          -1.07166e-16 -0.633649 -0.77362,
+                          -3.83843e-17 -0.35534 -0.934737,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          -7.34644e-17 -0.49992 -0.866072,
+                          -1.70612e-16 -0.865979 -0.50008,
+                          -1.07166e-16 -0.633649 -0.77362,
+                          -1.82119e-16 -0.903743 -0.428076,
+                          -1.07166e-16 -0.633649 -0.77362,
+                          -1.70612e-16 -0.865979 -0.50008,
+                          1.70612e-16 0.865979 0.50008,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          1.70612e-16 0.865979 0.50008,
+                          1.74317e-16 0.878356 0.478006,
+                          2.22045e-16 1 9.27896e-05,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1.82119e-16 -0.903743 -0.428076,
+                          -1.70612e-16 -0.865979 -0.50008,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -1.82119e-16 -0.903743 -0.428076,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 59.524 -62.0082 87.9942,
+                          82.7313 66.9918 88.0062,
+                          32.23 66.9918 88.0062,
+                          77.5797 71.1151 87.3856,
+                          32.23 66.9918 88.0062,
+                          82.7313 66.9918 88.0062,
+                          32.23 55.9918 88.0052,
+                          59.524 -62.0082 87.9942,
+                          32.23 66.9918 88.0062,
+                          32.23 55.992 86.0052,
+                          32.23 55.9918 88.0052,
+                          32.23 66.9918 88.0062,
+                          32.23 55.992 86.0052,
+                          32.23 66.9918 88.0062,
+                          32.23 66.992 86.0062,
+                          32.23 73.993 86.1302,
+                          32.23 66.992 86.0062,
+                          32.23 66.9918 88.0062,
+                          32.23 73.993 86.1302,
+                          32.23 66.9918 88.0062,
+                          77.5797 71.1151 87.3856,
+                          125.741 -31.3078 87.9971,
+                          132.788 26.9267 88.0025,
+                          82.7313 66.9918 88.0062,
+                          82.7313 66.992 86.0062,
+                          82.7313 66.9918 88.0062,
+                          132.788 26.9267 88.0025,
+                          59.524 -62.0082 87.9942,
+                          125.741 -31.3078 87.9971,
+                          82.7313 66.9918 88.0062,
+                          77.4024 71.2572 85.2231,
+                          82.7313 66.9918 88.0062,
+                          82.7313 66.992 86.0062,
+                          77.4024 71.2572 85.2231,
+                          77.5797 71.1151 87.3856,
+                          82.7313 66.9918 88.0062,
+                          136.935 -23.0184 87.9979,
+                          141.682 16.2066 88.0015,
+                          132.788 26.9267 88.0025,
+                          132.788 26.9269 86.0025,
+                          132.788 26.9267 88.0025,
+                          141.682 16.2066 88.0015,
+                          125.741 -31.3078 87.9971,
+                          136.935 -23.0184 87.9979,
+                          132.788 26.9267 88.0025,
+                          82.7313 66.992 86.0062,
+                          132.788 26.9267 88.0025,
+                          132.788 26.9269 86.0025,
+                          143.938 -10.9828 87.999,
+                          145.611 2.84811 88.0003,
+                          141.682 16.2066 88.0015,
+                          141.682 16.2068 86.0015,
+                          141.682 16.2066 88.0015,
+                          145.611 2.84811 88.0003,
+                          136.935 -23.0184 87.9979,
+                          143.938 -10.9828 87.999,
+                          141.682 16.2066 88.0015,
+                          132.788 26.9269 86.0025,
+                          141.682 16.2066 88.0015,
+                          141.682 16.2068 86.0015,
+                          145.611 2.8483 86.0003,
+                          145.611 2.84811 88.0003,
+                          143.938 -10.9828 87.999,
+                          141.682 16.2068 86.0015,
+                          145.611 2.84811 88.0003,
+                          145.611 2.8483 86.0003,
+                          143.938 -10.9827 85.999,
+                          143.938 -10.9828 87.999,
+                          136.935 -23.0184 87.9979,
+                          145.611 2.8483 86.0003,
+                          143.938 -10.9828 87.999,
+                          143.938 -10.9827 85.999,
+                          136.935 -23.0183 85.9979,
+                          136.935 -23.0184 87.9979,
+                          125.741 -31.3078 87.9971,
+                          143.938 -10.9827 85.999,
+                          136.935 -23.0184 87.9979,
+                          136.935 -23.0183 85.9979,
+                          125.741 -31.3076 85.9971,
+                          125.741 -31.3078 87.9971,
+                          59.524 -62.0082 87.9942,
+                          136.935 -23.0183 85.9979,
+                          125.741 -31.3078 87.9971,
+                          125.741 -31.3076 85.9971,
+                          3.23005 62.4918 88.0058,
+                          3.23005 -62.0082 87.9942,
+                          59.524 -62.0082 87.9942,
+                          59.524 -62.008 85.9942,
+                          59.524 -62.0082 87.9942,
+                          3.23005 -62.0082 87.9942,
+                          7.23005 55.9918 88.0052,
+                          3.23005 62.4918 88.0058,
+                          59.524 -62.0082 87.9942,
+                          32.23 55.9918 88.0052,
+                          7.23005 55.9918 88.0052,
+                          59.524 -62.0082 87.9942,
+                          125.741 -31.3076 85.9971,
+                          59.524 -62.0082 87.9942,
+                          59.524 -62.008 85.9942,
+                          3.23005 -62.0072 77.9942,
+                          3.23005 -62.0082 87.9942,
+                          3.23005 62.4918 88.0058,
+                          59.524 -62.008 85.9942,
+                          3.23005 -62.0082 87.9942,
+                          5.23005 -62.008 85.9942,
+                          5.23005 -62.0072 77.9942,
+                          5.23005 -62.008 85.9942,
+                          3.23005 -62.0082 87.9942,
+                          5.23005 -62.0072 77.9942,
+                          3.23005 -62.0082 87.9942,
+                          3.23005 -62.0072 77.9942,
+                          7.23005 55.9918 88.0052,
+                          7.23005 62.4918 88.0058,
+                          3.23005 62.4918 88.0058,
+                          7.23005 62.492 86.0058,
+                          3.23005 62.4918 88.0058,
+                          7.23005 62.4918 88.0058,
+                          5.23005 62.492 86.0058,
+                          3.23005 62.4918 88.0058,
+                          7.23005 62.492 86.0058,
+                          5.23005 62.4928 78.0058,
+                          3.23005 62.4918 88.0058,
+                          5.23005 62.492 86.0058,
+                          3.23005 -62.0072 77.9942,
+                          3.23005 62.4918 88.0058,
+                          3.23005 62.4928 78.0058,
+                          5.23005 62.4928 78.0058,
+                          3.23005 62.4928 78.0058,
+                          3.23005 62.4918 88.0058,
+                          7.23005 62.492 86.0058,
+                          7.23005 62.4918 88.0058,
+                          7.23005 55.9918 88.0052,
+                          7.23005 55.992 86.0052,
+                          7.23005 55.9918 88.0052,
+                          32.23 55.9918 88.0052,
+                          7.23005 62.492 86.0058,
+                          7.23005 55.9918 88.0052,
+                          7.23005 55.992 86.0052,
+                          7.23005 55.992 86.0052,
+                          32.23 55.9918 88.0052,
+                          32.23 55.992 86.0052,
+                          82.7313 66.992 86.0062,
+                          32.23 55.992 86.0052,
+                          32.23 66.992 86.0062,
+                          32.23 72.993 84.3982,
+                          82.7313 66.992 86.0062,
+                          32.23 66.992 86.0062,
+                          32.23 72.993 84.3982,
+                          32.23 66.992 86.0062,
+                          32.23 73.993 86.1302,
+                          5.23005 -62.008 85.9942,
+                          7.23005 55.992 86.0052,
+                          32.23 55.992 86.0052,
+                          59.524 -62.008 85.9942,
+                          5.23005 -62.008 85.9942,
+                          32.23 55.992 86.0052,
+                          82.7313 66.992 86.0062,
+                          59.524 -62.008 85.9942,
+                          32.23 55.992 86.0052,
+                          5.23005 -62.008 85.9942,
+                          7.23005 62.492 86.0058,
+                          7.23005 55.992 86.0052,
+                          5.23005 -62.008 85.9942,
+                          5.23005 62.492 86.0058,
+                          7.23005 62.492 86.0058,
+                          5.23005 62.4928 78.0058,
+                          5.23005 62.492 86.0058,
+                          5.23005 -62.008 85.9942,
+                          5.23005 62.4928 78.0058,
+                          5.23005 -62.008 85.9942,
+                          5.23005 -62.0072 77.9942,
+                          82.7313 66.992 86.0062,
+                          125.741 -31.3076 85.9971,
+                          59.524 -62.008 85.9942,
+                          132.788 26.9269 86.0025,
+                          136.935 -23.0183 85.9979,
+                          125.741 -31.3076 85.9971,
+                          82.7313 66.992 86.0062,
+                          132.788 26.9269 86.0025,
+                          125.741 -31.3076 85.9971,
+                          141.682 16.2068 86.0015,
+                          143.938 -10.9827 85.999,
+                          136.935 -23.0183 85.9979,
+                          132.788 26.9269 86.0025,
+                          141.682 16.2068 86.0015,
+                          136.935 -23.0183 85.9979,
+                          141.682 16.2068 86.0015,
+                          145.611 2.8483 86.0003,
+                          143.938 -10.9827 85.999,
+                          32.23 72.993 84.3982,
+                          77.4024 71.2572 85.2231,
+                          82.7313 66.992 86.0062,
+                          5.23005 -62.0072 77.9942,
+                          3.23005 -62.0072 77.9942,
+                          3.23005 62.4928 78.0058,
+                          5.23005 62.4928 78.0058,
+                          5.23005 -62.0072 77.9942,
+                          3.23005 62.4928 78.0058,
+                          73.23 74.5969 83.2897,
+                          73.23 74.5967 85.7615,
+                          77.5797 71.1151 87.3856,
+                          32.23 73.993 86.1302,
+                          77.5797 71.1151 87.3856,
+                          73.23 74.5967 85.7615,
+                          77.4024 71.2572 85.2231,
+                          73.23 74.5969 83.2897,
+                          77.5797 71.1151 87.3856,
+                          73.23 79.2901 80.6983,
+                          73.23 74.5967 85.7615,
+                          73.23 74.5969 83.2897,
+                          32.23 79.1159 81.0083,
+                          73.23 74.5967 85.7615,
+                          73.23 79.2901 80.6983,
+                          32.23 79.1159 81.0083,
+                          32.23 73.993 86.1302,
+                          73.23 74.5967 85.7615,
+                          32.23 72.993 84.3982,
+                          73.23 74.5969 83.2897,
+                          77.4024 71.2572 85.2231,
+                          73.23 77.8378 79.143,
+                          73.23 79.2901 80.6983,
+                          73.23 74.5969 83.2897,
+                          32.23 72.993 84.3982,
+                          32.23 77.384 80.008,
+                          73.23 74.5969 83.2897,
+                          73.23 77.8378 79.143,
+                          73.23 74.5969 83.2897,
+                          32.23 77.384 80.008,
+                          32.23 79.1159 81.0083,
+                          73.23 80.9931 74.0075,
+                          32.23 80.9931 74.0075,
+                          32.23 80.9937 68.0075,
+                          32.23 80.9931 74.0075,
+                          73.23 80.9931 74.0075,
+                          32.23 78.9937 68.0073,
+                          32.23 79.1159 81.0083,
+                          32.23 80.9931 74.0075,
+                          32.23 80.9937 68.0075,
+                          32.23 78.9937 68.0073,
+                          32.23 80.9931 74.0075,
+                          32.23 79.1159 81.0083,
+                          73.23 79.2901 80.6983,
+                          73.23 80.9931 74.0075,
+                          73.23 78.9931 74.0073,
+                          73.23 80.9931 74.0075,
+                          73.23 79.2901 80.6983,
+                          73.23 78.9937 68.0073,
+                          73.23 80.9931 74.0075,
+                          73.23 78.9931 74.0073,
+                          73.23 80.9937 68.0075,
+                          73.23 80.9931 74.0075,
+                          73.23 78.9937 68.0073,
+                          32.23 80.9937 68.0075,
+                          73.23 80.9931 74.0075,
+                          73.23 80.9937 68.0075,
+                          73.23 78.9931 74.0073,
+                          73.23 79.2901 80.6983,
+                          73.23 77.8378 79.143,
+                          32.23 77.384 80.008,
+                          32.23 73.993 86.1302,
+                          32.23 79.1159 81.0083,
+                          32.23 72.993 84.3982,
+                          32.23 73.993 86.1302,
+                          32.23 77.384 80.008,
+                          32.23 77.384 80.008,
+                          32.23 79.1159 81.0083,
+                          32.23 78.9931 74.0073,
+                          32.23 78.9937 68.0073,
+                          32.23 78.9931 74.0073,
+                          32.23 79.1159 81.0083,
+                          73.23 77.8378 79.143,
+                          32.23 77.384 80.008,
+                          32.23 78.9931 74.0073,
+                          73.23 78.9931 74.0073,
+                          73.23 77.8378 79.143,
+                          32.23 78.9931 74.0073,
+                          73.23 78.9937 68.0073,
+                          73.23 78.9931 74.0073,
+                          32.23 78.9931 74.0073,
+                          32.23 78.9937 68.0073,
+                          73.23 78.9937 68.0073,
+                          32.23 78.9931 74.0073,
+                          73.23 80.9937 68.0075,
+                          73.23 78.9937 68.0073,
+                          32.23 78.9937 68.0073,
+                          32.23 80.9937 68.0075,
+                          73.23 80.9937 68.0075,
+                          32.23 78.9937 68.0073 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.463437 0.535976 0.575758
+    }
+    Separator {
+        Normal {
+            vector      [ 1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.2624e-16 0.981181 -0.19309,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          1.7064e-16 0.866073 0.499918,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.09484e-16 0.981145 0.193272,
+                          2.22045e-16 1 9.27896e-05,
+                          1.7064e-16 0.866073 0.499918,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          2.13994e-16 0.866166 -0.499757,
+                          2.22045e-16 1 9.27896e-05,
+                          2.2187e-16 0.925035 -0.379881,
+                          2.2624e-16 0.981181 -0.19309,
+                          2.2187e-16 0.925035 -0.379881,
+                          2.22045e-16 1 9.27896e-05,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          2.13994e-16 0.866166 -0.499757,
+                          2.2187e-16 0.925035 -0.379881,
+                          1.99461e-16 0.774875 -0.632114,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1.7064e-16 0.866073 0.499918,
+                          1.44627e-16 0.774758 0.632258,
+                          1.88913e-16 0.924965 0.380053,
+                          2.09484e-16 0.981145 0.193272,
+                          1.7064e-16 0.866073 0.499918,
+                          1.88913e-16 0.924965 0.380053,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          1.4854e-16 0.499874 -0.866098,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1.4854e-16 0.499874 -0.866098,
+                          1.06118e-16 0.291144 -0.956679,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          2.31366e-17 0.290966 0.956733,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          7.34135e-17 0.499714 0.866191,
+                          -4.33681e-17 -9.27896e-05 1,
+                          2.31366e-17 0.290966 0.956733,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          2.13994e-16 0.866166 -0.499757,
+                          1.99461e-16 0.774875 -0.632114,
+                          1.59601e-16 0.556584 -0.830791,
+                          1.4854e-16 0.499874 -0.866098,
+                          1.59601e-16 0.556584 -0.830791,
+                          1.06118e-16 0.291144 -0.956679,
+                          2.13994e-16 0.866166 -0.499757,
+                          1.59601e-16 0.556584 -0.830791,
+                          1.4854e-16 0.499874 -0.866098,
+                          7.34135e-17 0.499714 0.866191,
+                          2.31366e-17 0.290966 0.956733,
+                          8.75373e-17 0.55643 0.830895,
+                          7.34135e-17 0.499714 0.866191,
+                          8.75373e-17 0.55643 0.830895,
+                          1.44627e-16 0.774758 0.632258,
+                          7.34135e-17 0.499714 0.866191,
+                          1.44627e-16 0.774758 0.632258,
+                          1.7064e-16 0.866073 0.499918 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 73.23 81.007 -74.9925,
+                          73.23 82.493 76.0077,
+                          73.23 80.993 76.0075,
+                          3.23005 82.493 76.0077,
+                          73.23 80.993 76.0075,
+                          73.23 82.493 76.0077,
+                          3.23005 81.007 -74.9925,
+                          73.23 81.007 -74.9925,
+                          73.23 80.993 76.0075,
+                          3.23005 82.493 76.0077,
+                          3.23005 80.993 76.0075,
+                          73.23 80.993 76.0075,
+                          3.23005 80.993 75.6069,
+                          73.23 80.993 76.0075,
+                          3.23005 80.993 76.0075,
+                          3.23005 81.0069 -74.5918,
+                          3.23005 81.007 -74.9925,
+                          73.23 80.993 76.0075,
+                          3.23005 80.993 75.6069,
+                          3.23005 81.0069 -74.5918,
+                          73.23 80.993 76.0075,
+                          73.23 81.007 -74.9925,
+                          73.23 82.507 -74.9923,
+                          73.23 82.493 76.0077,
+                          3.23005 82.493 76.0077,
+                          73.23 82.493 76.0077,
+                          73.23 82.507 -74.9923,
+                          3.23005 81.007 -74.9925,
+                          73.23 82.507 -74.9923,
+                          73.23 81.007 -74.9925,
+                          3.23005 82.4937 68.0077,
+                          3.23005 82.493 76.0077,
+                          73.23 82.507 -74.9923,
+                          3.23005 82.507 -74.9923,
+                          3.23005 82.5062 -66.9923,
+                          73.23 82.507 -74.9923,
+                          1.73005 82.4937 68.0077,
+                          73.23 82.507 -74.9923,
+                          3.23005 82.5062 -66.9923,
+                          3.23005 81.007 -74.9925,
+                          3.23005 82.507 -74.9923,
+                          73.23 82.507 -74.9923,
+                          1.73005 82.4937 68.0077,
+                          3.23005 82.4937 68.0077,
+                          73.23 82.507 -74.9923,
+                          3.23005 82.1164 71.8712,
+                          3.23005 80.993 76.0075,
+                          3.23005 82.493 76.0077,
+                          3.23005 82.1164 71.8712,
+                          3.23005 80.993 75.6069,
+                          3.23005 80.993 76.0075,
+                          3.23005 82.1164 71.8712,
+                          3.23005 82.493 76.0077,
+                          3.23005 82.4937 68.0077,
+                          3.23005 82.1296 -70.856,
+                          3.23005 82.5062 -66.9923,
+                          3.23005 82.507 -74.9923,
+                          1.73005 82.5062 -66.9923,
+                          1.73005 82.4937 68.0077,
+                          3.23005 82.5062 -66.9923,
+                          3.23005 82.1296 -70.856,
+                          1.73005 82.5062 -66.9923,
+                          3.23005 82.5062 -66.9923,
+                          3.23005 81.0069 -74.5918,
+                          3.23005 82.507 -74.9923,
+                          3.23005 81.007 -74.9925,
+                          3.23005 82.1296 -70.856,
+                          3.23005 82.507 -74.9923,
+                          3.23005 81.0069 -74.5918,
+                          1.73005 79.8151 78.0042,
+                          3.23005 82.4937 68.0077,
+                          1.73005 82.4937 68.0077,
+                          3.23005 82.1164 71.8712,
+                          3.23005 82.4937 68.0077,
+                          1.73005 79.8151 78.0042,
+                          1.73005 52.4918 88.0049,
+                          1.73005 82.4937 68.0077,
+                          1.73005 82.5062 -66.9923,
+                          1.73005 79.8151 78.0042,
+                          1.73005 82.4937 68.0077,
+                          1.73005 52.4918 88.0049,
+                          1.73005 79.8295 -76.9893,
+                          1.73005 82.5062 -66.9923,
+                          3.23005 81.0069 -74.5918,
+                          3.23005 82.1296 -70.856,
+                          3.23005 81.0069 -74.5918,
+                          1.73005 82.5062 -66.9923,
+                          1.73005 79.8295 -76.9893,
+                          1.73005 52.4918 88.0049,
+                          1.73005 82.5062 -66.9923,
+                          3.23005 52.5081 -86.9951,
+                          3.23005 81.0069 -74.5918,
+                          3.23005 80.993 75.6069,
+                          3.23005 78.0028 -79.6377,
+                          3.23005 81.0069 -74.5918,
+                          3.23005 52.5081 -86.9951,
+                          1.73005 79.8295 -76.9893,
+                          3.23005 81.0069 -74.5918,
+                          3.23005 78.0028 -79.6377,
+                          3.23005 77.9879 80.6522,
+                          3.23005 52.5081 -86.9951,
+                          3.23005 80.993 75.6069,
+                          1.73005 79.8151 78.0042,
+                          3.23005 77.9879 80.6522,
+                          3.23005 80.993 75.6069,
+                          3.23005 82.1164 71.8712,
+                          1.73005 79.8151 78.0042,
+                          3.23005 80.993 75.6069,
+                          3.23005 52.5081 -86.9951,
+                          1.73005 62.5081 -86.9942,
+                          3.23005 62.5081 -86.9942,
+                          1.73005 72.5037 -84.3162,
+                          3.23005 62.5081 -86.9942,
+                          1.73005 62.5081 -86.9942,
+                          3.23005 68.3303 -86.1266,
+                          3.23005 52.5081 -86.9951,
+                          3.23005 62.5081 -86.9942,
+                          1.73005 72.5037 -84.3162,
+                          3.23005 68.3303 -86.1266,
+                          3.23005 62.5081 -86.9942,
+                          3.23005 52.5081 -86.9951,
+                          1.73005 52.5081 -86.9951,
+                          1.73005 62.5081 -86.9942,
+                          1.73005 52.4918 88.0049,
+                          1.73005 62.5081 -86.9942,
+                          1.73005 52.5081 -86.9951,
+                          1.73005 72.5037 -84.3162,
+                          1.73005 62.5081 -86.9942,
+                          1.73005 52.4918 88.0049,
+                          3.23005 52.4918 88.0049,
+                          1.73005 52.5081 -86.9951,
+                          3.23005 52.5081 -86.9951,
+                          1.73005 52.4918 88.0049,
+                          1.73005 52.5081 -86.9951,
+                          3.23005 52.4918 88.0049,
+                          3.23005 52.4918 88.0049,
+                          3.23005 52.5081 -86.9951,
+                          3.23005 62.4918 88.0058,
+                          3.23005 68.3142 87.1393,
+                          3.23005 62.4918 88.0058,
+                          3.23005 52.5081 -86.9951,
+                          3.23005 73.638 -83.6101,
+                          3.23005 78.0028 -79.6377,
+                          3.23005 52.5081 -86.9951,
+                          3.23005 68.3303 -86.1266,
+                          3.23005 73.638 -83.6101,
+                          3.23005 52.5081 -86.9951,
+                          3.23005 73.6224 84.6237,
+                          3.23005 68.3142 87.1393,
+                          3.23005 52.5081 -86.9951,
+                          3.23005 77.9879 80.6522,
+                          3.23005 73.6224 84.6237,
+                          3.23005 52.5081 -86.9951,
+                          1.73005 52.4918 88.0049,
+                          3.23005 62.4918 88.0058,
+                          1.73005 62.4918 88.0058,
+                          3.23005 68.3142 87.1393,
+                          1.73005 62.4918 88.0058,
+                          3.23005 62.4918 88.0058,
+                          1.73005 72.488 85.3296,
+                          1.73005 52.4918 88.0049,
+                          1.73005 62.4918 88.0058,
+                          1.73005 72.488 85.3296,
+                          1.73005 62.4918 88.0058,
+                          3.23005 68.3142 87.1393,
+                          1.73005 52.4918 88.0049,
+                          3.23005 52.4918 88.0049,
+                          3.23005 62.4918 88.0058,
+                          1.73005 79.8295 -76.9893,
+                          1.73005 72.5037 -84.3162,
+                          1.73005 52.4918 88.0049,
+                          1.73005 72.488 85.3296,
+                          1.73005 79.8151 78.0042,
+                          1.73005 52.4918 88.0049,
+                          1.73005 79.8295 -76.9893,
+                          3.23005 78.0028 -79.6377,
+                          3.23005 73.638 -83.6101,
+                          1.73005 72.5037 -84.3162,
+                          3.23005 73.638 -83.6101,
+                          3.23005 68.3303 -86.1266,
+                          1.73005 79.8295 -76.9893,
+                          3.23005 73.638 -83.6101,
+                          1.73005 72.5037 -84.3162,
+                          1.73005 72.488 85.3296,
+                          3.23005 68.3142 87.1393,
+                          3.23005 73.6224 84.6237,
+                          1.73005 72.488 85.3296,
+                          3.23005 73.6224 84.6237,
+                          3.23005 77.9879 80.6522,
+                          1.73005 72.488 85.3296,
+                          3.23005 77.9879 80.6522,
+                          1.73005 79.8151 78.0042 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.6 0.6 0.6
+    }
+    Separator {
+        Normal {
+            vector      [ -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1.19458e-16 -0.355517 0.93467,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1.19458e-16 -0.355517 0.93467,
+                          -1.4858e-16 -0.50008 0.865979,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          0.62488 0.780721 7.24428e-05,
+                          0.62488 0.780721 7.24428e-05,
+                          0.62488 0.780721 7.24428e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          0.62488 0.780721 7.24428e-05,
+                          0.62488 0.780721 7.24428e-05,
+                          0.62488 0.780721 7.24428e-05,
+                          0.62488 0.780721 7.24428e-05,
+                          0.62488 0.780721 7.24428e-05,
+                          0.62488 0.780721 7.24428e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          0.62488 0.780721 7.24428e-05,
+                          0.62488 0.780721 7.24428e-05,
+                          0.882652 0.470027 4.36136e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          0.62488 0.780721 7.24428e-05,
+                          0.62488 0.780721 7.24428e-05,
+                          0.62488 0.780721 7.24428e-05,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          0.882652 0.470027 4.36136e-05,
+                          0.882652 0.470027 4.36136e-05,
+                          0.996572 0.0827302 7.67649e-06,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          0.62488 0.780721 7.24428e-05,
+                          0.882652 0.470027 4.36136e-05,
+                          0.882652 0.470027 4.36136e-05,
+                          0.996572 0.0827302 7.67649e-06,
+                          0.996572 0.0827302 7.67649e-06,
+                          0.948074 -0.31805 -2.95117e-05,
+                          0.882652 0.470027 4.36136e-05,
+                          0.996572 0.0827302 7.67649e-06,
+                          0.996572 0.0827302 7.67649e-06,
+                          0.948074 -0.31805 -2.95117e-05,
+                          0.948074 -0.31805 -2.95117e-05,
+                          0.745061 -0.666996 -6.18902e-05,
+                          0.996572 0.0827302 7.67649e-06,
+                          0.948074 -0.31805 -2.95117e-05,
+                          0.948074 -0.31805 -2.95117e-05,
+                          0.745061 -0.666996 -6.18902e-05,
+                          0.745061 -0.666996 -6.18902e-05,
+                          0.420621 -0.907236 -8.41821e-05,
+                          0.948074 -0.31805 -2.95117e-05,
+                          0.745061 -0.666996 -6.18902e-05,
+                          0.745061 -0.666996 -6.18902e-05,
+                          0.420621 -0.907236 -8.41821e-05,
+                          0.420621 -0.907236 -8.41821e-05,
+                          0.420621 -0.907236 -8.41821e-05,
+                          0.745061 -0.666996 -6.18902e-05,
+                          0.420621 -0.907236 -8.41821e-05,
+                          0.420621 -0.907236 -8.41821e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          0.420621 -0.907236 -8.41821e-05,
+                          0.420621 -0.907236 -8.41821e-05,
+                          0.420621 -0.907236 -8.41821e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          1.4858e-16 0.50008 -0.865979,
+                          4.33681e-17 9.27896e-05 -1,
+                          4.33681e-17 9.27896e-05 -1,
+                          1.06853e-16 0.294665 -0.955601,
+                          4.33681e-17 9.27896e-05 -1,
+                          1.4858e-16 0.50008 -0.865979,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          1.57025e-16 0.543267 -0.83956,
+                          1.4858e-16 0.50008 -0.865979,
+                          2.1398e-16 0.866072 -0.49992,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          1.06853e-16 0.294665 -0.955601,
+                          1.4858e-16 0.50008 -0.865979,
+                          1.57025e-16 0.543267 -0.83956,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          2.15771e-16 0.878445 -0.477843,
+                          2.1398e-16 0.866072 -0.49992,
+                          2.22045e-16 1 9.27896e-05,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          2.15771e-16 0.878445 -0.477843,
+                          1.57025e-16 0.543267 -0.83956,
+                          2.1398e-16 0.866072 -0.49992,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.15771e-16 0.878445 -0.477843,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          2.22045e-16 1 9.27896e-05,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -1 5.55112e-17 -9.19878e-17,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.1398e-16 -0.866072 0.49992,
+                          -1.74262e-16 -0.633793 0.773503,
+                          -2.1398e-16 -0.866072 0.49992,
+                          -1.4858e-16 -0.50008 0.865979,
+                          -2.19241e-16 -0.903822 0.427909,
+                          -2.1398e-16 -0.866072 0.49992,
+                          -1.74262e-16 -0.633793 0.773503,
+                          -2.19241e-16 -0.903822 0.427909,
+                          -2.22045e-16 -1 -9.27896e-05,
+                          -2.1398e-16 -0.866072 0.49992,
+                          -1.74262e-16 -0.633793 0.773503,
+                          -1.4858e-16 -0.50008 0.865979,
+                          -1.19458e-16 -0.355517 0.93467,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          -4.33681e-17 -9.27896e-05 1,
+                          0.62488 0.780721 7.24428e-05,
+                          0.62488 0.780721 7.24428e-05,
+                          0.62488 0.780721 7.24428e-05,
+                          0.62488 0.780721 7.24428e-05,
+                          0.62488 0.780721 7.24428e-05,
+                          0.62488 0.780721 7.24428e-05,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17,
+                          1 -5.55112e-17 9.19878e-17 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 3.23005 67.0079 -84.9938,
+                          3.23005 62.5079 -84.9942,
+                          5.23005 62.5079 -84.9942,
+                          3.23005 62.5071 -76.9942,
+                          5.23005 62.5079 -84.9942,
+                          3.23005 62.5079 -84.9942,
+                          82.7313 67.0079 -84.9938,
+                          3.23005 67.0079 -84.9938,
+                          5.23005 62.5079 -84.9942,
+                          59.524 -61.9921 -85.0058,
+                          82.7313 67.0079 -84.9938,
+                          5.23005 62.5079 -84.9942,
+                          5.23005 -61.9921 -85.0058,
+                          59.524 -61.9921 -85.0058,
+                          5.23005 62.5079 -84.9942,
+                          5.23005 -61.9929 -77.0058,
+                          5.23005 -61.9921 -85.0058,
+                          5.23005 62.5079 -84.9942,
+                          5.23005 62.5071 -76.9942,
+                          5.23005 62.5079 -84.9942,
+                          3.23005 62.5071 -76.9942,
+                          5.23005 62.5071 -76.9942,
+                          5.23005 -61.9929 -77.0058,
+                          5.23005 62.5079 -84.9942,
+                          3.23005 -61.9919 -87.0058,
+                          3.23005 62.5079 -84.9942,
+                          3.23005 67.0079 -84.9938,
+                          3.23005 62.5071 -76.9942,
+                          3.23005 62.5079 -84.9942,
+                          3.23005 -61.9919 -87.0058,
+                          77.4024 71.273 -84.2098,
+                          3.23005 67.0079 -84.9938,
+                          82.7313 67.0079 -84.9938,
+                          3.23005 -61.9919 -87.0058,
+                          3.23005 67.0079 -84.9938,
+                          3.23005 67.0081 -86.9938,
+                          3.23005 73.006 -83.3859,
+                          3.23005 67.0081 -86.9938,
+                          3.23005 67.0079 -84.9938,
+                          77.4024 71.273 -84.2098,
+                          3.23005 73.006 -83.3859,
+                          3.23005 67.0079 -84.9938,
+                          125.741 -31.2918 -85.0029,
+                          132.788 26.9428 -84.9975,
+                          82.7313 67.0079 -84.9938,
+                          82.7313 67.0081 -86.9938,
+                          82.7313 67.0079 -84.9938,
+                          132.788 26.9428 -84.9975,
+                          59.524 -61.9921 -85.0058,
+                          125.741 -31.2918 -85.0029,
+                          82.7313 67.0079 -84.9938,
+                          77.5796 71.1313 -86.3723,
+                          82.7313 67.0079 -84.9938,
+                          82.7313 67.0081 -86.9938,
+                          77.5796 71.1313 -86.3723,
+                          77.4024 71.273 -84.2098,
+                          82.7313 67.0079 -84.9938,
+                          136.935 -23.0024 -85.0021,
+                          141.682 16.2227 -84.9985,
+                          132.788 26.9428 -84.9975,
+                          132.788 26.9429 -86.9975,
+                          132.788 26.9428 -84.9975,
+                          141.682 16.2227 -84.9985,
+                          125.741 -31.2918 -85.0029,
+                          136.935 -23.0024 -85.0021,
+                          132.788 26.9428 -84.9975,
+                          82.7313 67.0081 -86.9938,
+                          132.788 26.9428 -84.9975,
+                          132.788 26.9429 -86.9975,
+                          143.938 -10.9668 -85.001,
+                          145.611 2.86417 -84.9997,
+                          141.682 16.2227 -84.9985,
+                          141.682 16.2229 -86.9985,
+                          141.682 16.2227 -84.9985,
+                          145.611 2.86417 -84.9997,
+                          136.935 -23.0024 -85.0021,
+                          143.938 -10.9668 -85.001,
+                          141.682 16.2227 -84.9985,
+                          132.788 26.9429 -86.9975,
+                          141.682 16.2227 -84.9985,
+                          141.682 16.2229 -86.9985,
+                          145.611 2.86435 -86.9997,
+                          145.611 2.86417 -84.9997,
+                          143.938 -10.9668 -85.001,
+                          141.682 16.2229 -86.9985,
+                          145.611 2.86417 -84.9997,
+                          145.611 2.86435 -86.9997,
+                          143.938 -10.9666 -87.001,
+                          143.938 -10.9668 -85.001,
+                          136.935 -23.0024 -85.0021,
+                          145.611 2.86435 -86.9997,
+                          143.938 -10.9668 -85.001,
+                          143.938 -10.9666 -87.001,
+                          136.935 -23.0022 -87.0021,
+                          136.935 -23.0024 -85.0021,
+                          125.741 -31.2918 -85.0029,
+                          143.938 -10.9666 -87.001,
+                          136.935 -23.0024 -85.0021,
+                          136.935 -23.0022 -87.0021,
+                          125.741 -31.2916 -87.0029,
+                          125.741 -31.2918 -85.0029,
+                          59.524 -61.9921 -85.0058,
+                          136.935 -23.0022 -87.0021,
+                          125.741 -31.2918 -85.0029,
+                          125.741 -31.2916 -87.0029,
+                          59.524 -61.9919 -87.0058,
+                          59.524 -61.9921 -85.0058,
+                          5.23005 -61.9921 -85.0058,
+                          125.741 -31.2916 -87.0029,
+                          59.524 -61.9921 -85.0058,
+                          59.524 -61.9919 -87.0058,
+                          3.23005 -61.9919 -87.0058,
+                          59.524 -61.9919 -87.0058,
+                          5.23005 -61.9921 -85.0058,
+                          3.23005 -61.9929 -77.0058,
+                          3.23005 -61.9919 -87.0058,
+                          5.23005 -61.9921 -85.0058,
+                          5.23005 -61.9929 -77.0058,
+                          3.23005 -61.9929 -77.0058,
+                          5.23005 -61.9921 -85.0058,
+                          82.7313 67.0081 -86.9938,
+                          125.741 -31.2916 -87.0029,
+                          59.524 -61.9919 -87.0058,
+                          3.23005 -61.9919 -87.0058,
+                          82.7313 67.0081 -86.9938,
+                          59.524 -61.9919 -87.0058,
+                          132.788 26.9429 -86.9975,
+                          136.935 -23.0022 -87.0021,
+                          125.741 -31.2916 -87.0029,
+                          82.7313 67.0081 -86.9938,
+                          132.788 26.9429 -86.9975,
+                          125.741 -31.2916 -87.0029,
+                          141.682 16.2229 -86.9985,
+                          143.938 -10.9666 -87.001,
+                          136.935 -23.0022 -87.0021,
+                          132.788 26.9429 -86.9975,
+                          141.682 16.2229 -86.9985,
+                          136.935 -23.0022 -87.0021,
+                          141.682 16.2229 -86.9985,
+                          145.611 2.86435 -86.9997,
+                          143.938 -10.9666 -87.001,
+                          3.23005 -61.9919 -87.0058,
+                          3.23005 67.0081 -86.9938,
+                          82.7313 67.0081 -86.9938,
+                          3.23005 74.0059 -85.1179,
+                          82.7313 67.0081 -86.9938,
+                          3.23005 67.0081 -86.9938,
+                          77.5796 71.1313 -86.3723,
+                          82.7313 67.0081 -86.9938,
+                          3.23005 74.0059 -85.1179,
+                          3.23005 73.006 -83.3859,
+                          3.23005 74.0059 -85.1179,
+                          3.23005 67.0081 -86.9938,
+                          3.23005 -61.9929 -77.0058,
+                          3.23005 62.5071 -76.9942,
+                          3.23005 -61.9919 -87.0058,
+                          3.23005 77.4 -78.9911,
+                          3.23005 79.1322 -79.9906,
+                          3.23005 74.0059 -85.1179,
+                          73.23 74.6125 -84.7476,
+                          3.23005 74.0059 -85.1179,
+                          3.23005 79.1322 -79.9906,
+                          3.23005 73.006 -83.3859,
+                          3.23005 77.4 -78.9911,
+                          3.23005 74.0059 -85.1179,
+                          77.5796 71.1313 -86.3723,
+                          3.23005 74.0059 -85.1179,
+                          73.23 74.6125 -84.7476,
+                          3.23005 81.0062 -66.9925,
+                          3.23005 81.0068 -72.9925,
+                          3.23005 79.1322 -79.9906,
+                          73.23 79.305 -79.6836,
+                          3.23005 79.1322 -79.9906,
+                          3.23005 81.0068 -72.9925,
+                          3.23005 79.0068 -72.9927,
+                          3.23005 81.0062 -66.9925,
+                          3.23005 79.1322 -79.9906,
+                          3.23005 77.4 -78.9911,
+                          3.23005 79.0068 -72.9927,
+                          3.23005 79.1322 -79.9906,
+                          73.23 79.305 -79.6836,
+                          73.23 74.6125 -84.7476,
+                          3.23005 79.1322 -79.9906,
+                          73.23 81.0062 -66.9925,
+                          3.23005 81.0068 -72.9925,
+                          3.23005 81.0062 -66.9925,
+                          73.23 81.0068 -72.9925,
+                          73.23 79.305 -79.6836,
+                          3.23005 81.0068 -72.9925,
+                          73.23 81.0062 -66.9925,
+                          73.23 81.0068 -72.9925,
+                          3.23005 81.0068 -72.9925,
+                          3.23005 79.0068 -72.9927,
+                          3.23005 79.0062 -66.9927,
+                          3.23005 81.0062 -66.9925,
+                          73.23 79.0062 -66.9927,
+                          3.23005 81.0062 -66.9925,
+                          3.23005 79.0062 -66.9927,
+                          73.23 79.0062 -66.9927,
+                          73.23 81.0062 -66.9925,
+                          3.23005 81.0062 -66.9925,
+                          73.23 79.0068 -72.9927,
+                          3.23005 79.0062 -66.9927,
+                          3.23005 79.0068 -72.9927,
+                          73.23 79.0068 -72.9927,
+                          73.23 79.0062 -66.9927,
+                          3.23005 79.0062 -66.9927,
+                          73.23 79.0068 -72.9927,
+                          3.23005 79.0068 -72.9927,
+                          3.23005 77.4 -78.9911,
+                          73.23 74.6123 -82.2758,
+                          3.23005 77.4 -78.9911,
+                          3.23005 73.006 -83.3859,
+                          73.23 77.8524 -78.1286,
+                          3.23005 77.4 -78.9911,
+                          73.23 74.6123 -82.2758,
+                          73.23 77.8524 -78.1286,
+                          73.23 79.0068 -72.9927,
+                          3.23005 77.4 -78.9911,
+                          73.23 74.6123 -82.2758,
+                          3.23005 73.006 -83.3859,
+                          77.4024 71.273 -84.2098,
+                          5.23005 62.5071 -76.9942,
+                          3.23005 62.5071 -76.9942,
+                          3.23005 -61.9929 -77.0058,
+                          5.23005 62.5071 -76.9942,
+                          3.23005 -61.9929 -77.0058,
+                          5.23005 -61.9929 -77.0058,
+                          73.23 74.6125 -84.7476,
+                          73.23 74.6123 -82.2758,
+                          77.4024 71.273 -84.2098,
+                          77.5796 71.1313 -86.3723,
+                          73.23 74.6125 -84.7476,
+                          77.4024 71.273 -84.2098,
+                          73.23 79.305 -79.6836,
+                          73.23 74.6123 -82.2758,
+                          73.23 74.6125 -84.7476,
+                          73.23 77.8524 -78.1286,
+                          73.23 74.6123 -82.2758,
+                          73.23 79.305 -79.6836,
+                          73.23 77.8524 -78.1286,
+                          73.23 79.305 -79.6836,
+                          73.23 81.0068 -72.9925,
+                          73.23 79.0068 -72.9927,
+                          73.23 81.0068 -72.9925,
+                          73.23 81.0062 -66.9925,
+                          73.23 77.8524 -78.1286,
+                          73.23 81.0068 -72.9925,
+                          73.23 79.0068 -72.9927,
+                          73.23 79.0068 -72.9927,
+                          73.23 81.0062 -66.9925,
+                          73.23 79.0062 -66.9927 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/left_arm/shoulder_link_l.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/left_arm/shoulder_link_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..6cc3ac8d7ada78879d359eeac494d785d81e8482
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/left_arm/shoulder_link_l.iv
@@ -0,0 +1,1225 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.386933 0.500748 0.62
+    }
+    Separator {
+        Normal {
+            vector      [ 1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 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,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          0.576683 7.0621e-17 -0.816968,
+                          0.576683 7.0621e-17 -0.816968,
+                          0.576683 7.0621e-17 -0.816968,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          0.576683 7.0621e-17 -0.816968,
+                          0.576683 7.0621e-17 -0.816968,
+                          0.576683 7.0621e-17 -0.816968,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 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,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1 3.44505e-16 0,
+                          1 1.22461e-16 0,
+                          0.5 -0.866025 0,
+                          0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          1 3.67382e-16 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.5 0.866025 0,
+                          1 3.67382e-16 0,
+                          1 3.67382e-16 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          1 3.44505e-16 0,
+                          0.5 -0.866025 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -1 -2.44921e-16 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -1 -2.44921e-16 0,
+                          -1 -2.44921e-16 0,
+                          -0.5 0.866025 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.5 -0.866025 0,
+                          -1 -2.44921e-16 0,
+                          -1 -2.44921e-16 0,
+                          -0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          -1 -2.44921e-16 0,
+                          -0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          0.671507 0.740998 0,
+                          0.671507 0.740998 0,
+                          0.671507 0.740998 0,
+                          0.671507 0.740998 0,
+                          0.671507 0.740998 0,
+                          -0.0327655 0.999463 0,
+                          0.671507 0.740998 0,
+                          0.671507 0.740998 0,
+                          0.671507 0.740998 0,
+                          -0.0327655 0.999463 0,
+                          -0.0327655 0.999463 0,
+                          -0.718598 0.695426 0,
+                          0.671507 0.740998 0,
+                          -0.0327655 0.999463 0,
+                          -0.0327655 0.999463 0,
+                          -0.718598 0.695426 0,
+                          -0.718598 0.695426 0,
+                          -1 -3.06152e-16 0,
+                          -0.0327655 0.999463 0,
+                          -0.718598 0.695426 0,
+                          -0.718598 0.695426 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -0.718598 0.695426 0,
+                          -1 -3.06152e-16 0,
+                          -1 -3.06152e-16 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 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,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          0.707107 0.707107 0,
+                          1 -1.22461e-16 0,
+                          1 -1.22461e-16 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.707107 0.707107 0,
+                          0.707107 0.707107 0,
+                          1 -1.22461e-16 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,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 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,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -0.5 -0.866025 0,
+                          -0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          -1 1.22461e-16 0,
+                          -0.5 0.866025 0,
+                          -1 1.22461e-16 0,
+                          -1 1.22461e-16 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -1 -1.22461e-16 0,
+                          -0.5 -0.866025 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          1 0 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          1 0 0,
+                          1 0 0,
+                          0.5 0.866025 0,
+                          0.5 -0.866025 0,
+                          1 0 0,
+                          1 0 0,
+                          0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          1 0 0,
+                          0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -1 2.44921e-16 0,
+                          -1 2.44921e-16 0,
+                          -0.707107 0.707107 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.707107 0.707107 0,
+                          -0.707107 0.707107 0,
+                          1.83691e-16 1 0,
+                          -0.707107 0.707107 0,
+                          -1 2.44921e-16 0,
+                          -0.707107 0.707107 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          0.707107 0.707107 0,
+                          -0.707107 0.707107 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          0.707107 0.707107 0,
+                          0.707107 0.707107 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 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,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 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,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.866025 0 0.5,
+                          -0.866025 0 -0.5,
+                          -0.866025 0 -0.5,
+                          -1 0 0,
+                          -0.866025 0 -0.5,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.866025 0 0.5,
+                          -0.866025 0 0.5,
+                          -0.5 0 0.866025,
+                          -0.866025 0 0.5,
+                          -1 0 0,
+                          -0.866025 0 0.5,
+                          -0.5 0 0.866025,
+                          -0.5 0 0.866025,
+                          -6.12303e-17 0 1,
+                          -0.866025 0 0.5,
+                          -0.5 0 0.866025,
+                          -0.5 0 0.866025,
+                          3.82859e-16 0 1,
+                          -6.12303e-17 0 1,
+                          0.5 0 0.866025,
+                          -0.5 0 0.866025,
+                          -6.12303e-17 0 1,
+                          3.82859e-16 0 1,
+                          0.5 0 0.866025,
+                          0.5 0 0.866025,
+                          0.866025 0 0.5,
+                          3.82859e-16 0 1,
+                          0.5 0 0.866025,
+                          0.5 0 0.866025,
+                          0.866025 0 0.5,
+                          0.866025 0 0.5,
+                          1 0 1.22461e-16,
+                          0.5 0 0.866025,
+                          0.866025 0 0.5,
+                          0.866025 0 0.5,
+                          1 0 -1.22461e-16,
+                          1 0 -1.22461e-16,
+                          0.866025 0 -0.5,
+                          0.866025 0 0.5,
+                          1 0 1.22461e-16,
+                          1 0 1.22461e-16,
+                          0.866025 0 -0.5,
+                          0.866025 0 -0.5,
+                          0.5 0 -0.866025,
+                          1 0 -1.22461e-16,
+                          0.866025 0 -0.5,
+                          0.866025 0 -0.5,
+                          0.5 0 -0.866025,
+                          0.5 0 -0.866025,
+                          -6.12303e-17 0 -1,
+                          0.866025 0 -0.5,
+                          0.5 0 -0.866025,
+                          0.5 0 -0.866025,
+                          1.60814e-16 0 -1,
+                          -6.12303e-17 0 -1,
+                          -0.5 0 -0.866025,
+                          0.5 0 -0.866025,
+                          -6.12303e-17 0 -1,
+                          1.60814e-16 0 -1,
+                          -0.5 0 -0.866025,
+                          -0.5 0 -0.866025,
+                          -0.866025 0 -0.5,
+                          1.60814e-16 0 -1,
+                          -0.5 0 -0.866025,
+                          -0.5 0 -0.866025,
+                          -0.5 0 -0.866025,
+                          -0.866025 0 -0.5,
+                          -0.866025 0 -0.5,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 30 -38 50,
+                          -30 -38 28,
+                          30 -38 28,
+                          30 -75 28,
+                          30 -38 28,
+                          -30 -38 28,
+                          30 -32 -18,
+                          30 -38 50,
+                          30 -38 28,
+                          30 -32 -18,
+                          30 -38 28,
+                          30 -38 -16,
+                          30 -75 28,
+                          30 -38 -16,
+                          30 -38 28,
+                          30 -38 50,
+                          -30 -38 50,
+                          -30 -38 28,
+                          -30 -32 28,
+                          -30 -38 28,
+                          -30 -38 50,
+                          -40 -32 28,
+                          30 -75 28,
+                          -30 -38 28,
+                          -40 -32 28,
+                          -30 -38 28,
+                          -30 -32 28,
+                          30 7.10543e-15 50,
+                          -30 -38 50,
+                          30 -38 50,
+                          5.5 -9.52628 50,
+                          -30 -38 50,
+                          30 7.10543e-15 50,
+                          -5.5 -9.52628 50,
+                          -11 0 50,
+                          -30 -38 50,
+                          -30 -7.10543e-15 50,
+                          -30 -38 50,
+                          -11 0 50,
+                          5.5 -9.52628 50,
+                          -5.5 -9.52628 50,
+                          -30 -38 50,
+                          -30 -7.10543e-15 44,
+                          -30 -38 50,
+                          -30 -7.10543e-15 50,
+                          -30 -32 44,
+                          -30 -32 28,
+                          -30 -38 50,
+                          -30 -7.10543e-15 44,
+                          -30 -32 44,
+                          -30 -38 50,
+                          30 -32 44,
+                          30 -38 50,
+                          30 -32 -18,
+                          30 7.10543e-15 44,
+                          30 7.10543e-15 50,
+                          30 -38 50,
+                          30 -32 44,
+                          30 7.10543e-15 44,
+                          30 -38 50,
+                          -30 -38 -51,
+                          13 -38 -28,
+                          -30 -38 -28,
+                          -40 -75 -28,
+                          -30 -38 -28,
+                          13 -38 -28,
+                          -30 -32 -45,
+                          -30 -38 -51,
+                          -30 -38 -28,
+                          -30 -32 -28,
+                          -30 -32 -45,
+                          -30 -38 -28,
+                          -40 -75 -28,
+                          -30 -32 -28,
+                          -30 -38 -28,
+                          30 -38 -18,
+                          30 -38 -16,
+                          13 -38 -28,
+                          30 -75 -16,
+                          13 -38 -28,
+                          30 -38 -16,
+                          52.4 -38 -18,
+                          30 -38 -18,
+                          13 -38 -28,
+                          -30 -38 -51,
+                          52.4 -38 -18,
+                          13 -38 -28,
+                          13 -75 -28,
+                          13 -38 -28,
+                          30 -75 -16,
+                          -40 -75 -28,
+                          13 -38 -28,
+                          13 -75 -28,
+                          30 -32 -18,
+                          30 -38 -16,
+                          30 -38 -18,
+                          30 -75 28,
+                          30 -75 -16,
+                          30 -38 -16,
+                          30 -32 -18,
+                          30 -38 -18,
+                          52.4 -38 -18,
+                          -30 -38 -51,
+                          52.4 -38 -51,
+                          52.4 -38 -18,
+                          52.4 -32 -18,
+                          52.4 -38 -18,
+                          52.4 -38 -51,
+                          30 -32 -18,
+                          52.4 -38 -18,
+                          52.4 -32 -18,
+                          52.4 -7 -51,
+                          52.4 -38 -51,
+                          -30 -38 -51,
+                          52.4 -7 -45,
+                          52.4 -38 -51,
+                          52.4 -7 -51,
+                          52.4 -32 -45,
+                          52.4 -32 -18,
+                          52.4 -38 -51,
+                          52.4 -7 -45,
+                          52.4 -32 -45,
+                          52.4 -38 -51,
+                          -7.99874 -13.8567 -51,
+                          -30 -38 -51,
+                          -16 0 -51,
+                          -21.5565 20.8637 -51,
+                          -16 0 -51,
+                          -30 -38 -51,
+                          -7.99874 -13.8567 -51,
+                          7.99874 -13.8567 -51,
+                          -30 -38 -51,
+                          52.4 -7 -51,
+                          -30 -38 -51,
+                          7.99874 -13.8567 -51,
+                          -30 -7.10543e-15 -51,
+                          -21.5565 20.8637 -51,
+                          -30 -38 -51,
+                          -30 -32 -45,
+                          -30 -7.10543e-15 -51,
+                          -30 -38 -51,
+                          -0.984611 29.9834 -51,
+                          -7.99874 13.8567 -51,
+                          -16 0 -51,
+                          -16 0 -45,
+                          -16 0 -51,
+                          -7.99874 13.8567 -51,
+                          -7.99874 -13.8567 -45,
+                          -7.99874 -13.8567 -51,
+                          -16 0 -51,
+                          -21.5565 20.8637 -51,
+                          -0.984611 29.9834 -51,
+                          -16 0 -51,
+                          -7.99874 -13.8567 -45,
+                          -16 0 -51,
+                          -16 0 -45,
+                          -0.984611 29.9834 -51,
+                          7.99874 13.8567 -51,
+                          -7.99874 13.8567 -51,
+                          -7.99874 13.8567 -45,
+                          -7.99874 13.8567 -51,
+                          7.99874 13.8567 -51,
+                          -7.99874 13.8567 -45,
+                          -16 0 -45,
+                          -7.99874 13.8567 -51,
+                          20.1452 22.2299 -51,
+                          16 0 -51,
+                          7.99874 13.8567 -51,
+                          7.99874 13.8567 -45,
+                          7.99874 13.8567 -51,
+                          16 0 -51,
+                          -0.984611 29.9834 -51,
+                          20.1452 22.2299 -51,
+                          7.99874 13.8567 -51,
+                          -7.99874 13.8567 -45,
+                          7.99874 13.8567 -51,
+                          7.99874 13.8567 -45,
+                          52.4 -7 -51,
+                          7.99874 -13.8567 -51,
+                          16 0 -51,
+                          16 0 -45,
+                          16 0 -51,
+                          7.99874 -13.8567 -51,
+                          20.1452 22.2299 -51,
+                          52.4 -7 -51,
+                          16 0 -51,
+                          7.99874 13.8567 -45,
+                          16 0 -51,
+                          16 0 -45,
+                          7.99874 -13.8567 -45,
+                          7.99874 -13.8567 -51,
+                          -7.99874 -13.8567 -51,
+                          16 0 -45,
+                          7.99874 -13.8567 -51,
+                          7.99874 -13.8567 -45,
+                          7.99874 -13.8567 -45,
+                          -7.99874 -13.8567 -51,
+                          -7.99874 -13.8567 -45,
+                          52.4 -7 -45,
+                          52.4 -7 -51,
+                          20.1452 22.2299 -51,
+                          20.1452 22.2299 -45,
+                          20.1452 22.2299 -51,
+                          -0.984611 29.9834 -51,
+                          20.1452 22.2299 -45,
+                          52.4 -7 -45,
+                          20.1452 22.2299 -51,
+                          -0.984611 29.9834 -45,
+                          -0.984611 29.9834 -51,
+                          -21.5565 20.8637 -51,
+                          20.1452 22.2299 -45,
+                          -0.984611 29.9834 -51,
+                          -0.984611 29.9834 -45,
+                          -21.5565 20.8637 -45,
+                          -21.5565 20.8637 -51,
+                          -30 -7.10543e-15 -51,
+                          -0.984611 29.9834 -45,
+                          -21.5565 20.8637 -51,
+                          -21.5565 20.8637 -45,
+                          -30 -32 -45,
+                          -30 -7.10543e-15 -45,
+                          -30 -7.10543e-15 -51,
+                          -21.5565 20.8637 -45,
+                          -30 -7.10543e-15 -51,
+                          -30 -7.10543e-15 -45,
+                          -30 -32 -45,
+                          52.4 -32 -18,
+                          52.4 -32 -45,
+                          -30 -32 -45,
+                          30 -32 -18,
+                          52.4 -32 -18,
+                          20.1452 22.2299 -45,
+                          52.4 -32 -45,
+                          52.4 -7 -45,
+                          -7.99874 -13.8567 -45,
+                          -30 -32 -45,
+                          52.4 -32 -45,
+                          7.99874 -13.8567 -45,
+                          -7.99874 -13.8567 -45,
+                          52.4 -32 -45,
+                          16 0 -45,
+                          7.99874 -13.8567 -45,
+                          52.4 -32 -45,
+                          20.1452 22.2299 -45,
+                          16 0 -45,
+                          52.4 -32 -45,
+                          23.5 -32 0,
+                          30 -32 44,
+                          30 -32 -18,
+                          11.75 -32 -20.3516,
+                          30 -32 -18,
+                          -30 -32 -45,
+                          20.3516 -32 -11.75,
+                          23.5 -32 0,
+                          30 -32 -18,
+                          11.75 -32 -20.3516,
+                          20.3516 -32 -11.75,
+                          30 -32 -18,
+                          20.3516 -75 11.75,
+                          30 -75 -16,
+                          30 -75 28,
+                          20.3516 -75 11.75,
+                          23.5 -75 0,
+                          30 -75 -16,
+                          20.3516 -75 -11.75,
+                          30 -75 -16,
+                          23.5 -75 0,
+                          13 -75 -28,
+                          30 -75 -16,
+                          20.3516 -75 -11.75,
+                          -40 -75 28,
+                          30 -75 28,
+                          -40 -32 28,
+                          11.75 -75 20.3516,
+                          20.3516 -75 11.75,
+                          30 -75 28,
+                          1.37303e-16 -75 23.5,
+                          11.75 -75 20.3516,
+                          30 -75 28,
+                          -40 -75 28,
+                          1.37303e-16 -75 23.5,
+                          30 -75 28,
+                          21.2115 21.2145 44,
+                          30 7.10543e-15 50,
+                          30 7.10543e-15 44,
+                          5.5 -9.52628 50,
+                          30 7.10543e-15 50,
+                          11 0 50,
+                          21.2115 21.2145 50,
+                          11 0 50,
+                          30 7.10543e-15 50,
+                          21.2115 21.2145 44,
+                          21.2115 21.2145 50,
+                          30 7.10543e-15 50,
+                          11 0 44,
+                          30 7.10543e-15 44,
+                          30 -32 44,
+                          5.5 9.52628 44,
+                          30 7.10543e-15 44,
+                          11 0 44,
+                          -21.2115 21.2145 44,
+                          30 7.10543e-15 44,
+                          5.5 9.52628 44,
+                          -21.2115 21.2145 44,
+                          21.2115 21.2145 44,
+                          30 7.10543e-15 44,
+                          -30 -32 44,
+                          30 -32 44,
+                          -30 -32 28,
+                          -11.75 -32 20.3516,
+                          -30 -32 28,
+                          30 -32 44,
+                          -30 -7.10543e-15 44,
+                          30 -32 44,
+                          -30 -32 44,
+                          -5.5 -9.52628 44,
+                          30 -32 44,
+                          -30 -7.10543e-15 44,
+                          5.5 -9.52628 44,
+                          11 0 44,
+                          30 -32 44,
+                          -5.5 -9.52628 44,
+                          5.5 -9.52628 44,
+                          30 -32 44,
+                          20.3516 -32 11.75,
+                          30 -32 44,
+                          23.5 -32 0,
+                          1.37303e-16 -32 23.5,
+                          -11.75 -32 20.3516,
+                          30 -32 44,
+                          11.75 -32 20.3516,
+                          1.37303e-16 -32 23.5,
+                          30 -32 44,
+                          20.3516 -32 11.75,
+                          11.75 -32 20.3516,
+                          30 -32 44,
+                          21.2115 21.2145 50,
+                          5.5 9.52628 50,
+                          11 0 50,
+                          11 0 44,
+                          11 0 50,
+                          5.5 9.52628 50,
+                          5.5 -9.52628 44,
+                          5.5 -9.52628 50,
+                          11 0 50,
+                          5.5 -9.52628 44,
+                          11 0 50,
+                          11 0 44,
+                          21.2115 21.2145 50,
+                          -5.5 9.52628 50,
+                          5.5 9.52628 50,
+                          5.5 9.52628 44,
+                          5.5 9.52628 50,
+                          -5.5 9.52628 50,
+                          5.5 9.52628 44,
+                          11 0 44,
+                          5.5 9.52628 50,
+                          -30 -7.10543e-15 50,
+                          -11 0 50,
+                          -5.5 9.52628 50,
+                          -5.5 9.52628 44,
+                          -5.5 9.52628 50,
+                          -11 0 50,
+                          21.2115 21.2145 50,
+                          -30 -7.10543e-15 50,
+                          -5.5 9.52628 50,
+                          5.5 9.52628 44,
+                          -5.5 9.52628 50,
+                          -5.5 9.52628 44,
+                          -11 0 44,
+                          -11 0 50,
+                          -5.5 -9.52628 50,
+                          -5.5 9.52628 44,
+                          -11 0 50,
+                          -11 0 44,
+                          -5.5 -9.52628 44,
+                          -5.5 -9.52628 50,
+                          5.5 -9.52628 50,
+                          -11 0 44,
+                          -5.5 -9.52628 50,
+                          -5.5 -9.52628 44,
+                          -5.5 -9.52628 44,
+                          5.5 -9.52628 50,
+                          5.5 -9.52628 44,
+                          21.2115 21.2145 50,
+                          -21.2115 21.2145 50,
+                          -30 -7.10543e-15 50,
+                          -30 -7.10543e-15 44,
+                          -30 -7.10543e-15 50,
+                          -21.2115 21.2145 50,
+                          21.2115 21.2145 50,
+                          3.43167e-15 29.9995 50,
+                          -21.2115 21.2145 50,
+                          -21.2115 21.2145 44,
+                          -21.2115 21.2145 50,
+                          3.43167e-15 29.9995 50,
+                          -21.2115 21.2145 44,
+                          -30 -7.10543e-15 44,
+                          -21.2115 21.2145 50,
+                          3.43167e-15 29.9995 44,
+                          3.43167e-15 29.9995 50,
+                          21.2115 21.2145 50,
+                          -21.2115 21.2145 44,
+                          3.43167e-15 29.9995 50,
+                          3.43167e-15 29.9995 44,
+                          3.43167e-15 29.9995 44,
+                          21.2115 21.2145 50,
+                          21.2115 21.2145 44,
+                          -40 -32 -28,
+                          -30 -32 28,
+                          -30 -32 -28,
+                          -23.5 -32 0,
+                          -30 -32 -28,
+                          -30 -32 28,
+                          -40 -32 -28,
+                          -40 -32 28,
+                          -30 -32 28,
+                          -20.3516 -32 11.75,
+                          -23.5 -32 0,
+                          -30 -32 28,
+                          -11.75 -32 20.3516,
+                          -20.3516 -32 11.75,
+                          -30 -32 28,
+                          -11 0 44,
+                          -5.5 -9.52628 44,
+                          -30 -7.10543e-15 44,
+                          -21.2115 21.2145 44,
+                          -11 0 44,
+                          -30 -7.10543e-15 44,
+                          -7.99874 -13.8567 -45,
+                          -30 -7.10543e-15 -45,
+                          -30 -32 -45,
+                          -7.99874 -13.8567 -45,
+                          -16 0 -45,
+                          -30 -7.10543e-15 -45,
+                          -21.5565 20.8637 -45,
+                          -30 -7.10543e-15 -45,
+                          -16 0 -45,
+                          -23.5 -32 0,
+                          -30 -32 -45,
+                          -30 -32 -28,
+                          1.05734e-14 -32 -23.5,
+                          11.75 -32 -20.3516,
+                          -30 -32 -45,
+                          -11.75 -32 -20.3516,
+                          1.05734e-14 -32 -23.5,
+                          -30 -32 -45,
+                          -20.3516 -32 -11.75,
+                          -11.75 -32 -20.3516,
+                          -30 -32 -45,
+                          -23.5 -32 0,
+                          -20.3516 -32 -11.75,
+                          -30 -32 -45,
+                          -40 -75 -28,
+                          -40 -32 -28,
+                          -30 -32 -28,
+                          -21.5565 20.8637 -45,
+                          -16 0 -45,
+                          -7.99874 13.8567 -45,
+                          -0.984611 29.9834 -45,
+                          7.99874 13.8567 -45,
+                          16 0 -45,
+                          20.1452 22.2299 -45,
+                          -0.984611 29.9834 -45,
+                          16 0 -45,
+                          -0.984611 29.9834 -45,
+                          -7.99874 13.8567 -45,
+                          7.99874 13.8567 -45,
+                          -0.984611 29.9834 -45,
+                          -21.5565 20.8637 -45,
+                          -7.99874 13.8567 -45,
+                          -21.2115 21.2145 44,
+                          -5.5 9.52628 44,
+                          -11 0 44,
+                          -21.2115 21.2145 44,
+                          5.5 9.52628 44,
+                          -5.5 9.52628 44,
+                          -21.2115 21.2145 44,
+                          3.43167e-15 29.9995 44,
+                          21.2115 21.2145 44,
+                          -40 -75 28,
+                          -40 -32 28,
+                          -40 -32 -28,
+                          -40 -75 28,
+                          -40 -32 -28,
+                          -40 -75 -28,
+                          23.5 -75 0,
+                          23.5 -32 0,
+                          20.3516 -32 -11.75,
+                          20.3516 -75 11.75,
+                          20.3516 -32 11.75,
+                          23.5 -32 0,
+                          20.3516 -75 11.75,
+                          23.5 -32 0,
+                          23.5 -75 0,
+                          20.3516 -75 -11.75,
+                          20.3516 -32 -11.75,
+                          11.75 -32 -20.3516,
+                          20.3516 -75 -11.75,
+                          23.5 -75 0,
+                          20.3516 -32 -11.75,
+                          11.75 -75 -20.3516,
+                          11.75 -32 -20.3516,
+                          1.05734e-14 -32 -23.5,
+                          20.3516 -75 -11.75,
+                          11.75 -32 -20.3516,
+                          11.75 -75 -20.3516,
+                          -5.08075e-15 -75 -23.5,
+                          1.05734e-14 -32 -23.5,
+                          -11.75 -32 -20.3516,
+                          11.75 -75 -20.3516,
+                          1.05734e-14 -32 -23.5,
+                          -5.08075e-15 -75 -23.5,
+                          -11.75 -75 -20.3516,
+                          -11.75 -32 -20.3516,
+                          -20.3516 -32 -11.75,
+                          -5.08075e-15 -75 -23.5,
+                          -11.75 -32 -20.3516,
+                          -11.75 -75 -20.3516,
+                          -20.3516 -75 -11.75,
+                          -20.3516 -32 -11.75,
+                          -23.5 -32 0,
+                          -11.75 -75 -20.3516,
+                          -20.3516 -32 -11.75,
+                          -20.3516 -75 -11.75,
+                          -23.5 -75 6.70532e-30,
+                          -23.5 -32 0,
+                          -20.3516 -32 11.75,
+                          -20.3516 -75 -11.75,
+                          -23.5 -32 0,
+                          -23.5 -75 6.70532e-30,
+                          -20.3516 -75 11.75,
+                          -20.3516 -32 11.75,
+                          -11.75 -32 20.3516,
+                          -23.5 -75 6.70532e-30,
+                          -20.3516 -32 11.75,
+                          -20.3516 -75 11.75,
+                          -11.75 -75 20.3516,
+                          -11.75 -32 20.3516,
+                          1.37303e-16 -32 23.5,
+                          -20.3516 -75 11.75,
+                          -11.75 -32 20.3516,
+                          -11.75 -75 20.3516,
+                          1.37303e-16 -75 23.5,
+                          1.37303e-16 -32 23.5,
+                          11.75 -32 20.3516,
+                          -11.75 -75 20.3516,
+                          1.37303e-16 -32 23.5,
+                          1.37303e-16 -75 23.5,
+                          11.75 -75 20.3516,
+                          11.75 -32 20.3516,
+                          20.3516 -32 11.75,
+                          1.37303e-16 -75 23.5,
+                          11.75 -32 20.3516,
+                          11.75 -75 20.3516,
+                          11.75 -75 20.3516,
+                          20.3516 -32 11.75,
+                          20.3516 -75 11.75,
+                          -40 -75 28,
+                          -11.75 -75 20.3516,
+                          1.37303e-16 -75 23.5,
+                          -40 -75 28,
+                          -20.3516 -75 11.75,
+                          -11.75 -75 20.3516,
+                          -40 -75 28,
+                          -23.5 -75 6.70532e-30,
+                          -20.3516 -75 11.75,
+                          -40 -75 28,
+                          -20.3516 -75 -11.75,
+                          -23.5 -75 6.70532e-30,
+                          -40 -75 -28,
+                          -11.75 -75 -20.3516,
+                          -20.3516 -75 -11.75,
+                          -40 -75 28,
+                          -40 -75 -28,
+                          -20.3516 -75 -11.75,
+                          13 -75 -28,
+                          -5.08075e-15 -75 -23.5,
+                          -11.75 -75 -20.3516,
+                          -40 -75 -28,
+                          13 -75 -28,
+                          -11.75 -75 -20.3516,
+                          13 -75 -28,
+                          11.75 -75 -20.3516,
+                          -5.08075e-15 -75 -23.5,
+                          13 -75 -28,
+                          20.3516 -75 -11.75,
+                          11.75 -75 -20.3516 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/left_arm/underarm_l.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/left_arm/underarm_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..fa83a284a9ce6a6e2fe0def5fe2b23ea4ecba51b
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/left_arm/underarm_l.iv
@@ -0,0 +1,553 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    1 1 1
+    }
+    Separator {
+        Normal {
+            vector      [ -8.61283e-17 -2.22045e-16 1,
+                          -8.61283e-17 -2.22045e-16 1,
+                          -8.61283e-17 -2.22045e-16 1,
+                          1 -2.59314e-16 8.61283e-17,
+                          1 -2.59314e-16 8.61283e-17,
+                          0.707107 -0.707107 -2.53117e-16,
+                          -8.61283e-17 -2.22045e-16 1,
+                          -8.61283e-17 -2.22045e-16 1,
+                          -8.61283e-17 -2.22045e-16 1,
+                          -8.61283e-17 -2.22045e-16 1,
+                          -8.61283e-17 -2.22045e-16 1,
+                          -8.61283e-17 -2.22045e-16 1,
+                          0.707107 0.707107 3.7492e-16,
+                          0.707107 0.707107 3.7492e-16,
+                          1 -1.43925e-17 8.61283e-17,
+                          0.707107 0.707107 3.7492e-16,
+                          1 -1.43925e-17 8.61283e-17,
+                          1 -1.43925e-17 8.61283e-17,
+                          -8.61283e-17 -2.22045e-16 1,
+                          -8.61283e-17 -2.22045e-16 1,
+                          -8.61283e-17 -2.22045e-16 1,
+                          0.707107 -0.707107 -2.53117e-16,
+                          0.707107 -0.707107 -2.53117e-16,
+                          -1.98083e-16 -1 -4.44089e-16,
+                          0.707107 -0.707107 -2.53117e-16,
+                          1 -2.59314e-16 8.61283e-17,
+                          0.707107 -0.707107 -2.53117e-16,
+                          -1.98083e-16 -1 -4.44089e-16,
+                          -1.98083e-16 -1 -4.44089e-16,
+                          -0.707107 -0.707107 -3.7492e-16,
+                          0.707107 -0.707107 -2.53117e-16,
+                          -1.98083e-16 -1 -4.44089e-16,
+                          -1.98083e-16 -1 -4.44089e-16,
+                          -0.707107 -0.707107 -3.7492e-16,
+                          -0.707107 -0.707107 -3.7492e-16,
+                          -1 1.36853e-16 -8.61283e-17,
+                          -1.98083e-16 -1 -4.44089e-16,
+                          -0.707107 -0.707107 -3.7492e-16,
+                          -0.707107 -0.707107 -3.7492e-16,
+                          -8.61283e-17 -2.22045e-16 1,
+                          -8.61283e-17 -2.22045e-16 1,
+                          -8.61283e-17 -2.22045e-16 1,
+                          -1 1.36853e-16 -8.61283e-17,
+                          -1 1.36853e-16 -8.61283e-17,
+                          -0.707107 0.707107 2.53117e-16,
+                          -0.707107 -0.707107 -3.7492e-16,
+                          -1 1.36853e-16 -8.61283e-17,
+                          -1 1.36853e-16 -8.61283e-17,
+                          -8.61283e-17 -2.22045e-16 1,
+                          -8.61283e-17 -2.22045e-16 1,
+                          -8.61283e-17 -2.22045e-16 1,
+                          -0.707107 0.707107 2.53117e-16,
+                          -0.707107 0.707107 2.53117e-16,
+                          7.56228e-17 1 4.44089e-16,
+                          -1 1.36853e-16 -8.61283e-17,
+                          -0.707107 0.707107 2.53117e-16,
+                          -0.707107 0.707107 2.53117e-16,
+                          7.56228e-17 1 4.44089e-16,
+                          7.56228e-17 1 4.44089e-16,
+                          0.707107 0.707107 3.7492e-16,
+                          -0.707107 0.707107 2.53117e-16,
+                          7.56228e-17 1 4.44089e-16,
+                          7.56228e-17 1 4.44089e-16,
+                          7.56228e-17 1 4.44089e-16,
+                          0.707107 0.707107 3.7492e-16,
+                          0.707107 0.707107 3.7492e-16,
+                          8.61283e-17 2.22045e-16 -1,
+                          8.61283e-17 2.22045e-16 -1,
+                          8.61283e-17 2.22045e-16 -1,
+                          8.61283e-17 2.22045e-16 -1,
+                          8.61283e-17 2.22045e-16 -1,
+                          8.61283e-17 2.22045e-16 -1,
+                          8.61283e-17 2.22045e-16 -1,
+                          8.61283e-17 2.22045e-16 -1,
+                          8.61283e-17 2.22045e-16 -1,
+                          8.61283e-17 2.22045e-16 -1,
+                          8.61283e-17 2.22045e-16 -1,
+                          8.61283e-17 2.22045e-16 -1,
+                          8.61283e-17 2.22045e-16 -1,
+                          8.61283e-17 2.22045e-16 -1,
+                          8.61283e-17 2.22045e-16 -1,
+                          8.61283e-17 2.22045e-16 -1,
+                          8.61283e-17 2.22045e-16 -1,
+                          8.61283e-17 2.22045e-16 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -31.7337 -31.7337 166,
+                          34.7337 -31.7337 166,
+                          48.5 1.5 166,
+                          48.5 1.5 20,
+                          48.5 1.5 166,
+                          34.7337 -31.7337 166,
+                          -45.5 1.5 166,
+                          -31.7337 -31.7337 166,
+                          48.5 1.5 166,
+                          34.7337 34.7337 166,
+                          -45.5 1.5 166,
+                          48.5 1.5 166,
+                          34.7337 34.7337 20,
+                          34.7337 34.7337 166,
+                          48.5 1.5 166,
+                          34.7337 34.7337 20,
+                          48.5 1.5 166,
+                          48.5 1.5 20,
+                          -31.7337 -31.7337 166,
+                          1.5 -45.5 166,
+                          34.7337 -31.7337 166,
+                          34.7337 -31.7337 20,
+                          34.7337 -31.7337 166,
+                          1.5 -45.5 166,
+                          34.7337 -31.7337 20,
+                          48.5 1.5 20,
+                          34.7337 -31.7337 166,
+                          1.5 -45.5 20,
+                          1.5 -45.5 166,
+                          -31.7337 -31.7337 166,
+                          34.7337 -31.7337 20,
+                          1.5 -45.5 166,
+                          1.5 -45.5 20,
+                          -31.7337 -31.7337 20,
+                          -31.7337 -31.7337 166,
+                          -45.5 1.5 166,
+                          1.5 -45.5 20,
+                          -31.7337 -31.7337 166,
+                          -31.7337 -31.7337 20,
+                          34.7337 34.7337 166,
+                          -31.7337 34.7337 166,
+                          -45.5 1.5 166,
+                          -45.5 1.5 20,
+                          -45.5 1.5 166,
+                          -31.7337 34.7337 166,
+                          -31.7337 -31.7337 20,
+                          -45.5 1.5 166,
+                          -45.5 1.5 20,
+                          34.7337 34.7337 166,
+                          1.5 48.5 166,
+                          -31.7337 34.7337 166,
+                          -31.7337 34.7337 20,
+                          -31.7337 34.7337 166,
+                          1.5 48.5 166,
+                          -45.5 1.5 20,
+                          -31.7337 34.7337 166,
+                          -31.7337 34.7337 20,
+                          1.5 48.5 20,
+                          1.5 48.5 166,
+                          34.7337 34.7337 166,
+                          -31.7337 34.7337 20,
+                          1.5 48.5 166,
+                          1.5 48.5 20,
+                          1.5 48.5 20,
+                          34.7337 34.7337 166,
+                          34.7337 34.7337 20,
+                          -31.7337 34.7337 20,
+                          34.7337 34.7337 20,
+                          48.5 1.5 20,
+                          -45.5 1.5 20,
+                          -31.7337 34.7337 20,
+                          48.5 1.5 20,
+                          34.7337 -31.7337 20,
+                          -45.5 1.5 20,
+                          48.5 1.5 20,
+                          -31.7337 34.7337 20,
+                          1.5 48.5 20,
+                          34.7337 34.7337 20,
+                          34.7337 -31.7337 20,
+                          -31.7337 -31.7337 20,
+                          -45.5 1.5 20,
+                          34.7337 -31.7337 20,
+                          1.5 -45.5 20,
+                          -31.7337 -31.7337 20 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.867564 0.849066 0.868687
+    }
+    Separator {
+        Normal {
+            vector      [ 0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0.999793 -0.0203361,
+                          0 0.638971 0.769231,
+                          0 0.638971 0.769231,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.999793 -0.0203361,
+                          0 0.638971 0.769231,
+                          0 0.999793 -0.0203361,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.999793 -0.0203361,
+                          0 -0.638971 0.769231,
+                          0 -0.638971 0.769231,
+                          0 -0.999793 -0.0203361,
+                          0 -0.638971 0.769231,
+                          0 -0.999793 -0.0203361,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -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,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.5 0.866025,
+                          0 0.5 0.866025,
+                          0 0.5 0.866025,
+                          0 0.5 0.866025,
+                          0 0.5 0.866025,
+                          0 0.5 0.866025,
+                          -1 0 0,
+                          -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 1.83691e-16,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 1 -6.12303e-17,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          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 -6.12303e-17,
+                          0 1.22461e-16 1,
+                          0 1 -6.12303e-17,
+                          0 -1 1.83691e-16,
+                          0 -1 1.83691e-16,
+                          0 1.22461e-16 1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -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 -2.44921e-16 -1,
+                          0 -2.44921e-16 -1,
+                          0 -1 1.83691e-16,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -1 1.83691e-16,
+                          0 -2.44921e-16 -1,
+                          0 -1 1.83691e-16,
+                          0 1 -6.12303e-17,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 -1.22461e-16 -1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.999793 -0.0203361,
+                          0 0.6071 -0.794625,
+                          0 0.6071 -0.794625,
+                          0 0.999793 -0.0203361,
+                          0 0.999793 -0.0203361,
+                          0 0.6071 -0.794625,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.999793 -0.0203361,
+                          0 -0.6071 -0.794625,
+                          0 -0.6071 -0.794625,
+                          0 -0.5 0.866025,
+                          0 -0.5 0.866025,
+                          0 -0.5 0.866025,
+                          0 -0.999793 -0.0203361,
+                          0 -0.999793 -0.0203361,
+                          0 -0.6071 -0.794625,
+                          0 -0.5 0.866025,
+                          0 -0.5 0.866025,
+                          0 -0.5 0.866025 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 22.5 -8.30662 203.5,
+                          22.5 8.30662 203.5,
+                          -22.5 8.30662 203.5,
+                          22.5 12.9968 193.236,
+                          -22.5 8.30662 203.5,
+                          22.5 8.30662 203.5,
+                          -22.5 -8.30662 203.5,
+                          22.5 -8.30662 203.5,
+                          -22.5 8.30662 203.5,
+                          -22.5 12.9968 193.236,
+                          -22.5 -8.30662 203.5,
+                          -22.5 8.30662 203.5,
+                          -22.5 12.9968 193.236,
+                          -22.5 8.30662 203.5,
+                          22.5 12.9968 193.236,
+                          22.5 -12.9968 193.236,
+                          22.5 8.30662 203.5,
+                          22.5 -8.30662 203.5,
+                          22.5 2.5 193.5,
+                          22.5 8.30662 203.5,
+                          22.5 -3.55271e-15 196,
+                          22.5 -12.9968 193.236,
+                          22.5 -3.55271e-15 196,
+                          22.5 8.30662 203.5,
+                          22.5 12.9968 193.236,
+                          22.5 8.30662 203.5,
+                          22.5 2.5 193.5,
+                          -22.5 -12.9968 193.236,
+                          22.5 -8.30662 203.5,
+                          -22.5 -8.30662 203.5,
+                          22.5 -12.9968 193.236,
+                          22.5 -8.30662 203.5,
+                          -22.5 -12.9968 193.236,
+                          -22.5 12.9968 193.236,
+                          -22.5 -3.55271e-15 196,
+                          -22.5 -8.30662 203.5,
+                          -22.5 -2.5 193.5,
+                          -22.5 -8.30662 203.5,
+                          -22.5 -3.55271e-15 196,
+                          -22.5 -2.5 193.5,
+                          -22.5 -12.9968 193.236,
+                          -22.5 -8.30662 203.5,
+                          22.5 -22.5 0,
+                          -22.5 22.5 0,
+                          22.5 22.5 0,
+                          -22.5 22.5 174.736,
+                          22.5 22.5 0,
+                          -22.5 22.5 0,
+                          22.5 22.5 174.736,
+                          22.5 -22.5 0,
+                          22.5 22.5 0,
+                          22.5 22.5 174.736,
+                          22.5 22.5 0,
+                          -22.5 22.5 174.736,
+                          22.5 -22.5 0,
+                          -22.5 -22.5 0,
+                          -22.5 22.5 0,
+                          -22.5 -22.5 174.736,
+                          -22.5 22.5 0,
+                          -22.5 -22.5 0,
+                          -22.5 -22.5 174.736,
+                          -22.5 22.5 174.736,
+                          -22.5 22.5 0,
+                          22.5 -22.5 174.736,
+                          -22.5 -22.5 0,
+                          22.5 -22.5 0,
+                          -22.5 -22.5 174.736,
+                          -22.5 -22.5 0,
+                          22.5 -22.5 174.736,
+                          22.5 -22.5 174.736,
+                          22.5 -22.5 0,
+                          22.5 22.5 174.736,
+                          22.5 7.8923 183.17,
+                          22.5 22.5 174.736,
+                          -22.5 22.5 174.736,
+                          -22.5 7.8923 183.17,
+                          22.5 7.8923 183.17,
+                          -22.5 22.5 174.736,
+                          -22.5 -7.8923 183.17,
+                          -22.5 7.8923 183.17,
+                          -22.5 22.5 174.736,
+                          -22.5 -22.5 174.736,
+                          -22.5 -7.8923 183.17,
+                          -22.5 22.5 174.736,
+                          22.5 -22.5 174.736,
+                          22.5 22.5 174.736,
+                          22.5 7.8923 183.17,
+                          22.5 2.5 193.5,
+                          -22.5 -3.55271e-15 191,
+                          22.5 -3.55271e-15 191,
+                          -22.5 -2.5 193.5,
+                          22.5 -3.55271e-15 191,
+                          -22.5 -3.55271e-15 191,
+                          22.5 12.9968 193.236,
+                          22.5 2.5 193.5,
+                          22.5 -3.55271e-15 191,
+                          22.5 -7.8923 183.17,
+                          22.5 12.9968 193.236,
+                          22.5 -3.55271e-15 191,
+                          22.5 -12.9968 193.236,
+                          22.5 -7.8923 183.17,
+                          22.5 -3.55271e-15 191,
+                          22.5 -2.5 193.5,
+                          22.5 -12.9968 193.236,
+                          22.5 -3.55271e-15 191,
+                          22.5 -2.5 193.5,
+                          22.5 -3.55271e-15 191,
+                          -22.5 -2.5 193.5,
+                          22.5 2.5 193.5,
+                          -22.5 2.5 193.5,
+                          -22.5 -3.55271e-15 191,
+                          -22.5 12.9968 193.236,
+                          -22.5 -3.55271e-15 191,
+                          -22.5 2.5 193.5,
+                          -22.5 12.9968 193.236,
+                          -22.5 7.8923 183.17,
+                          -22.5 -3.55271e-15 191,
+                          -22.5 -12.9968 193.236,
+                          -22.5 -3.55271e-15 191,
+                          -22.5 7.8923 183.17,
+                          -22.5 -2.5 193.5,
+                          -22.5 -3.55271e-15 191,
+                          -22.5 -12.9968 193.236,
+                          22.5 -3.55271e-15 196,
+                          -22.5 -3.55271e-15 196,
+                          -22.5 2.5 193.5,
+                          -22.5 12.9968 193.236,
+                          -22.5 2.5 193.5,
+                          -22.5 -3.55271e-15 196,
+                          22.5 2.5 193.5,
+                          22.5 -3.55271e-15 196,
+                          -22.5 2.5 193.5,
+                          22.5 -2.5 193.5,
+                          -22.5 -3.55271e-15 196,
+                          22.5 -3.55271e-15 196,
+                          22.5 -2.5 193.5,
+                          -22.5 -2.5 193.5,
+                          -22.5 -3.55271e-15 196,
+                          22.5 -2.5 193.5,
+                          22.5 -3.55271e-15 196,
+                          22.5 -12.9968 193.236,
+                          -22.5 12.9968 193.236,
+                          22.5 7.8923 183.17,
+                          -22.5 7.8923 183.17,
+                          -22.5 12.9968 193.236,
+                          22.5 12.9968 193.236,
+                          22.5 7.8923 183.17,
+                          22.5 -7.8923 183.17,
+                          22.5 7.8923 183.17,
+                          22.5 12.9968 193.236,
+                          22.5 -22.5 174.736,
+                          22.5 7.8923 183.17,
+                          22.5 -7.8923 183.17,
+                          -22.5 -12.9968 193.236,
+                          -22.5 7.8923 183.17,
+                          -22.5 -7.8923 183.17,
+                          22.5 -12.9968 193.236,
+                          -22.5 -7.8923 183.17,
+                          22.5 -7.8923 183.17,
+                          22.5 -22.5 174.736,
+                          22.5 -7.8923 183.17,
+                          -22.5 -7.8923 183.17,
+                          22.5 -12.9968 193.236,
+                          -22.5 -12.9968 193.236,
+                          -22.5 -7.8923 183.17,
+                          -22.5 -22.5 174.736,
+                          22.5 -22.5 174.736,
+                          -22.5 -7.8923 183.17 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/left_arm/upperarm_l.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/left_arm/upperarm_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..aa4448cf7c2a0d5473f68a877283dd00728006e5
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/left_arm/upperarm_l.iv
@@ -0,0 +1,3464 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+
+    Material {
+        diffuseColor    0.62 0.62 0.62
+    }
+    Separator {
+        Normal {
+            vector      [ 6.0227e-17 -0.809017 0.587785,
+                          1.4115e-17 -1 1.20726e-16,
+                          1.4115e-17 -1 1.20726e-16,
+                          -3.73885e-17 -0.809017 -0.587785,
+                          1.4115e-17 -1 1.20726e-16,
+                          1.4115e-17 -1 1.20726e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -3.73885e-17 -0.809017 -0.587785,
+                          -3.73885e-17 -0.809017 -0.587785,
+                          1.4115e-17 -1 1.20726e-16,
+                          6.0227e-17 -0.809017 0.587785,
+                          6.0227e-17 -0.809017 0.587785,
+                          1.4115e-17 -1 1.20726e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          8.33344e-17 -0.309017 0.951057,
+                          8.33344e-17 -0.309017 0.951057,
+                          6.0227e-17 -0.809017 0.587785,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          6.0227e-17 -0.809017 0.587785,
+                          8.33344e-17 -0.309017 0.951057,
+                          6.0227e-17 -0.809017 0.587785,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          7.46109e-17 0.309017 0.951057,
+                          7.46109e-17 0.309017 0.951057,
+                          8.33344e-17 -0.309017 0.951057,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          8.33344e-17 -0.309017 0.951057,
+                          7.46109e-17 0.309017 0.951057,
+                          8.33344e-17 -0.309017 0.951057,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          3.73885e-17 0.809017 0.587785,
+                          3.73885e-17 0.809017 0.587785,
+                          7.46109e-17 0.309017 0.951057,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          7.46109e-17 0.309017 0.951057,
+                          3.73885e-17 0.809017 0.587785,
+                          7.46109e-17 0.309017 0.951057,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          -1.4115e-17 1 1.73472e-18,
+                          -1.4115e-17 1 1.73472e-18,
+                          3.73885e-17 0.809017 0.587785,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          3.73885e-17 0.809017 0.587785,
+                          -1.4115e-17 1 1.73472e-18,
+                          3.73885e-17 0.809017 0.587785,
+                          -6.0227e-17 0.809017 -0.587785,
+                          -1.4115e-17 1 -2.43187e-16,
+                          -1.4115e-17 1 -2.43187e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          -6.0227e-17 0.809017 -0.587785,
+                          -1.4115e-17 1 -2.43187e-16,
+                          -6.0227e-17 0.809017 -0.587785,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          -1.4115e-17 1 -1.20726e-16,
+                          -1.4115e-17 1 -1.20726e-16,
+                          -4.87454e-17 0.900969 -0.433884,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          2.33112e-17 0.900969 0.433884,
+                          2.33112e-17 0.900969 0.433884,
+                          -1.4115e-17 1 -1.20726e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          2.33112e-17 0.900969 0.433884,
+                          -1.4115e-17 1 -1.20726e-16,
+                          -1.4115e-17 1 -1.20726e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          -4.87454e-17 0.900969 -0.433884,
+                          -4.87454e-17 0.900969 -0.433884,
+                          -7.37213e-17 0.62349 -0.781832,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          -4.87454e-17 0.900969 -0.433884,
+                          -1.4115e-17 1 -1.20726e-16,
+                          -4.87454e-17 0.900969 -0.433884,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          -7.37213e-17 0.62349 -0.781832,
+                          -7.37213e-17 0.62349 -0.781832,
+                          -8.40957e-17 0.222521 -0.974928,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          -7.37213e-17 0.62349 -0.781832,
+                          -4.87454e-17 0.900969 -0.433884,
+                          -7.37213e-17 0.62349 -0.781832,
+                          -8.40957e-17 0.222521 -0.974928,
+                          -8.40957e-17 0.222521 -0.974928,
+                          -7.7814e-17 -0.222521 -0.974928,
+                          -8.40957e-17 0.222521 -0.974928,
+                          -7.37213e-17 0.62349 -0.781832,
+                          -8.40957e-17 0.222521 -0.974928,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          -7.7814e-17 -0.222521 -0.974928,
+                          -7.7814e-17 -0.222521 -0.974928,
+                          -5.61202e-17 -0.62349 -0.781832,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          -7.7814e-17 -0.222521 -0.974928,
+                          -8.40957e-17 0.222521 -0.974928,
+                          -7.7814e-17 -0.222521 -0.974928,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          -5.61202e-17 -0.62349 -0.781832,
+                          -5.61202e-17 -0.62349 -0.781832,
+                          -2.33112e-17 -0.900969 -0.433884,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          -5.61202e-17 -0.62349 -0.781832,
+                          -7.7814e-17 -0.222521 -0.974928,
+                          -5.61202e-17 -0.62349 -0.781832,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          -2.33112e-17 -0.900969 -0.433884,
+                          -2.33112e-17 -0.900969 -0.433884,
+                          1.4115e-17 -1 -1.73472e-18,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          -2.33112e-17 -0.900969 -0.433884,
+                          -5.61202e-17 -0.62349 -0.781832,
+                          -2.33112e-17 -0.900969 -0.433884,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1.4115e-17 -1 2.43187e-16,
+                          1.4115e-17 -1 2.43187e-16,
+                          4.87454e-17 -0.900969 0.433884,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1.4115e-17 -1 -1.73472e-18,
+                          -2.33112e-17 -0.900969 -0.433884,
+                          1.4115e-17 -1 -1.73472e-18,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          4.87454e-17 -0.900969 0.433884,
+                          4.87454e-17 -0.900969 0.433884,
+                          7.37213e-17 -0.62349 0.781832,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          4.87454e-17 -0.900969 0.433884,
+                          1.4115e-17 -1 2.43187e-16,
+                          4.87454e-17 -0.900969 0.433884,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          7.37213e-17 -0.62349 0.781832,
+                          7.37213e-17 -0.62349 0.781832,
+                          8.40957e-17 -0.222521 0.974928,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          4.87454e-17 -0.900969 0.433884,
+                          7.37213e-17 -0.62349 0.781832,
+                          7.37213e-17 -0.62349 0.781832,
+                          8.40957e-17 -0.222521 0.974928,
+                          8.40957e-17 -0.222521 0.974928,
+                          7.7814e-17 0.222521 0.974928,
+                          7.37213e-17 -0.62349 0.781832,
+                          8.40957e-17 -0.222521 0.974928,
+                          8.40957e-17 -0.222521 0.974928,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          7.7814e-17 0.222521 0.974928,
+                          7.7814e-17 0.222521 0.974928,
+                          5.61202e-17 0.62349 0.781832,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          8.40957e-17 -0.222521 0.974928,
+                          7.7814e-17 0.222521 0.974928,
+                          7.7814e-17 0.222521 0.974928,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          5.61202e-17 0.62349 0.781832,
+                          5.61202e-17 0.62349 0.781832,
+                          2.33112e-17 0.900969 0.433884,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          7.7814e-17 0.222521 0.974928,
+                          5.61202e-17 0.62349 0.781832,
+                          5.61202e-17 0.62349 0.781832,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          5.61202e-17 0.62349 0.781832,
+                          2.33112e-17 0.900969 0.433884,
+                          2.33112e-17 0.900969 0.433884,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -6.0227e-17 0.809017 -0.587785,
+                          -6.0227e-17 0.809017 -0.587785,
+                          -8.33344e-17 0.309017 -0.951057,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -8.33344e-17 0.309017 -0.951057,
+                          -8.33344e-17 0.309017 -0.951057,
+                          -7.46109e-17 -0.309017 -0.951057,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -8.33344e-17 0.309017 -0.951057,
+                          -6.0227e-17 0.809017 -0.587785,
+                          -8.33344e-17 0.309017 -0.951057,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -7.46109e-17 -0.309017 -0.951057,
+                          -7.46109e-17 -0.309017 -0.951057,
+                          -3.73885e-17 -0.809017 -0.587785,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -7.46109e-17 -0.309017 -0.951057,
+                          -8.33344e-17 0.309017 -0.951057,
+                          -7.46109e-17 -0.309017 -0.951057,
+                          -3.73885e-17 -0.809017 -0.587785,
+                          -7.46109e-17 -0.309017 -0.951057,
+                          -3.73885e-17 -0.809017 -0.587785,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -72.5 14.9668 -10.874,
+                          -69.5 18.5 4.30283e-14,
+                          -72.5 18.5 4.3403e-14,
+                          -69.5 14.9668 10.874,
+                          -72.5 18.5 4.3403e-14,
+                          -69.5 18.5 4.30283e-14,
+                          -72.5 34.237 -16.4872,
+                          -72.5 14.9668 -10.874,
+                          -72.5 18.5 4.3403e-14,
+                          -72.5 34.237 -16.4872,
+                          -72.5 18.5 4.3403e-14,
+                          -72.5 38 4.34368e-14,
+                          -72.5 14.9668 10.874,
+                          -72.5 38 4.34368e-14,
+                          -72.5 18.5 4.3403e-14,
+                          -69.5 14.9668 10.874,
+                          -72.5 14.9668 10.874,
+                          -72.5 18.5 4.3403e-14,
+                          -72.5 14.9668 -10.874,
+                          -69.5 14.9668 -10.874,
+                          -69.5 18.5 4.30283e-14,
+                          -69.5 33.5 4.30543e-14,
+                          -69.5 18.5 4.30283e-14,
+                          -69.5 14.9668 -10.874,
+                          -69.5 30.1822 14.5355,
+                          -69.5 18.5 4.30283e-14,
+                          -69.5 33.5 4.30543e-14,
+                          -69.5 14.9668 10.874,
+                          -69.5 18.5 4.30283e-14,
+                          -69.5 30.1822 14.5355,
+                          -72.5 5.71681 -17.5945,
+                          -69.5 5.71681 -17.5945,
+                          -69.5 14.9668 -10.874,
+                          -69.5 30.1822 -14.5355,
+                          -69.5 14.9668 -10.874,
+                          -69.5 5.71681 -17.5945,
+                          -72.5 14.9668 -10.874,
+                          -72.5 5.71681 -17.5945,
+                          -69.5 14.9668 -10.874,
+                          -69.5 30.1822 -14.5355,
+                          -69.5 33.5 4.30543e-14,
+                          -69.5 14.9668 -10.874,
+                          -72.5 -5.71681 -17.5945,
+                          -69.5 -5.71681 -17.5945,
+                          -69.5 5.71681 -17.5945,
+                          -69.5 -20.887 -26.1912,
+                          -69.5 5.71681 -17.5945,
+                          -69.5 -5.71681 -17.5945,
+                          -72.5 5.71681 -17.5945,
+                          -72.5 -5.71681 -17.5945,
+                          -69.5 5.71681 -17.5945,
+                          -69.5 30.1822 -14.5355,
+                          -69.5 5.71681 -17.5945,
+                          -69.5 -20.887 -26.1912,
+                          -72.5 -14.9668 -10.874,
+                          -69.5 -14.9668 -10.874,
+                          -69.5 -5.71681 -17.5945,
+                          -69.5 -30.1822 -14.5355,
+                          -69.5 -5.71681 -17.5945,
+                          -69.5 -14.9668 -10.874,
+                          -72.5 -5.71681 -17.5945,
+                          -72.5 -14.9668 -10.874,
+                          -69.5 -5.71681 -17.5945,
+                          -69.5 -20.887 -26.1912,
+                          -69.5 -5.71681 -17.5945,
+                          -69.5 -30.1822 -14.5355,
+                          -72.5 -18.5 4.33388e-14,
+                          -69.5 -18.5 4.29641e-14,
+                          -69.5 -14.9668 -10.874,
+                          -69.5 -30.1822 -14.5355,
+                          -69.5 -14.9668 -10.874,
+                          -69.5 -18.5 4.29641e-14,
+                          -72.5 -14.9668 -10.874,
+                          -72.5 -18.5 4.33388e-14,
+                          -69.5 -14.9668 -10.874,
+                          -72.5 -14.9668 10.874,
+                          -69.5 -18.5 4.29641e-14,
+                          -72.5 -18.5 4.33388e-14,
+                          -69.5 -30.1822 -14.5355,
+                          -69.5 -18.5 4.29641e-14,
+                          -69.5 -33.5 4.2938e-14,
+                          -69.5 -14.9668 10.874,
+                          -69.5 -33.5 4.2938e-14,
+                          -69.5 -18.5 4.29641e-14,
+                          -69.5 -14.9668 10.874,
+                          -69.5 -18.5 4.29641e-14,
+                          -72.5 -14.9668 10.874,
+                          -72.5 -38 4.33049e-14,
+                          -72.5 -18.5 4.33388e-14,
+                          -72.5 -14.9668 -10.874,
+                          -72.5 -34.237 16.4872,
+                          -72.5 -18.5 4.33388e-14,
+                          -72.5 -38 4.33049e-14,
+                          -72.5 -34.237 16.4872,
+                          -72.5 -14.9668 10.874,
+                          -72.5 -18.5 4.33388e-14,
+                          -72.5 -34.237 -16.4872,
+                          -72.5 -14.9668 -10.874,
+                          -72.5 -5.71681 -17.5945,
+                          -72.5 -38 4.33049e-14,
+                          -72.5 -14.9668 -10.874,
+                          -72.5 -34.237 -16.4872,
+                          -72.5 23.6929 -29.7093,
+                          -72.5 -5.71681 -17.5945,
+                          -72.5 5.71681 -17.5945,
+                          -72.5 -34.237 -16.4872,
+                          -72.5 -5.71681 -17.5945,
+                          -72.5 23.6929 -29.7093,
+                          -72.5 34.237 -16.4872,
+                          -72.5 5.71681 -17.5945,
+                          -72.5 14.9668 -10.874,
+                          -72.5 23.6929 -29.7093,
+                          -72.5 5.71681 -17.5945,
+                          -72.5 34.237 -16.4872,
+                          -69.5 30.1822 -14.5355,
+                          -69.5 34.237 -16.4872,
+                          -69.5 38 4.30621e-14,
+                          -72.5 38 4.34368e-14,
+                          -69.5 38 4.30621e-14,
+                          -69.5 34.237 -16.4872,
+                          -69.5 33.5 4.30543e-14,
+                          -69.5 38 4.30621e-14,
+                          -69.5 34.237 16.4872,
+                          -72.5 34.237 16.4872,
+                          -69.5 34.237 16.4872,
+                          -69.5 38 4.30621e-14,
+                          -69.5 30.1822 -14.5355,
+                          -69.5 38 4.30621e-14,
+                          -69.5 33.5 4.30543e-14,
+                          -72.5 34.237 16.4872,
+                          -69.5 38 4.30621e-14,
+                          -72.5 38 4.34368e-14,
+                          -69.5 20.887 -26.1912,
+                          -69.5 23.6929 -29.7093,
+                          -69.5 34.237 -16.4872,
+                          -72.5 34.237 -16.4872,
+                          -69.5 34.237 -16.4872,
+                          -69.5 23.6929 -29.7093,
+                          -69.5 30.1822 -14.5355,
+                          -69.5 20.887 -26.1912,
+                          -69.5 34.237 -16.4872,
+                          -72.5 34.237 -16.4872,
+                          -72.5 38 4.34368e-14,
+                          -69.5 34.237 -16.4872,
+                          -69.5 -8.45593 -37.0472,
+                          -69.5 8.45593 -37.0472,
+                          -69.5 23.6929 -29.7093,
+                          -72.5 23.6929 -29.7093,
+                          -69.5 23.6929 -29.7093,
+                          -69.5 8.45593 -37.0472,
+                          -69.5 7.45486 -32.66,
+                          -69.5 -8.45593 -37.0472,
+                          -69.5 23.6929 -29.7093,
+                          -69.5 20.887 -26.1912,
+                          -69.5 7.45486 -32.66,
+                          -69.5 23.6929 -29.7093,
+                          -72.5 23.6929 -29.7093,
+                          -72.5 34.237 -16.4872,
+                          -69.5 23.6929 -29.7093,
+                          -72.5 8.45593 -37.0472,
+                          -69.5 8.45593 -37.0472,
+                          -69.5 -8.45593 -37.0472,
+                          -72.5 8.45593 -37.0472,
+                          -72.5 23.6929 -29.7093,
+                          -69.5 8.45593 -37.0472,
+                          -69.5 -7.45486 -32.66,
+                          -69.5 -23.6929 -29.7093,
+                          -69.5 -8.45593 -37.0472,
+                          -72.5 -8.45593 -37.0472,
+                          -69.5 -8.45593 -37.0472,
+                          -69.5 -23.6929 -29.7093,
+                          -69.5 7.45486 -32.66,
+                          -69.5 -7.45486 -32.66,
+                          -69.5 -8.45593 -37.0472,
+                          -72.5 -8.45593 -37.0472,
+                          -72.5 8.45593 -37.0472,
+                          -69.5 -8.45593 -37.0472,
+                          -69.5 -20.887 -26.1912,
+                          -69.5 -34.237 -16.4872,
+                          -69.5 -23.6929 -29.7093,
+                          -72.5 -23.6929 -29.7093,
+                          -69.5 -23.6929 -29.7093,
+                          -69.5 -34.237 -16.4872,
+                          -69.5 -7.45486 -32.66,
+                          -69.5 -20.887 -26.1912,
+                          -69.5 -23.6929 -29.7093,
+                          -72.5 -23.6929 -29.7093,
+                          -72.5 -8.45593 -37.0472,
+                          -69.5 -23.6929 -29.7093,
+                          -69.5 -33.5 4.2938e-14,
+                          -69.5 -38 4.29302e-14,
+                          -69.5 -34.237 -16.4872,
+                          -72.5 -34.237 -16.4872,
+                          -69.5 -34.237 -16.4872,
+                          -69.5 -38 4.29302e-14,
+                          -69.5 -30.1822 -14.5355,
+                          -69.5 -33.5 4.2938e-14,
+                          -69.5 -34.237 -16.4872,
+                          -69.5 -20.887 -26.1912,
+                          -69.5 -30.1822 -14.5355,
+                          -69.5 -34.237 -16.4872,
+                          -72.5 -34.237 -16.4872,
+                          -72.5 -23.6929 -29.7093,
+                          -69.5 -34.237 -16.4872,
+                          -69.5 -30.1822 14.5355,
+                          -69.5 -34.237 16.4872,
+                          -69.5 -38 4.29302e-14,
+                          -72.5 -38 4.33049e-14,
+                          -69.5 -38 4.29302e-14,
+                          -69.5 -34.237 16.4872,
+                          -69.5 -33.5 4.2938e-14,
+                          -69.5 -30.1822 14.5355,
+                          -69.5 -38 4.29302e-14,
+                          -72.5 -38 4.33049e-14,
+                          -72.5 -34.237 -16.4872,
+                          -69.5 -38 4.29302e-14,
+                          -69.5 -20.887 26.1912,
+                          -69.5 -23.6929 29.7093,
+                          -69.5 -34.237 16.4872,
+                          -72.5 -34.237 16.4872,
+                          -69.5 -34.237 16.4872,
+                          -69.5 -23.6929 29.7093,
+                          -69.5 -30.1822 14.5355,
+                          -69.5 -20.887 26.1912,
+                          -69.5 -34.237 16.4872,
+                          -72.5 -34.237 16.4872,
+                          -72.5 -38 4.33049e-14,
+                          -69.5 -34.237 16.4872,
+                          -69.5 8.45593 37.0472,
+                          -69.5 -8.45593 37.0472,
+                          -69.5 -23.6929 29.7093,
+                          -72.5 -23.6929 29.7093,
+                          -69.5 -23.6929 29.7093,
+                          -69.5 -8.45593 37.0472,
+                          -69.5 -7.45486 32.66,
+                          -69.5 8.45593 37.0472,
+                          -69.5 -23.6929 29.7093,
+                          -69.5 -20.887 26.1912,
+                          -69.5 -7.45486 32.66,
+                          -69.5 -23.6929 29.7093,
+                          -72.5 -34.237 16.4872,
+                          -69.5 -23.6929 29.7093,
+                          -72.5 -23.6929 29.7093,
+                          -72.5 -8.45593 37.0472,
+                          -69.5 -8.45593 37.0472,
+                          -69.5 8.45593 37.0472,
+                          -72.5 -23.6929 29.7093,
+                          -69.5 -8.45593 37.0472,
+                          -72.5 -8.45593 37.0472,
+                          -69.5 7.45486 32.66,
+                          -69.5 23.6929 29.7093,
+                          -69.5 8.45593 37.0472,
+                          -72.5 8.45593 37.0472,
+                          -69.5 8.45593 37.0472,
+                          -69.5 23.6929 29.7093,
+                          -69.5 -7.45486 32.66,
+                          -69.5 7.45486 32.66,
+                          -69.5 8.45593 37.0472,
+                          -72.5 -8.45593 37.0472,
+                          -69.5 8.45593 37.0472,
+                          -72.5 8.45593 37.0472,
+                          -69.5 20.887 26.1912,
+                          -69.5 34.237 16.4872,
+                          -69.5 23.6929 29.7093,
+                          -72.5 23.6929 29.7093,
+                          -69.5 23.6929 29.7093,
+                          -69.5 34.237 16.4872,
+                          -69.5 7.45486 32.66,
+                          -69.5 20.887 26.1912,
+                          -69.5 23.6929 29.7093,
+                          -72.5 8.45593 37.0472,
+                          -69.5 23.6929 29.7093,
+                          -72.5 23.6929 29.7093,
+                          -69.5 30.1822 14.5355,
+                          -69.5 33.5 4.30543e-14,
+                          -69.5 34.237 16.4872,
+                          -69.5 20.887 26.1912,
+                          -69.5 30.1822 14.5355,
+                          -69.5 34.237 16.4872,
+                          -72.5 23.6929 29.7093,
+                          -69.5 34.237 16.4872,
+                          -72.5 34.237 16.4872,
+                          -69.5 5.71681 17.5945,
+                          -69.5 30.1822 14.5355,
+                          -69.5 20.887 26.1912,
+                          -69.5 14.9668 10.874,
+                          -69.5 30.1822 14.5355,
+                          -69.5 5.71681 17.5945,
+                          -69.5 -20.887 26.1912,
+                          -69.5 20.887 26.1912,
+                          -69.5 7.45486 32.66,
+                          -69.5 -30.1822 14.5355,
+                          -69.5 20.887 26.1912,
+                          -69.5 -20.887 26.1912,
+                          -69.5 -5.71681 17.5945,
+                          -69.5 20.887 26.1912,
+                          -69.5 -30.1822 14.5355,
+                          -69.5 5.71681 17.5945,
+                          -69.5 20.887 26.1912,
+                          -69.5 -5.71681 17.5945,
+                          -69.5 -20.887 26.1912,
+                          -69.5 7.45486 32.66,
+                          -69.5 -7.45486 32.66,
+                          -69.5 -14.9668 10.874,
+                          -69.5 -30.1822 14.5355,
+                          -69.5 -33.5 4.2938e-14,
+                          -69.5 -5.71681 17.5945,
+                          -69.5 -30.1822 14.5355,
+                          -69.5 -14.9668 10.874,
+                          -69.5 20.887 -26.1912,
+                          -69.5 -20.887 -26.1912,
+                          -69.5 -7.45486 -32.66,
+                          -69.5 30.1822 -14.5355,
+                          -69.5 -20.887 -26.1912,
+                          -69.5 20.887 -26.1912,
+                          -69.5 20.887 -26.1912,
+                          -69.5 -7.45486 -32.66,
+                          -69.5 7.45486 -32.66,
+                          -72.5 34.237 16.4872,
+                          -72.5 38 4.34368e-14,
+                          -72.5 14.9668 10.874,
+                          -72.5 -23.6929 -29.7093,
+                          -72.5 23.6929 -29.7093,
+                          -72.5 8.45593 -37.0472,
+                          -72.5 -34.237 -16.4872,
+                          -72.5 23.6929 -29.7093,
+                          -72.5 -23.6929 -29.7093,
+                          -72.5 -23.6929 -29.7093,
+                          -72.5 8.45593 -37.0472,
+                          -72.5 -8.45593 -37.0472,
+                          -72.5 -34.237 16.4872,
+                          -72.5 -5.71681 17.5945,
+                          -72.5 -14.9668 10.874,
+                          -69.5 -14.9668 10.874,
+                          -72.5 -14.9668 10.874,
+                          -72.5 -5.71681 17.5945,
+                          -72.5 -23.6929 29.7093,
+                          -72.5 5.71681 17.5945,
+                          -72.5 -5.71681 17.5945,
+                          -69.5 -5.71681 17.5945,
+                          -72.5 -5.71681 17.5945,
+                          -72.5 5.71681 17.5945,
+                          -72.5 -34.237 16.4872,
+                          -72.5 -23.6929 29.7093,
+                          -72.5 -5.71681 17.5945,
+                          -69.5 -5.71681 17.5945,
+                          -69.5 -14.9668 10.874,
+                          -72.5 -5.71681 17.5945,
+                          -72.5 34.237 16.4872,
+                          -72.5 14.9668 10.874,
+                          -72.5 5.71681 17.5945,
+                          -69.5 5.71681 17.5945,
+                          -72.5 5.71681 17.5945,
+                          -72.5 14.9668 10.874,
+                          -72.5 -23.6929 29.7093,
+                          -72.5 34.237 16.4872,
+                          -72.5 5.71681 17.5945,
+                          -69.5 5.71681 17.5945,
+                          -69.5 -5.71681 17.5945,
+                          -72.5 5.71681 17.5945,
+                          -69.5 14.9668 10.874,
+                          -69.5 5.71681 17.5945,
+                          -72.5 14.9668 10.874,
+                          -72.5 -23.6929 29.7093,
+                          -72.5 23.6929 29.7093,
+                          -72.5 34.237 16.4872,
+                          -72.5 -8.45593 37.0472,
+                          -72.5 8.45593 37.0472,
+                          -72.5 23.6929 29.7093,
+                          -72.5 -23.6929 29.7093,
+                          -72.5 -8.45593 37.0472,
+                          -72.5 23.6929 29.7093 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+    Separator {
+        Normal {
+            vector      [ 1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          -8.30368e-17 2.28279e-16 -1,
+                          -8.30368e-17 2.28279e-16 -1,
+                          -5.88816e-17 -0.587785 -0.809017,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          -7.54747e-17 0.587785 -0.809017,
+                          -7.54747e-17 0.587785 -0.809017,
+                          -8.30368e-17 2.28279e-16 -1,
+                          -7.54747e-17 0.587785 -0.809017,
+                          -8.30368e-17 2.28279e-16 -1,
+                          -8.30368e-17 2.28279e-16 -1,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          -5.88816e-17 -0.587785 -0.809017,
+                          -5.88816e-17 -0.587785 -0.809017,
+                          -1.22356e-17 -0.951057 -0.309017,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          -5.88816e-17 -0.587785 -0.809017,
+                          -8.30368e-17 2.28279e-16 -1,
+                          -5.88816e-17 -0.587785 -0.809017,
+                          -1.22356e-17 -0.951057 -0.309017,
+                          -1.22356e-17 -0.951057 -0.309017,
+                          3.90839e-17 -0.951057 0.309017,
+                          -5.88816e-17 -0.587785 -0.809017,
+                          -1.22356e-17 -0.951057 -0.309017,
+                          -1.22356e-17 -0.951057 -0.309017,
+                          3.90839e-17 -0.951057 0.309017,
+                          3.90839e-17 -0.951057 0.309017,
+                          7.54747e-17 -0.587785 0.809017,
+                          -1.22356e-17 -0.951057 -0.309017,
+                          3.90839e-17 -0.951057 0.309017,
+                          3.90839e-17 -0.951057 0.309017,
+                          7.54747e-17 -0.587785 0.809017,
+                          7.54747e-17 -0.587785 0.809017,
+                          8.30368e-17 -3.50739e-16 1,
+                          3.90839e-17 -0.951057 0.309017,
+                          7.54747e-17 -0.587785 0.809017,
+                          7.54747e-17 -0.587785 0.809017,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          8.30368e-17 -1.05818e-16 1,
+                          8.30368e-17 -1.05818e-16 1,
+                          5.88816e-17 0.587785 0.809017,
+                          7.54747e-17 -0.587785 0.809017,
+                          8.30368e-17 -3.50739e-16 1,
+                          8.30368e-17 -3.50739e-16 1,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          5.88816e-17 0.587785 0.809017,
+                          5.88816e-17 0.587785 0.809017,
+                          1.22356e-17 0.951057 0.309017,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          1 5.66496e-17 -1.249e-16,
+                          8.30368e-17 -1.05818e-16 1,
+                          5.88816e-17 0.587785 0.809017,
+                          5.88816e-17 0.587785 0.809017,
+                          1.22356e-17 0.951057 0.309017,
+                          1.22356e-17 0.951057 0.309017,
+                          -3.90839e-17 0.951057 -0.309017,
+                          5.88816e-17 0.587785 0.809017,
+                          1.22356e-17 0.951057 0.309017,
+                          1.22356e-17 0.951057 0.309017,
+                          -3.90839e-17 0.951057 -0.309017,
+                          -3.90839e-17 0.951057 -0.309017,
+                          -7.54747e-17 0.587785 -0.809017,
+                          1.22356e-17 0.951057 0.309017,
+                          -3.90839e-17 0.951057 -0.309017,
+                          -3.90839e-17 0.951057 -0.309017,
+                          -3.90839e-17 0.951057 -0.309017,
+                          -7.54747e-17 0.587785 -0.809017,
+                          -7.54747e-17 0.587785 -0.809017,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -8.30368e-17 2.28279e-16 -1,
+                          -8.30368e-17 2.28279e-16 -1,
+                          -7.54747e-17 0.587785 -0.809017,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -5.88816e-17 -0.587785 -0.809017,
+                          -5.88816e-17 -0.587785 -0.809017,
+                          -8.30368e-17 2.28279e-16 -1,
+                          -5.88816e-17 -0.587785 -0.809017,
+                          -8.30368e-17 2.28279e-16 -1,
+                          -8.30368e-17 2.28279e-16 -1,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -7.54747e-17 0.587785 -0.809017,
+                          -7.54747e-17 0.587785 -0.809017,
+                          -3.90839e-17 0.951057 -0.309017,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -7.54747e-17 0.587785 -0.809017,
+                          -8.30368e-17 2.28279e-16 -1,
+                          -7.54747e-17 0.587785 -0.809017,
+                          -3.90839e-17 0.951057 -0.309017,
+                          -3.90839e-17 0.951057 -0.309017,
+                          1.22356e-17 0.951057 0.309017,
+                          -3.90839e-17 0.951057 -0.309017,
+                          -7.54747e-17 0.587785 -0.809017,
+                          -3.90839e-17 0.951057 -0.309017,
+                          1.22356e-17 0.951057 0.309017,
+                          1.22356e-17 0.951057 0.309017,
+                          5.88816e-17 0.587785 0.809017,
+                          1.22356e-17 0.951057 0.309017,
+                          -3.90839e-17 0.951057 -0.309017,
+                          1.22356e-17 0.951057 0.309017,
+                          5.88816e-17 0.587785 0.809017,
+                          5.88816e-17 0.587785 0.809017,
+                          8.30368e-17 -1.05818e-16 1,
+                          5.88816e-17 0.587785 0.809017,
+                          1.22356e-17 0.951057 0.309017,
+                          5.88816e-17 0.587785 0.809017,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          8.30368e-17 -3.50739e-16 1,
+                          8.30368e-17 -3.50739e-16 1,
+                          7.54747e-17 -0.587785 0.809017,
+                          8.30368e-17 -1.05818e-16 1,
+                          5.88816e-17 0.587785 0.809017,
+                          8.30368e-17 -1.05818e-16 1,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          7.54747e-17 -0.587785 0.809017,
+                          7.54747e-17 -0.587785 0.809017,
+                          3.90839e-17 -0.951057 0.309017,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          -1 -5.66496e-17 1.249e-16,
+                          7.54747e-17 -0.587785 0.809017,
+                          8.30368e-17 -3.50739e-16 1,
+                          7.54747e-17 -0.587785 0.809017,
+                          3.90839e-17 -0.951057 0.309017,
+                          3.90839e-17 -0.951057 0.309017,
+                          -1.22356e-17 -0.951057 -0.309017,
+                          3.90839e-17 -0.951057 0.309017,
+                          7.54747e-17 -0.587785 0.809017,
+                          3.90839e-17 -0.951057 0.309017,
+                          -1.22356e-17 -0.951057 -0.309017,
+                          -1.22356e-17 -0.951057 -0.309017,
+                          -5.88816e-17 -0.587785 -0.809017,
+                          -1.22356e-17 -0.951057 -0.309017,
+                          3.90839e-17 -0.951057 0.309017,
+                          -1.22356e-17 -0.951057 -0.309017,
+                          -5.88816e-17 -0.587785 -0.809017,
+                          -1.22356e-17 -0.951057 -0.309017,
+                          -5.88816e-17 -0.587785 -0.809017 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -5.68434e-14 -9.11272 12.5378,
+                          -5.68434e-14 -9.11272 -12.5378,
+                          -5.68434e-14 -1.0329e-13 -15.5,
+                          -159.7 -1.10439e-13 -15.5,
+                          -5.68434e-14 -1.0329e-13 -15.5,
+                          -5.68434e-14 -9.11272 -12.5378,
+                          -5.68434e-14 -1.0657e-13 15.5,
+                          -5.68434e-14 -9.11272 12.5378,
+                          -5.68434e-14 -1.0329e-13 -15.5,
+                          -5.68434e-14 9.11272 -12.5378,
+                          -5.68434e-14 -1.0657e-13 15.5,
+                          -5.68434e-14 -1.0329e-13 -15.5,
+                          -159.7 9.11067 -12.5398,
+                          -5.68434e-14 9.11272 -12.5378,
+                          -5.68434e-14 -1.0329e-13 -15.5,
+                          -159.7 9.11067 -12.5398,
+                          -5.68434e-14 -1.0329e-13 -15.5,
+                          -159.7 -1.10439e-13 -15.5,
+                          -5.68434e-14 -14.741 4.78816,
+                          -5.68434e-14 -14.741 -4.78816,
+                          -5.68434e-14 -9.11272 -12.5378,
+                          -159.7 -9.11067 -12.5398,
+                          -5.68434e-14 -9.11272 -12.5378,
+                          -5.68434e-14 -14.741 -4.78816,
+                          -5.68434e-14 -9.11272 12.5378,
+                          -5.68434e-14 -14.741 4.78816,
+                          -5.68434e-14 -9.11272 -12.5378,
+                          -159.7 -9.11067 -12.5398,
+                          -159.7 -1.10439e-13 -15.5,
+                          -5.68434e-14 -9.11272 -12.5378,
+                          -159.7 -14.7414 -4.78976,
+                          -5.68434e-14 -14.741 -4.78816,
+                          -5.68434e-14 -14.741 4.78816,
+                          -159.7 -9.11067 -12.5398,
+                          -5.68434e-14 -14.741 -4.78816,
+                          -159.7 -14.7414 -4.78976,
+                          -159.7 -14.7414 4.78976,
+                          -5.68434e-14 -14.741 4.78816,
+                          -5.68434e-14 -9.11272 12.5378,
+                          -159.7 -14.7414 -4.78976,
+                          -5.68434e-14 -14.741 4.78816,
+                          -159.7 -14.7414 4.78976,
+                          -159.7 -9.11067 12.5398,
+                          -5.68434e-14 -9.11272 12.5378,
+                          -5.68434e-14 -1.0657e-13 15.5,
+                          -159.7 -14.7414 4.78976,
+                          -5.68434e-14 -9.11272 12.5378,
+                          -159.7 -9.11067 12.5398,
+                          -5.68434e-14 9.11272 -12.5378,
+                          -5.68434e-14 9.11272 12.5378,
+                          -5.68434e-14 -1.0657e-13 15.5,
+                          -159.7 -1.15617e-13 15.5,
+                          -5.68434e-14 -1.0657e-13 15.5,
+                          -5.68434e-14 9.11272 12.5378,
+                          -159.7 -9.11067 12.5398,
+                          -5.68434e-14 -1.0657e-13 15.5,
+                          -159.7 -1.15617e-13 15.5,
+                          -5.68434e-14 14.741 -4.78816,
+                          -5.68434e-14 14.741 4.78816,
+                          -5.68434e-14 9.11272 12.5378,
+                          -159.7 9.11067 12.5398,
+                          -5.68434e-14 9.11272 12.5378,
+                          -5.68434e-14 14.741 4.78816,
+                          -5.68434e-14 9.11272 -12.5378,
+                          -5.68434e-14 14.741 -4.78816,
+                          -5.68434e-14 9.11272 12.5378,
+                          -159.7 -1.15617e-13 15.5,
+                          -5.68434e-14 9.11272 12.5378,
+                          -159.7 9.11067 12.5398,
+                          -159.7 14.7414 4.78976,
+                          -5.68434e-14 14.741 4.78816,
+                          -5.68434e-14 14.741 -4.78816,
+                          -159.7 9.11067 12.5398,
+                          -5.68434e-14 14.741 4.78816,
+                          -159.7 14.7414 4.78976,
+                          -159.7 14.7414 -4.78976,
+                          -5.68434e-14 14.741 -4.78816,
+                          -5.68434e-14 9.11272 -12.5378,
+                          -159.7 14.7414 4.78976,
+                          -5.68434e-14 14.741 -4.78816,
+                          -159.7 14.7414 -4.78976,
+                          -159.7 14.7414 -4.78976,
+                          -5.68434e-14 9.11272 -12.5378,
+                          -159.7 9.11067 -12.5398,
+                          -234.7 9.11272 12.5378,
+                          -234.7 9.11272 -12.5378,
+                          -234.7 -1.16586e-13 -15.5,
+                          -159.7 -1.10439e-13 -15.5,
+                          -234.7 -1.16586e-13 -15.5,
+                          -234.7 9.11272 -12.5378,
+                          -234.7 -1.19866e-13 15.5,
+                          -234.7 9.11272 12.5378,
+                          -234.7 -1.16586e-13 -15.5,
+                          -234.7 -9.11272 -12.5378,
+                          -234.7 -1.19866e-13 15.5,
+                          -234.7 -1.16586e-13 -15.5,
+                          -159.7 -9.11067 -12.5398,
+                          -234.7 -9.11272 -12.5378,
+                          -234.7 -1.16586e-13 -15.5,
+                          -159.7 -9.11067 -12.5398,
+                          -234.7 -1.16586e-13 -15.5,
+                          -159.7 -1.10439e-13 -15.5,
+                          -234.7 14.741 4.78816,
+                          -234.7 14.741 -4.78816,
+                          -234.7 9.11272 -12.5378,
+                          -159.7 9.11067 -12.5398,
+                          -234.7 9.11272 -12.5378,
+                          -234.7 14.741 -4.78816,
+                          -234.7 9.11272 12.5378,
+                          -234.7 14.741 4.78816,
+                          -234.7 9.11272 -12.5378,
+                          -159.7 9.11067 -12.5398,
+                          -159.7 -1.10439e-13 -15.5,
+                          -234.7 9.11272 -12.5378,
+                          -159.7 14.7414 -4.78976,
+                          -234.7 14.741 -4.78816,
+                          -234.7 14.741 4.78816,
+                          -159.7 14.7414 -4.78976,
+                          -159.7 9.11067 -12.5398,
+                          -234.7 14.741 -4.78816,
+                          -159.7 14.7414 4.78976,
+                          -234.7 14.741 4.78816,
+                          -234.7 9.11272 12.5378,
+                          -159.7 14.7414 4.78976,
+                          -159.7 14.7414 -4.78976,
+                          -234.7 14.741 4.78816,
+                          -159.7 9.11067 12.5398,
+                          -234.7 9.11272 12.5378,
+                          -234.7 -1.19866e-13 15.5,
+                          -159.7 9.11067 12.5398,
+                          -159.7 14.7414 4.78976,
+                          -234.7 9.11272 12.5378,
+                          -234.7 -9.11272 -12.5378,
+                          -234.7 -9.11272 12.5378,
+                          -234.7 -1.19866e-13 15.5,
+                          -159.7 -1.15617e-13 15.5,
+                          -234.7 -1.19866e-13 15.5,
+                          -234.7 -9.11272 12.5378,
+                          -159.7 -1.15617e-13 15.5,
+                          -159.7 9.11067 12.5398,
+                          -234.7 -1.19866e-13 15.5,
+                          -234.7 -14.741 -4.78816,
+                          -234.7 -14.741 4.78816,
+                          -234.7 -9.11272 12.5378,
+                          -159.7 -9.11067 12.5398,
+                          -234.7 -9.11272 12.5378,
+                          -234.7 -14.741 4.78816,
+                          -234.7 -9.11272 -12.5378,
+                          -234.7 -14.741 -4.78816,
+                          -234.7 -9.11272 12.5378,
+                          -159.7 -9.11067 12.5398,
+                          -159.7 -1.15617e-13 15.5,
+                          -234.7 -9.11272 12.5378,
+                          -159.7 -14.7414 4.78976,
+                          -234.7 -14.741 4.78816,
+                          -234.7 -14.741 -4.78816,
+                          -159.7 -14.7414 4.78976,
+                          -159.7 -9.11067 12.5398,
+                          -234.7 -14.741 4.78816,
+                          -159.7 -14.7414 -4.78976,
+                          -234.7 -14.741 -4.78816,
+                          -234.7 -9.11272 -12.5378,
+                          -159.7 -14.7414 -4.78976,
+                          -159.7 -14.7414 4.78976,
+                          -234.7 -14.741 -4.78816,
+                          -159.7 -9.11067 -12.5398,
+                          -159.7 -14.7414 -4.78976,
+                          -234.7 -9.11272 -12.5378 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    1 1 1
+    }
+    Separator {
+        Normal {
+            vector      [ -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0104096 -0.0102794 -0.999893,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0104096 -0.0102794 -0.999893,
+                          -0.0104096 0.0102794 0.999893,
+                          -0.0104096 0.0102794 0.999893,
+                          -0.0104096 0.0102794 0.999893,
+                          -0.0104096 0.0102794 0.999893,
+                          -0.0104096 0.0102794 0.999893,
+                          -0.0104096 0.0102794 0.999893,
+                          -0.0104096 0.0102794 0.999893,
+                          -0.0104096 0.0102794 0.999893,
+                          -0.0104096 0.0102794 0.999893,
+                          -0.0104096 0.0102794 0.999893,
+                          -0.0104096 0.0102794 0.999893,
+                          -0.0104096 0.0102794 0.999893,
+                          -0.0104096 0.0102794 0.999893,
+                          -0.0104096 0.0102794 0.999893,
+                          -0.0104096 0.0102794 0.999893,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          -0.0104096 0.0102794 0.999893,
+                          -0.0104096 0.0102794 0.999893,
+                          -0.0104096 0.0102794 0.999893,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          -0.595219 0.00828923 0.803521,
+                          -0.284419 0.0098688 0.958649,
+                          -0.284419 0.0098688 0.958649,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -0.595219 0.00828923 0.803521,
+                          -0.284419 0.0098688 0.958649,
+                          -0.595219 0.00828923 0.803521,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          -0.595219 0.00828923 0.803521,
+                          -0.284419 0.0098688 0.958649,
+                          -0.284419 0.0098688 0.958649,
+                          -0.595219 0.00828923 0.803521,
+                          -0.284419 0.0098688 0.958649,
+                          -0.595219 0.00828923 0.803521,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0104096 -0.0102794 -0.999893,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          -0.595219 0.00828923 0.803521,
+                          -0.595219 0.00828923 0.803521,
+                          -0.834198 0.00570945 0.551436,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          -0.834198 0.00570945 0.551436,
+                          -0.834198 0.00570945 0.551436,
+                          -0.972519 0.00244074 0.232813,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          -0.595219 0.00828923 0.803521,
+                          -0.834198 0.00570945 0.551436,
+                          -0.834198 0.00570945 0.551436,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          -0.972519 0.00244074 0.232813,
+                          -0.972519 0.00244074 0.232813,
+                          -0.972519 0.00244074 0.232813,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          -0.972519 0.00244074 0.232813,
+                          -0.972519 0.00244074 0.232813,
+                          -0.972519 0.00244074 0.232813,
+                          -0.834198 0.00570945 0.551436,
+                          -0.972519 0.00244074 0.232813,
+                          -0.972519 0.00244074 0.232813,
+                          -0.972519 0.00244074 0.232813,
+                          -0.972519 0.00244074 0.232813,
+                          -0.812659 -0.00595063 -0.58271,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          -0.812659 -0.00595063 -0.58271,
+                          -0.812659 -0.00595063 -0.58271,
+                          -0.0914936 -0.0102319 -0.995753,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          -0.972519 0.00244074 0.232813,
+                          -0.812659 -0.00595063 -0.58271,
+                          -0.812659 -0.00595063 -0.58271,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          -0.0914936 -0.0102319 -0.995753,
+                          -0.0914936 -0.0102319 -0.995753,
+                          0.692866 -0.00744596 -0.721028,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          -0.812659 -0.00595063 -0.58271,
+                          -0.0914936 -0.0102319 -0.995753,
+                          -0.0914936 -0.0102319 -0.995753,
+                          0.692866 -0.00744596 -0.721028,
+                          0.692866 -0.00744596 -0.721028,
+                          0.692866 -0.00744596 -0.721028,
+                          0.692866 -0.00744596 -0.721028,
+                          0.692866 -0.00744596 -0.721028,
+                          0.692866 -0.00744596 -0.721028,
+                          -0.0914936 -0.0102319 -0.995753,
+                          0.692866 -0.00744596 -0.721028,
+                          0.692866 -0.00744596 -0.721028,
+                          0.692866 -0.00744596 -0.721028,
+                          0.692866 -0.00744596 -0.721028,
+                          0.338071 -0.00969071 -0.941071,
+                          0.338071 -0.00969071 -0.941071,
+                          0.338071 -0.00969071 -0.941071,
+                          -0.0756506 -0.0102463 -0.997082,
+                          0.692866 -0.00744596 -0.721028,
+                          0.338071 -0.00969071 -0.941071,
+                          0.338071 -0.00969071 -0.941071,
+                          0.338071 -0.00969071 -0.941071,
+                          -0.0756506 -0.0102463 -0.997082,
+                          -0.0756506 -0.0102463 -0.997082,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.508988 0.00887312 0.860728,
+                          -0.490958 -0.00893136 -0.871137,
+                          -0.490958 -0.00893136 -0.871137,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.490958 -0.00893136 -0.871137,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.508988 0.00887312 0.860728,
+                          -0.508988 0.00887312 0.860728,
+                          0.490958 0.00893136 0.871137,
+                          -0.508988 0.00887312 0.860728,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.508988 0.00887312 0.860728,
+                          0.490958 0.00893136 0.871137,
+                          0.490958 0.00893136 0.871137,
+                          0.999946 5.82483e-05 0.0104096,
+                          -0.508988 0.00887312 0.860728,
+                          0.490958 0.00893136 0.871137,
+                          0.490958 0.00893136 0.871137,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.508988 -0.00887312 -0.860728,
+                          0.490958 0.00893136 0.871137,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.508988 -0.00887312 -0.860728,
+                          0.508988 -0.00887312 -0.860728,
+                          -0.490958 -0.00893136 -0.871137,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.508988 -0.00887312 -0.860728,
+                          0.508988 -0.00887312 -0.860728,
+                          0.508988 -0.00887312 -0.860728,
+                          -0.490958 -0.00893136 -0.871137,
+                          -0.490958 -0.00893136 -0.871137,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.508988 0.00887312 0.860728,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          -0.490958 -0.00893136 -0.871137,
+                          -0.490958 -0.00893136 -0.871137,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          -0.490958 -0.00893136 -0.871137,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          -0.508988 0.00887312 0.860728,
+                          -0.508988 0.00887312 0.860728,
+                          0.490958 0.00893136 0.871137,
+                          -0.508988 0.00887312 0.860728,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.508988 0.00887312 0.860728,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          0.490958 0.00893136 0.871137,
+                          0.490958 0.00893136 0.871137,
+                          0.999946 5.82483e-05 0.0104096,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          -0.508988 0.00887312 0.860728,
+                          0.490958 0.00893136 0.871137,
+                          0.490958 0.00893136 0.871137,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.508988 -0.00887312 -0.860728,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          0.490958 0.00893136 0.871137,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          0.508988 -0.00887312 -0.860728,
+                          0.508988 -0.00887312 -0.860728,
+                          -0.490958 -0.00893136 -0.871137,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.508988 -0.00887312 -0.860728,
+                          0.508988 -0.00887312 -0.860728,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          0.508988 -0.00887312 -0.860728,
+                          -0.490958 -0.00893136 -0.871137,
+                          -0.490958 -0.00893136 -0.871137,
+                          -0.595219 0.00828923 0.803521,
+                          -0.595219 0.00828923 0.803521,
+                          -0.834198 0.00570945 0.551436,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          -0.834198 0.00570945 0.551436,
+                          -0.834198 0.00570945 0.551436,
+                          -0.972519 0.00244074 0.232813,
+                          -0.595219 0.00828923 0.803521,
+                          -0.834198 0.00570945 0.551436,
+                          -0.834198 0.00570945 0.551436,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          -0.972519 0.00244074 0.232813,
+                          -0.972519 0.00244074 0.232813,
+                          -0.972519 0.00244074 0.232813,
+                          -0.972519 0.00244074 0.232813,
+                          -0.972519 0.00244074 0.232813,
+                          -0.972519 0.00244074 0.232813,
+                          -0.834198 0.00570945 0.551436,
+                          -0.972519 0.00244074 0.232813,
+                          -0.972519 0.00244074 0.232813,
+                          -0.972519 0.00244074 0.232813,
+                          -0.972519 0.00244074 0.232813,
+                          -0.812659 -0.00595063 -0.58271,
+                          -0.812659 -0.00595063 -0.58271,
+                          -0.812659 -0.00595063 -0.58271,
+                          -0.0914936 -0.0102319 -0.995753,
+                          -0.972519 0.00244074 0.232813,
+                          -0.812659 -0.00595063 -0.58271,
+                          -0.812659 -0.00595063 -0.58271,
+                          -0.0914936 -0.0102319 -0.995753,
+                          -0.0914936 -0.0102319 -0.995753,
+                          0.692866 -0.00744596 -0.721028,
+                          -0.812659 -0.00595063 -0.58271,
+                          -0.0914936 -0.0102319 -0.995753,
+                          -0.0914936 -0.0102319 -0.995753,
+                          0.692866 -0.00744596 -0.721028,
+                          0.692866 -0.00744596 -0.721028,
+                          0.692866 -0.00744596 -0.721028,
+                          0.692866 -0.00744596 -0.721028,
+                          0.692866 -0.00744596 -0.721028,
+                          0.692866 -0.00744596 -0.721028,
+                          -0.0914936 -0.0102319 -0.995753,
+                          0.692866 -0.00744596 -0.721028,
+                          0.692866 -0.00744596 -0.721028,
+                          0.692866 -0.00744596 -0.721028,
+                          0.692866 -0.00744596 -0.721028,
+                          0.338071 -0.00969071 -0.941071,
+                          0.338071 -0.00969071 -0.941071,
+                          0.338071 -0.00969071 -0.941071,
+                          -0.0756506 -0.0102463 -0.997082,
+                          0.692866 -0.00744596 -0.721028,
+                          0.338071 -0.00969071 -0.941071,
+                          0.338071 -0.00969071 -0.941071,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.338071 -0.00969071 -0.941071,
+                          -0.0756506 -0.0102463 -0.997082,
+                          -0.0756506 -0.0102463 -0.997082,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0104096 -0.0102794 -0.999893,
+                          -0.373045 -0.00951924 -0.927764,
+                          -0.373045 -0.00951924 -0.927764,
+                          -0.373045 -0.00951924 -0.927764,
+                          -0.699708 -0.00730984 -0.714392,
+                          -0.373045 -0.00951924 -0.927764,
+                          0.0104096 -0.0102794 -0.999893,
+                          -0.373045 -0.00951924 -0.927764,
+                          -0.699708 -0.00730984 -0.714392,
+                          -0.699708 -0.00730984 -0.714392,
+                          -0.699708 -0.00730984 -0.714392,
+                          -0.373045 -0.00951924 -0.927764,
+                          -0.699708 -0.00730984 -0.714392,
+                          -0.699708 -0.00730984 -0.714392,
+                          -0.699708 -0.00730984 -0.714392,
+                          -0.699708 -0.00730984 -0.714392,
+                          0.0104096 -0.0102794 -0.999893,
+                          -0.699708 -0.00730984 -0.714392,
+                          -0.699708 -0.00730984 -0.714392,
+                          -0.699708 -0.00730984 -0.714392,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.714429 -0.00722746 -0.69967,
+                          -0.699708 -0.00730984 -0.714392,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.714429 -0.00722746 -0.69967,
+                          0.714429 -0.00722746 -0.69967,
+                          0.714429 -0.00722746 -0.69967,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.714429 -0.00722746 -0.69967,
+                          0.714429 -0.00722746 -0.69967,
+                          0.714429 -0.00722746 -0.69967,
+                          0.714429 -0.00722746 -0.69967,
+                          0.39228 -0.00947466 -0.919797,
+                          0.714429 -0.00722746 -0.69967,
+                          0.714429 -0.00722746 -0.69967,
+                          0.714429 -0.00722746 -0.69967,
+                          0.39228 -0.00947466 -0.919797,
+                          0.39228 -0.00947466 -0.919797,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.714429 -0.00722746 -0.69967,
+                          0.39228 -0.00947466 -0.919797,
+                          0.39228 -0.00947466 -0.919797,
+                          0.39228 -0.00947466 -0.919797,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0104096 -0.0102794 -0.999893,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -235.261 33.3202 18.8286,
+                          -234.839 32.9039 -21.6671,
+                          -234.842 -19.0933 -21.1325,
+                          -231.114 -19.0931 -21.0937,
+                          -234.842 -19.0933 -21.1325,
+                          -234.839 32.9039 -21.6671,
+                          -235.263 -18.677 19.3631,
+                          -235.261 33.3202 18.8286,
+                          -234.842 -19.0933 -21.1325,
+                          -240.932 -19.1742 -29.0244,
+                          -235.263 -18.677 19.3631,
+                          -234.842 -19.0933 -21.1325,
+                          -234.634 -19.1084 -22.5949,
+                          -240.932 -19.1742 -29.0244,
+                          -234.842 -19.0933 -21.1325,
+                          -233.023 -19.0971 -21.4942,
+                          -234.634 -19.1084 -22.5949,
+                          -234.842 -19.0933 -21.1325,
+                          -231.114 -19.0931 -21.0937,
+                          -233.023 -19.0971 -21.4942,
+                          -234.842 -19.0933 -21.1325,
+                          -268.259 33.3183 18.4851,
+                          -234.839 32.9039 -21.6671,
+                          -235.261 33.3202 18.8286,
+                          -258.855 32.9025 -21.9171,
+                          -234.839 32.9039 -21.6671,
+                          -268.259 33.3183 18.4851,
+                          -258.855 36.9023 -21.9582,
+                          -230.839 36.9039 -21.6666,
+                          -234.839 32.9039 -21.6671,
+                          -231.114 -19.0931 -21.0937,
+                          -234.839 32.9039 -21.6671,
+                          -230.839 36.9039 -21.6666,
+                          -258.855 32.9025 -21.9171,
+                          -258.855 36.9023 -21.9582,
+                          -234.839 32.9039 -21.6671,
+                          -231.261 37.3203 18.8291,
+                          -235.261 33.3202 18.8286,
+                          -235.263 -18.677 19.3631,
+                          -268.259 33.3183 18.4851,
+                          -235.261 33.3202 18.8286,
+                          -231.261 37.3203 18.8291,
+                          -231.264 -22.6766 19.4459,
+                          -231.261 37.3203 18.8291,
+                          -235.263 -18.677 19.3631,
+                          -268.262 -22.6787 19.0607,
+                          -231.264 -22.6766 19.4459,
+                          -235.263 -18.677 19.3631,
+                          -268.262 -18.6789 19.0196,
+                          -268.262 -22.6787 19.0607,
+                          -235.263 -18.677 19.3631,
+                          -267.786 -19.1067 -22.5913,
+                          -268.262 -18.6789 19.0196,
+                          -235.263 -18.677 19.3631,
+                          -258.857 -19.0947 -21.3826,
+                          -267.786 -19.1067 -22.5913,
+                          -235.263 -18.677 19.3631,
+                          -256.569 -19.0946 -21.3587,
+                          -258.857 -19.0947 -21.3826,
+                          -235.263 -18.677 19.3631,
+                          -254.651 -19.0984 -21.7194,
+                          -256.569 -19.0946 -21.3587,
+                          -235.263 -18.677 19.3631,
+                          -253.018 -19.1094 -22.7862,
+                          -254.651 -19.0984 -21.7194,
+                          -235.263 -18.677 19.3631,
+                          -246.588 -19.1745 -29.0833,
+                          -253.018 -19.1094 -22.7862,
+                          -235.263 -18.677 19.3631,
+                          -243.748 -19.1864 -30.2253,
+                          -246.588 -19.1745 -29.0833,
+                          -235.263 -18.677 19.3631,
+                          -240.932 -19.1742 -29.0244,
+                          -243.748 -19.1864 -30.2253,
+                          -235.263 -18.677 19.3631,
+                          -230.839 36.9039 -21.6666,
+                          -231.261 37.3203 18.8291,
+                          -231.264 -22.6766 19.4459,
+                          -268.259 37.3181 18.444,
+                          -268.259 33.3183 18.4851,
+                          -231.261 37.3203 18.8291,
+                          -267.783 36.8903 -23.1669,
+                          -268.259 37.3181 18.444,
+                          -231.261 37.3203 18.8291,
+                          -258.855 36.9023 -21.9582,
+                          -231.261 37.3203 18.8291,
+                          -230.839 36.9039 -21.6666,
+                          -258.855 36.9023 -21.9582,
+                          -267.783 36.8903 -23.1669,
+                          -231.261 37.3203 18.8291,
+                          -230.842 -23.0929 -21.0498,
+                          -231.264 -22.6766 19.4459,
+                          -268.262 -22.6787 19.0607,
+                          -230.839 36.9039 -21.6666,
+                          -231.264 -22.6766 19.4459,
+                          -230.842 -23.0929 -21.0498,
+                          -277.775 -18.7273 14.2713,
+                          -268.262 -22.6787 19.0607,
+                          -268.262 -18.6789 19.0196,
+                          -231.114 -23.0929 -21.0526,
+                          -230.842 -23.0929 -21.0498,
+                          -268.262 -22.6787 19.0607,
+                          -277.775 -22.7271 14.3125,
+                          -268.262 -22.6787 19.0607,
+                          -277.775 -18.7273 14.2713,
+                          -258.858 -23.0945 -21.3414,
+                          -256.569 -23.0944 -21.3176,
+                          -268.262 -22.6787 19.0607,
+                          -254.651 -23.0982 -21.6783,
+                          -268.262 -22.6787 19.0607,
+                          -256.569 -23.0944 -21.3176,
+                          -267.786 -23.1065 -22.5502,
+                          -258.858 -23.0945 -21.3414,
+                          -268.262 -22.6787 19.0607,
+                          -275.442 -23.1549 -27.2987,
+                          -267.786 -23.1065 -22.5502,
+                          -268.262 -22.6787 19.0607,
+                          -277.775 -22.7271 14.3125,
+                          -275.442 -23.1549 -27.2987,
+                          -268.262 -22.6787 19.0607,
+                          -233.024 -23.0969 -21.4531,
+                          -231.114 -23.0929 -21.0526,
+                          -268.262 -22.6787 19.0607,
+                          -234.634 -23.1082 -22.5537,
+                          -233.024 -23.0969 -21.4531,
+                          -268.262 -22.6787 19.0607,
+                          -240.932 -23.1739 -28.9833,
+                          -234.634 -23.1082 -22.5537,
+                          -268.262 -22.6787 19.0607,
+                          -243.748 -23.1862 -30.1842,
+                          -240.932 -23.1739 -28.9833,
+                          -268.262 -22.6787 19.0607,
+                          -246.588 -23.1743 -29.0422,
+                          -243.748 -23.1862 -30.1842,
+                          -268.262 -22.6787 19.0607,
+                          -253.018 -23.1092 -22.7451,
+                          -246.588 -23.1743 -29.0422,
+                          -268.262 -22.6787 19.0607,
+                          -254.651 -23.0982 -21.6783,
+                          -253.018 -23.1092 -22.7451,
+                          -268.262 -22.6787 19.0607,
+                          -275.442 -19.1552 -27.3398,
+                          -277.775 -18.7273 14.2713,
+                          -268.262 -18.6789 19.0196,
+                          -267.786 -19.1067 -22.5913,
+                          -275.442 -19.1552 -27.3398,
+                          -268.262 -18.6789 19.0196,
+                          -277.772 37.2698 13.6957,
+                          -268.259 33.3183 18.4851,
+                          -268.259 37.3181 18.444,
+                          -277.772 33.27 13.7368,
+                          -268.259 33.3183 18.4851,
+                          -277.772 37.2698 13.6957,
+                          -267.783 32.8905 -23.1258,
+                          -258.855 32.9025 -21.9171,
+                          -268.259 33.3183 18.4851,
+                          -275.44 32.8421 -27.8743,
+                          -267.783 32.8905 -23.1258,
+                          -268.259 33.3183 18.4851,
+                          -277.772 33.27 13.7368,
+                          -275.44 32.8421 -27.8743,
+                          -268.259 33.3183 18.4851,
+                          -275.439 36.8419 -27.9155,
+                          -277.772 37.2698 13.6957,
+                          -268.259 37.3181 18.444,
+                          -267.783 36.8903 -23.1669,
+                          -275.439 36.8419 -27.9155,
+                          -268.259 37.3181 18.444,
+                          -231.114 -19.0931 -21.0937,
+                          -230.839 36.9039 -21.6666,
+                          -230.842 -23.0929 -21.0498,
+                          -231.114 -23.0929 -21.0526,
+                          -231.114 -19.0931 -21.0937,
+                          -230.842 -23.0929 -21.0498,
+                          -282.857 36.9211 -20.2439,
+                          -285.089 37.1908 5.97712,
+                          -277.772 37.2698 13.6957,
+                          -277.772 33.27 13.7368,
+                          -277.772 37.2698 13.6957,
+                          -285.089 37.1908 5.97712,
+                          -275.439 36.8419 -27.9155,
+                          -278.841 36.8084 -31.1843,
+                          -277.772 37.2698 13.6957,
+                          -280.821 36.8856 -23.6869,
+                          -277.772 37.2698 13.6957,
+                          -278.841 36.8084 -31.1843,
+                          -282.857 36.9211 -20.2439,
+                          -277.772 37.2698 13.6957,
+                          -280.821 36.8856 -23.6869,
+                          -288.82 36.8852 -23.7702,
+                          -289.323 37.0907 -3.77536,
+                          -285.089 37.1908 5.97712,
+                          -285.089 33.191 6.01824,
+                          -285.089 37.1908 5.97712,
+                          -289.323 37.0907 -3.77536,
+                          -286.856 36.9209 -20.2855,
+                          -288.82 36.8852 -23.7702,
+                          -285.089 37.1908 5.97712,
+                          -282.857 36.9211 -20.2439,
+                          -286.856 36.9209 -20.2855,
+                          -285.089 37.1908 5.97712,
+                          -277.772 33.27 13.7368,
+                          -285.089 37.1908 5.97712,
+                          -285.089 33.191 6.01824,
+                          -292.391 36.8219 -29.9386,
+                          -293.83 36.8974 -22.5997,
+                          -289.323 37.0907 -3.77536,
+                          -293.83 32.8976 -22.5586,
+                          -289.323 37.0907 -3.77536,
+                          -293.83 36.8974 -22.5997,
+                          -288.82 36.8852 -23.7702,
+                          -292.391 36.8219 -29.9386,
+                          -289.323 37.0907 -3.77536,
+                          -289.323 33.0909 -3.73424,
+                          -289.323 37.0907 -3.77536,
+                          -293.83 32.8976 -22.5586,
+                          -285.089 33.191 6.01824,
+                          -289.323 37.0907 -3.77536,
+                          -289.323 33.0909 -3.73424,
+                          -293.83 32.8976 -22.5586,
+                          -293.83 36.8974 -22.5997,
+                          -292.391 36.8219 -29.9386,
+                          -286.784 36.8497 -27.2132,
+                          -285.9 36.7834 -33.6566,
+                          -292.391 36.8219 -29.9386,
+                          -292.392 32.8221 -29.8974,
+                          -292.391 36.8219 -29.9386,
+                          -285.9 36.7834 -33.6566,
+                          -288.82 36.8852 -23.7702,
+                          -286.784 36.8497 -27.2132,
+                          -292.391 36.8219 -29.9386,
+                          -293.83 32.8976 -22.5586,
+                          -292.391 36.8219 -29.9386,
+                          -292.392 32.8221 -29.8974,
+                          -280.821 36.8856 -23.6869,
+                          -278.841 36.8084 -31.1843,
+                          -285.9 36.7834 -33.6566,
+                          -285.9 32.7836 -33.6155,
+                          -285.9 36.7834 -33.6566,
+                          -278.841 36.8084 -31.1843,
+                          -282.785 36.8499 -27.1716,
+                          -280.821 36.8856 -23.6869,
+                          -285.9 36.7834 -33.6566,
+                          -286.784 36.8497 -27.2132,
+                          -282.785 36.8499 -27.1716,
+                          -285.9 36.7834 -33.6566,
+                          -292.392 32.8221 -29.8974,
+                          -285.9 36.7834 -33.6566,
+                          -285.9 32.7836 -33.6155,
+                          -275.44 32.8421 -27.8743,
+                          -278.841 36.8084 -31.1843,
+                          -275.439 36.8419 -27.9155,
+                          -278.842 32.8087 -31.1432,
+                          -278.841 36.8084 -31.1843,
+                          -275.44 32.8421 -27.8743,
+                          -285.9 32.7836 -33.6155,
+                          -278.841 36.8084 -31.1843,
+                          -278.842 32.8087 -31.1432,
+                          -275.44 32.8421 -27.8743,
+                          -275.439 36.8419 -27.9155,
+                          -267.783 36.8903 -23.1669,
+                          -267.783 32.8905 -23.1258,
+                          -267.783 36.8903 -23.1669,
+                          -258.855 36.9023 -21.9582,
+                          -275.44 32.8421 -27.8743,
+                          -267.783 36.8903 -23.1669,
+                          -267.783 32.8905 -23.1258,
+                          -267.783 32.8905 -23.1258,
+                          -258.855 36.9023 -21.9582,
+                          -258.855 32.9025 -21.9171,
+                          -280.821 32.8858 -23.6458,
+                          -280.821 36.8856 -23.6869,
+                          -282.785 36.8499 -27.1716,
+                          -282.858 32.9213 -20.2027,
+                          -282.857 36.9211 -20.2439,
+                          -280.821 36.8856 -23.6869,
+                          -282.858 32.9213 -20.2027,
+                          -280.821 36.8856 -23.6869,
+                          -280.821 32.8858 -23.6458,
+                          -282.786 32.8501 -27.1304,
+                          -282.785 36.8499 -27.1716,
+                          -286.784 36.8497 -27.2132,
+                          -282.786 32.8501 -27.1304,
+                          -280.821 32.8858 -23.6458,
+                          -282.785 36.8499 -27.1716,
+                          -286.784 32.8499 -27.1721,
+                          -286.784 36.8497 -27.2132,
+                          -288.82 36.8852 -23.7702,
+                          -282.786 32.8501 -27.1304,
+                          -286.784 36.8497 -27.2132,
+                          -286.784 32.8499 -27.1721,
+                          -288.821 32.8854 -23.729,
+                          -288.82 36.8852 -23.7702,
+                          -286.856 36.9209 -20.2855,
+                          -286.784 32.8499 -27.1721,
+                          -288.82 36.8852 -23.7702,
+                          -288.821 32.8854 -23.729,
+                          -286.856 32.9211 -20.2444,
+                          -286.856 36.9209 -20.2855,
+                          -282.857 36.9211 -20.2439,
+                          -288.821 32.8854 -23.729,
+                          -286.856 36.9209 -20.2855,
+                          -286.856 32.9211 -20.2444,
+                          -286.856 32.9211 -20.2444,
+                          -282.857 36.9211 -20.2439,
+                          -282.858 32.9213 -20.2027,
+                          -277.772 33.27 13.7368,
+                          -278.842 32.8087 -31.1432,
+                          -275.44 32.8421 -27.8743,
+                          -282.786 32.8501 -27.1304,
+                          -285.9 32.7836 -33.6155,
+                          -278.842 32.8087 -31.1432,
+                          -277.772 33.27 13.7368,
+                          -285.089 33.191 6.01824,
+                          -278.842 32.8087 -31.1432,
+                          -280.821 32.8858 -23.6458,
+                          -278.842 32.8087 -31.1432,
+                          -285.089 33.191 6.01824,
+                          -282.786 32.8501 -27.1304,
+                          -278.842 32.8087 -31.1432,
+                          -280.821 32.8858 -23.6458,
+                          -288.821 32.8854 -23.729,
+                          -292.392 32.8221 -29.8974,
+                          -285.9 32.7836 -33.6155,
+                          -286.784 32.8499 -27.1721,
+                          -288.821 32.8854 -23.729,
+                          -285.9 32.7836 -33.6155,
+                          -282.786 32.8501 -27.1304,
+                          -286.784 32.8499 -27.1721,
+                          -285.9 32.7836 -33.6155,
+                          -289.323 33.0909 -3.73424,
+                          -293.83 32.8976 -22.5586,
+                          -292.392 32.8221 -29.8974,
+                          -288.821 32.8854 -23.729,
+                          -289.323 33.0909 -3.73424,
+                          -292.392 32.8221 -29.8974,
+                          -286.856 32.9211 -20.2444,
+                          -285.089 33.191 6.01824,
+                          -289.323 33.0909 -3.73424,
+                          -288.821 32.8854 -23.729,
+                          -286.856 32.9211 -20.2444,
+                          -289.323 33.0909 -3.73424,
+                          -282.858 32.9213 -20.2027,
+                          -280.821 32.8858 -23.6458,
+                          -285.089 33.191 6.01824,
+                          -286.856 32.9211 -20.2444,
+                          -282.858 32.9213 -20.2027,
+                          -285.089 33.191 6.01824,
+                          -285.902 -19.2137 -33.081,
+                          -282.788 -19.1472 -26.5959,
+                          -280.824 -19.1114 -23.1112,
+                          -280.824 -23.1112 -23.0701,
+                          -280.824 -19.1114 -23.1112,
+                          -282.788 -19.1472 -26.5959,
+                          -277.775 -18.7273 14.2713,
+                          -280.824 -19.1114 -23.1112,
+                          -282.86 -19.0759 -19.6682,
+                          -282.86 -23.0757 -19.6271,
+                          -282.86 -19.0759 -19.6682,
+                          -280.824 -19.1114 -23.1112,
+                          -278.844 -19.1886 -30.6086,
+                          -280.824 -19.1114 -23.1112,
+                          -277.775 -18.7273 14.2713,
+                          -278.844 -19.1886 -30.6086,
+                          -285.902 -19.2137 -33.081,
+                          -280.824 -19.1114 -23.1112,
+                          -282.86 -23.0757 -19.6271,
+                          -280.824 -19.1114 -23.1112,
+                          -280.824 -23.1112 -23.0701,
+                          -285.902 -19.2137 -33.081,
+                          -286.787 -19.1474 -26.6375,
+                          -282.788 -19.1472 -26.5959,
+                          -282.788 -23.1469 -26.5548,
+                          -282.788 -19.1472 -26.5959,
+                          -286.787 -19.1474 -26.6375,
+                          -282.788 -23.1469 -26.5548,
+                          -280.824 -23.1112 -23.0701,
+                          -282.788 -19.1472 -26.5959,
+                          -292.394 -19.1751 -29.3629,
+                          -288.823 -19.1119 -23.1945,
+                          -286.787 -19.1474 -26.6375,
+                          -286.787 -23.1472 -26.5964,
+                          -286.787 -19.1474 -26.6375,
+                          -288.823 -19.1119 -23.1945,
+                          -285.902 -19.2137 -33.081,
+                          -292.394 -19.1751 -29.3629,
+                          -286.787 -19.1474 -26.6375,
+                          -282.788 -23.1469 -26.5548,
+                          -286.787 -19.1474 -26.6375,
+                          -286.787 -23.1472 -26.5964,
+                          -285.092 -18.8063 6.55277,
+                          -286.859 -19.0762 -19.7098,
+                          -288.823 -19.1119 -23.1945,
+                          -288.823 -23.1117 -23.1534,
+                          -288.823 -19.1119 -23.1945,
+                          -286.859 -19.0762 -19.7098,
+                          -289.326 -18.9063 -3.19971,
+                          -285.092 -18.8063 6.55277,
+                          -288.823 -19.1119 -23.1945,
+                          -292.394 -19.1751 -29.3629,
+                          -289.326 -18.9063 -3.19971,
+                          -288.823 -19.1119 -23.1945,
+                          -286.787 -23.1472 -26.5964,
+                          -288.823 -19.1119 -23.1945,
+                          -288.823 -23.1117 -23.1534,
+                          -285.092 -18.8063 6.55277,
+                          -282.86 -19.0759 -19.6682,
+                          -286.859 -19.0762 -19.7098,
+                          -286.859 -23.076 -19.6687,
+                          -286.859 -19.0762 -19.7098,
+                          -282.86 -19.0759 -19.6682,
+                          -288.823 -23.1117 -23.1534,
+                          -286.859 -19.0762 -19.7098,
+                          -286.859 -23.076 -19.6687,
+                          -285.092 -18.8063 6.55277,
+                          -277.775 -18.7273 14.2713,
+                          -282.86 -19.0759 -19.6682,
+                          -286.859 -23.076 -19.6687,
+                          -282.86 -19.0759 -19.6682,
+                          -282.86 -23.0757 -19.6271,
+                          -277.775 -22.7271 14.3125,
+                          -277.775 -18.7273 14.2713,
+                          -285.092 -18.8063 6.55277,
+                          -275.442 -19.1552 -27.3398,
+                          -278.844 -19.1886 -30.6086,
+                          -277.775 -18.7273 14.2713,
+                          -285.092 -22.8061 6.59389,
+                          -285.092 -18.8063 6.55277,
+                          -289.326 -18.9063 -3.19971,
+                          -277.775 -22.7271 14.3125,
+                          -285.092 -18.8063 6.55277,
+                          -285.092 -22.8061 6.59389,
+                          -292.394 -19.1751 -29.3629,
+                          -293.833 -19.0996 -22.0241,
+                          -289.326 -18.9063 -3.19971,
+                          -293.833 -23.0994 -21.9829,
+                          -289.326 -18.9063 -3.19971,
+                          -293.833 -19.0996 -22.0241,
+                          -289.326 -22.9061 -3.15859,
+                          -289.326 -18.9063 -3.19971,
+                          -293.833 -23.0994 -21.9829,
+                          -285.092 -22.8061 6.59389,
+                          -289.326 -18.9063 -3.19971,
+                          -289.326 -22.9061 -3.15859,
+                          -293.833 -23.0994 -21.9829,
+                          -293.833 -19.0996 -22.0241,
+                          -292.394 -19.1751 -29.3629,
+                          -292.394 -23.1749 -29.3218,
+                          -292.394 -19.1751 -29.3629,
+                          -285.902 -19.2137 -33.081,
+                          -293.833 -23.0994 -21.9829,
+                          -292.394 -19.1751 -29.3629,
+                          -292.394 -23.1749 -29.3218,
+                          -285.903 -23.2135 -33.0399,
+                          -285.902 -19.2137 -33.081,
+                          -278.844 -19.1886 -30.6086,
+                          -292.394 -23.1749 -29.3218,
+                          -285.902 -19.2137 -33.081,
+                          -285.903 -23.2135 -33.0399,
+                          -275.442 -23.1549 -27.2987,
+                          -278.844 -19.1886 -30.6086,
+                          -275.442 -19.1552 -27.3398,
+                          -278.844 -23.1884 -30.5675,
+                          -278.844 -19.1886 -30.6086,
+                          -275.442 -23.1549 -27.2987,
+                          -285.903 -23.2135 -33.0399,
+                          -278.844 -19.1886 -30.6086,
+                          -278.844 -23.1884 -30.5675,
+                          -275.442 -23.1549 -27.2987,
+                          -275.442 -19.1552 -27.3398,
+                          -267.786 -19.1067 -22.5913,
+                          -267.786 -23.1065 -22.5502,
+                          -267.786 -19.1067 -22.5913,
+                          -258.857 -19.0947 -21.3826,
+                          -275.442 -23.1549 -27.2987,
+                          -267.786 -19.1067 -22.5913,
+                          -267.786 -23.1065 -22.5502,
+                          -256.569 -23.0944 -21.3176,
+                          -258.857 -19.0947 -21.3826,
+                          -256.569 -19.0946 -21.3587,
+                          -258.858 -23.0945 -21.3414,
+                          -258.857 -19.0947 -21.3826,
+                          -256.569 -23.0944 -21.3176,
+                          -267.786 -23.1065 -22.5502,
+                          -258.857 -19.0947 -21.3826,
+                          -258.858 -23.0945 -21.3414,
+                          -256.569 -23.0944 -21.3176,
+                          -256.569 -19.0946 -21.3587,
+                          -254.651 -19.0984 -21.7194,
+                          -254.651 -23.0982 -21.6783,
+                          -254.651 -19.0984 -21.7194,
+                          -253.018 -19.1094 -22.7862,
+                          -254.651 -23.0982 -21.6783,
+                          -256.569 -23.0944 -21.3176,
+                          -254.651 -19.0984 -21.7194,
+                          -253.018 -23.1092 -22.7451,
+                          -253.018 -19.1094 -22.7862,
+                          -246.588 -19.1745 -29.0833,
+                          -254.651 -23.0982 -21.6783,
+                          -253.018 -19.1094 -22.7862,
+                          -253.018 -23.1092 -22.7451,
+                          -246.588 -23.1743 -29.0422,
+                          -246.588 -19.1745 -29.0833,
+                          -243.748 -19.1864 -30.2253,
+                          -253.018 -23.1092 -22.7451,
+                          -246.588 -19.1745 -29.0833,
+                          -246.588 -23.1743 -29.0422,
+                          -243.748 -23.1862 -30.1842,
+                          -243.748 -19.1864 -30.2253,
+                          -240.932 -19.1742 -29.0244,
+                          -246.588 -23.1743 -29.0422,
+                          -243.748 -19.1864 -30.2253,
+                          -243.748 -23.1862 -30.1842,
+                          -240.932 -23.1739 -28.9833,
+                          -240.932 -19.1742 -29.0244,
+                          -234.634 -19.1084 -22.5949,
+                          -243.748 -23.1862 -30.1842,
+                          -240.932 -19.1742 -29.0244,
+                          -240.932 -23.1739 -28.9833,
+                          -234.634 -23.1082 -22.5537,
+                          -234.634 -19.1084 -22.5949,
+                          -233.023 -19.0971 -21.4942,
+                          -240.932 -23.1739 -28.9833,
+                          -234.634 -19.1084 -22.5949,
+                          -234.634 -23.1082 -22.5537,
+                          -233.024 -23.0969 -21.4531,
+                          -233.023 -19.0971 -21.4942,
+                          -231.114 -19.0931 -21.0937,
+                          -234.634 -23.1082 -22.5537,
+                          -233.023 -19.0971 -21.4942,
+                          -233.024 -23.0969 -21.4531,
+                          -233.024 -23.0969 -21.4531,
+                          -231.114 -19.0931 -21.0937,
+                          -231.114 -23.0929 -21.0526,
+                          -285.092 -22.8061 6.59389,
+                          -282.86 -23.0757 -19.6271,
+                          -280.824 -23.1112 -23.0701,
+                          -278.844 -23.1884 -30.5675,
+                          -280.824 -23.1112 -23.0701,
+                          -282.788 -23.1469 -26.5548,
+                          -285.092 -22.8061 6.59389,
+                          -280.824 -23.1112 -23.0701,
+                          -278.844 -23.1884 -30.5675,
+                          -285.092 -22.8061 6.59389,
+                          -286.859 -23.076 -19.6687,
+                          -282.86 -23.0757 -19.6271,
+                          -289.326 -22.9061 -3.15859,
+                          -288.823 -23.1117 -23.1534,
+                          -286.859 -23.076 -19.6687,
+                          -285.092 -22.8061 6.59389,
+                          -289.326 -22.9061 -3.15859,
+                          -286.859 -23.076 -19.6687,
+                          -285.903 -23.2135 -33.0399,
+                          -286.787 -23.1472 -26.5964,
+                          -288.823 -23.1117 -23.1534,
+                          -292.394 -23.1749 -29.3218,
+                          -285.903 -23.2135 -33.0399,
+                          -288.823 -23.1117 -23.1534,
+                          -289.326 -22.9061 -3.15859,
+                          -292.394 -23.1749 -29.3218,
+                          -288.823 -23.1117 -23.1534,
+                          -285.903 -23.2135 -33.0399,
+                          -282.788 -23.1469 -26.5548,
+                          -286.787 -23.1472 -26.5964,
+                          -285.903 -23.2135 -33.0399,
+                          -278.844 -23.1884 -30.5675,
+                          -282.788 -23.1469 -26.5548,
+                          -277.775 -22.7271 14.3125,
+                          -278.844 -23.1884 -30.5675,
+                          -275.442 -23.1549 -27.2987,
+                          -277.775 -22.7271 14.3125,
+                          -285.092 -22.8061 6.59389,
+                          -278.844 -23.1884 -30.5675,
+                          -289.326 -22.9061 -3.15859,
+                          -293.833 -23.0994 -21.9829,
+                          -292.394 -23.1749 -29.3218 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0 0 1
+    }
+    Separator {
+        Normal {
+            vector      [ -0.278798 0.81795 -0.50322,
+                          -0.265906 0.835696 -0.480528,
+                          -0.272395 0.826913 -0.491951,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.339823 0.715451 -0.61045,
+                          -0.265906 0.835696 -0.480528,
+                          -0.278798 0.81795 -0.50322,
+                          0.00447263 -0.905381 -0.424576,
+                          0.00374681 -0.934977 -0.354688,
+                          0.00574087 -0.837254 -0.546785,
+                          0.00447263 -0.905381 -0.424576,
+                          0.00574087 -0.837254 -0.546785,
+                          0.00645217 -0.788199 -0.615386,
+                          0.00752979 -0.694528 -0.719427,
+                          0.00645217 -0.788199 -0.615386,
+                          0.00574087 -0.837254 -0.546785,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.00226882 0.977164 0.212475,
+                          -0.00556992 0.84779 0.530303,
+                          -0.00141746 0.991432 0.130614,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.00645217 0.788199 0.615386,
+                          -0.00556992 0.84779 0.530303,
+                          -0.00226882 0.977164 0.212475,
+                          -0.00743344 0.704043 0.710119,
+                          -0.00556992 0.84779 0.530303,
+                          -0.00645217 0.788199 0.615386,
+                          -0.34678 0.701462 -0.622651,
+                          -0.339823 0.715451 -0.61045,
+                          -0.278798 0.81795 -0.50322,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          0.0023639 0.972589 -0.232519,
+                          -0.00141746 0.991432 0.130614,
+                          0.00299069 0.956219 -0.292637,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.00226882 0.977164 0.212475,
+                          -0.00141746 0.991432 0.130614,
+                          0.0023639 0.972589 -0.232519,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          0.00652842 0.775381 -0.63146,
+                          0.00299069 0.956219 -0.292637,
+                          0.00685939 0.748497 -0.663103,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          0.0023639 0.972589 -0.232519,
+                          0.00299069 0.956219 -0.292637,
+                          0.00652842 0.775381 -0.63146,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          0.0093999 0.424599 -0.905333,
+                          0.00685939 0.748497 -0.663103,
+                          0.00949068 0.405724 -0.913946,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          0.00652842 0.775381 -0.63146,
+                          0.00685939 0.748497 -0.663103,
+                          0.0093999 0.424599 -0.905333,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          0.0093999 0.424599 -0.905333,
+                          0.00949068 0.405724 -0.913946,
+                          0.0104096 -0.0102794 -0.999893,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          0.0093999 0.424599 -0.905333,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0104096 -0.0102794 -0.999893,
+                          -0.0104096 0.0102794 0.999893,
+                          -0.0104096 0.0102794 0.999893,
+                          -0.0101782 -0.204252 0.978865,
+                          -0.0101595 -0.212487 0.977111,
+                          -0.0101782 -0.204252 0.978865,
+                          -0.00947391 -0.409288 0.912356,
+                          -0.0104096 0.0102794 0.999893,
+                          -0.0101782 -0.204252 0.978865,
+                          -0.0101595 -0.212487 0.977111,
+                          -0.0093999 -0.424599 0.905333,
+                          -0.00947391 -0.409288 0.912356,
+                          -0.00832943 -0.595303 0.803458,
+                          -0.0101595 -0.212487 0.977111,
+                          -0.00947391 -0.409288 0.912356,
+                          -0.0093999 -0.424599 0.905333,
+                          -0.00816897 -0.61542 0.788157,
+                          -0.00832943 -0.595303 0.803458,
+                          -0.00679798 -0.753657 0.657232,
+                          -0.0093999 -0.424599 0.905333,
+                          -0.00832943 -0.595303 0.803458,
+                          -0.00816897 -0.61542 0.788157,
+                          -0.00652842 -0.775381 0.63146,
+                          -0.00679798 -0.753657 0.657232,
+                          -0.00495073 -0.876994 0.480475,
+                          -0.00816897 -0.61542 0.788157,
+                          -0.00679798 -0.753657 0.657232,
+                          -0.00652842 -0.775381 0.63146,
+                          -0.0045605 -0.896461 0.443099,
+                          -0.00495073 -0.876994 0.480475,
+                          -0.00287349 -0.959587 0.281398,
+                          -0.00652842 -0.775381 0.63146,
+                          -0.00495073 -0.876994 0.480475,
+                          -0.0045605 -0.896461 0.443099,
+                          -0.0023639 -0.972589 0.232519,
+                          -0.00287349 -0.959587 0.281398,
+                          -0.000662791 -0.997599 0.0692501,
+                          -0.0045605 -0.896461 0.443099,
+                          -0.00287349 -0.959587 0.281398,
+                          -0.0023639 -0.972589 0.232519,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -0.000662791 -0.997599 0.0692501,
+                          0.00157868 -0.989267 -0.146113,
+                          -0.0023639 -0.972589 0.232519,
+                          -0.000662791 -0.997599 0.0692501,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          0.00226882 -0.977164 -0.212475,
+                          0.00157868 -0.989267 -0.146113,
+                          0.00374681 -0.934977 -0.354688,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          0.00157868 -0.989267 -0.146113,
+                          0.00226882 -0.977164 -0.212475,
+                          0.00226882 -0.977164 -0.212475,
+                          0.00374681 -0.934977 -0.354688,
+                          0.00447263 -0.905381 -0.424576,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0101378 -0.232531 -0.972536,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.00966057 -0.377688 -0.925883,
+                          0.0101378 -0.232531 -0.972536,
+                          0.00935759 -0.443122 -0.896412,
+                          0.0101779 -0.215349 -0.976484,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0101378 -0.232531 -0.972536,
+                          0.00966057 -0.377688 -0.925883,
+                          0.0101779 -0.215349 -0.976484,
+                          0.0101378 -0.232531 -0.972536,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.00868841 -0.555454 -0.831502,
+                          0.00935759 -0.443122 -0.896412,
+                          0.00810817 -0.631494 -0.775339,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.00868841 -0.555454 -0.831502,
+                          0.00966057 -0.377688 -0.925883,
+                          0.00935759 -0.443122 -0.896412,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.00752979 -0.694528 -0.719427,
+                          0.00810817 -0.631494 -0.775339,
+                          0.00645217 -0.788199 -0.615386,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.00752979 -0.694528 -0.719427,
+                          0.00868841 -0.555454 -0.831502,
+                          0.00810817 -0.631494 -0.775339,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          -0.00743344 0.704043 0.710119,
+                          -0.00645217 0.788199 0.615386,
+                          -0.00935759 0.443122 0.896412,
+                          -0.00960197 0.391385 0.920177,
+                          -0.00935759 0.443122 0.896412,
+                          -0.0104096 0.0102794 0.999893,
+                          -0.00860852 0.566868 0.823764,
+                          -0.00743344 0.704043 0.710119,
+                          -0.00935759 0.443122 0.896412,
+                          -0.00960197 0.391385 0.920177,
+                          -0.00860852 0.566868 0.823764,
+                          -0.00935759 0.443122 0.896412,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          4.87624e-05 0.999947 -0.0102795,
+                          -0.0101627 0.222037 0.974985,
+                          -0.00960197 0.391385 0.920177,
+                          -0.0104096 0.0102794 0.999893,
+                          -0.0104096 0.0102794 0.999893,
+                          -0.0101627 0.222037 0.974985,
+                          -0.0104096 0.0102794 0.999893,
+                          -0.48492 0.14742 -0.862044,
+                          -0.48492 0.14742 -0.862044,
+                          -0.464257 0.316731 -0.827132,
+                          -0.436266 0.450631 -0.778848,
+                          -0.464257 0.316731 -0.827132,
+                          -0.43611 0.451248 -0.778578,
+                          -0.464444 0.315619 -0.827452,
+                          -0.464257 0.316731 -0.827132,
+                          -0.436266 0.450631 -0.778848,
+                          -0.48492 0.14742 -0.862044,
+                          -0.464257 0.316731 -0.827132,
+                          -0.464444 0.315619 -0.827452,
+                          -0.393364 0.591104 -0.704173,
+                          -0.43611 0.451248 -0.778578,
+                          -0.390404 0.599149 -0.699003,
+                          -0.436266 0.450631 -0.778848,
+                          -0.43611 0.451248 -0.778578,
+                          -0.393364 0.591104 -0.704173,
+                          -0.34678 0.701462 -0.622651,
+                          -0.390404 0.599149 -0.699003,
+                          -0.339823 0.715451 -0.61045,
+                          -0.393364 0.591104 -0.704173,
+                          -0.390404 0.599149 -0.699003,
+                          -0.34678 0.701462 -0.622651 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -230.822 -32.6199 -22.9346,
+                          -230.807 -33.4754 -24.381,
+                          -230.814 -33.052 -23.6529,
+                          -230.886 -37.3357 -16.7921,
+                          -230.814 -33.052 -23.6529,
+                          -230.807 -33.4754 -24.381,
+                          -204.574 -27.8362 -30.9281,
+                          -230.807 -33.4754 -24.381,
+                          -230.822 -32.6199 -22.9346,
+                          -69.3657 -36.157 -17.8721,
+                          -230.886 -37.3357 -16.7921,
+                          -230.807 -33.4754 -24.381,
+                          -69.3657 -36.157 -17.8721,
+                          -230.807 -33.4754 -24.381,
+                          -69.2876 -31.5291 -25.4086,
+                          -204.574 -27.8362 -30.9281,
+                          -69.2876 -31.5291 -25.4086,
+                          -230.807 -33.4754 -24.381,
+                          -230.886 -37.3357 -16.7921,
+                          -230.822 -32.6199 -22.9346,
+                          -230.814 -33.052 -23.6529,
+                          -230.971 -39.4796 -8.55514,
+                          -230.98 -38.078 -7.74696,
+                          -230.822 -32.6199 -22.9346,
+                          -69.4562 -37.5263 -9.17716,
+                          -230.822 -32.6199 -22.9346,
+                          -230.98 -38.078 -7.74696,
+                          -230.886 -37.3357 -16.7921,
+                          -230.971 -39.4796 -8.55514,
+                          -230.822 -32.6199 -22.9346,
+                          -69.2972 -30.3468 -24.4856,
+                          -230.822 -32.6199 -22.9346,
+                          -69.4562 -37.5263 -9.17716,
+                          -205.723 -27.1561 -29.507,
+                          -230.822 -32.6199 -22.9346,
+                          -69.2972 -30.3468 -24.4856,
+                          -205.723 -27.1561 -29.507,
+                          -204.574 -27.8362 -30.9281,
+                          -230.822 -32.6199 -22.9346,
+                          -231.147 -38.3071 8.33337,
+                          -231.147 -36.7398 8.33829,
+                          -230.98 -38.078 -7.74696,
+                          -69.6323 -37.3524 7.73497,
+                          -230.98 -38.078 -7.74696,
+                          -231.147 -36.7398 8.33829,
+                          -231.06 -39.8091 -0.0486542,
+                          -231.147 -38.3071 8.33337,
+                          -230.98 -38.078 -7.74696,
+                          -230.971 -39.4796 -8.55514,
+                          -231.06 -39.8091 -0.0486542,
+                          -230.98 -38.078 -7.74696,
+                          -69.4562 -37.5263 -9.17716,
+                          -230.98 -38.078 -7.74696,
+                          -69.6323 -37.3524 7.73497,
+                          -231.229 -35.045 16.1956,
+                          -231.294 -28.8475 22.4139,
+                          -231.147 -36.7398 8.33829,
+                          -69.7905 -29.8597 22.8926,
+                          -231.147 -36.7398 8.33829,
+                          -231.294 -28.8475 22.4139,
+                          -231.147 -38.3071 8.33337,
+                          -231.229 -35.045 16.1956,
+                          -231.147 -36.7398 8.33829,
+                          -69.6323 -37.3524 7.73497,
+                          -231.147 -36.7398 8.33829,
+                          -69.7905 -29.8597 22.8926,
+                          -231.363 -23.9176 28.9541,
+                          -231.394 -15.8208 31.947,
+                          -231.294 -28.8475 22.4139,
+                          -69.8996 -16.5287 33.3007,
+                          -231.294 -28.8475 22.4139,
+                          -231.394 -15.8208 31.947,
+                          -231.302 -30.1741 23.1766,
+                          -231.363 -23.9176 28.9541,
+                          -231.294 -28.8475 22.4139,
+                          -231.229 -35.045 16.1956,
+                          -231.302 -30.1741 23.1766,
+                          -231.294 -28.8475 22.4139,
+                          -69.7905 -29.8597 22.8926,
+                          -231.294 -28.8475 22.4139,
+                          -69.8996 -16.5287 33.3007,
+                          -231.408 -16.5701 33.2551,
+                          -231.429 -0.013281 35.2129,
+                          -231.394 -15.8208 31.947,
+                          -69.8996 -16.5287 33.3007,
+                          -231.394 -15.8208 31.947,
+                          -231.429 -0.013281 35.2129,
+                          -231.363 -23.9176 28.9541,
+                          -231.408 -16.5701 33.2551,
+                          -231.394 -15.8208 31.947,
+                          -231.436 -8.47294 35.8817,
+                          -231.445 0.00213815 36.7127,
+                          -231.429 -0.013281 35.2129,
+                          -69.9536 0.0115452 38.3939,
+                          -231.429 -0.013281 35.2129,
+                          -231.445 0.00213815 36.7127,
+                          -231.408 -16.5701 33.2551,
+                          -231.436 -8.47294 35.8817,
+                          -231.429 -0.013281 35.2129,
+                          -69.938 -0.00387389 36.894,
+                          -231.429 -0.013281 35.2129,
+                          -69.9536 0.0115452 38.3939,
+                          -69.8996 -16.5287 33.3007,
+                          -231.429 -0.013281 35.2129,
+                          -69.938 -0.00387389 36.894,
+                          -69.9536 0.0115452 38.3939,
+                          -231.445 0.00213815 36.7127,
+                          -231.436 -8.47294 35.8817,
+                          -69.9437 -8.78897 37.4935,
+                          -231.436 -8.47294 35.8817,
+                          -231.408 -16.5701 33.2551,
+                          -69.9536 0.0115452 38.3939,
+                          -231.436 -8.47294 35.8817,
+                          -69.9437 -8.78897 37.4935,
+                          -69.9137 -17.1656 34.6587,
+                          -231.408 -16.5701 33.2551,
+                          -231.363 -23.9176 28.9541,
+                          -69.9437 -8.78897 37.4935,
+                          -231.408 -16.5701 33.2551,
+                          -69.9137 -17.1656 34.6587,
+                          -69.8651 -24.7025 30.031,
+                          -231.363 -23.9176 28.9541,
+                          -231.302 -30.1741 23.1766,
+                          -69.9137 -17.1656 34.6587,
+                          -231.363 -23.9176 28.9541,
+                          -69.8651 -24.7025 30.031,
+                          -69.8003 -31.0228 23.8397,
+                          -231.302 -30.1741 23.1766,
+                          -231.229 -35.045 16.1956,
+                          -69.8651 -24.7025 30.031,
+                          -231.302 -30.1741 23.1766,
+                          -69.8003 -31.0228 23.8397,
+                          -69.7225 -35.8047 16.3999,
+                          -231.229 -35.045 16.1956,
+                          -231.147 -38.3071 8.33337,
+                          -69.8003 -31.0228 23.8397,
+                          -231.229 -35.045 16.1956,
+                          -69.7225 -35.8047 16.3999,
+                          -69.6358 -38.8113 8.0838,
+                          -231.147 -38.3071 8.33337,
+                          -231.06 -39.8091 -0.0486542,
+                          -69.7225 -35.8047 16.3999,
+                          -231.147 -38.3071 8.33337,
+                          -69.6358 -38.8113 8.0838,
+                          -69.5443 -39.8924 -0.695876,
+                          -231.06 -39.8091 -0.0486542,
+                          -230.971 -39.4796 -8.55514,
+                          -69.6358 -38.8113 8.0838,
+                          -231.06 -39.8091 -0.0486542,
+                          -69.5443 -39.8924 -0.695876,
+                          -69.4528 -38.992 -9.49592,
+                          -230.971 -39.4796 -8.55514,
+                          -230.886 -37.3357 -16.7921,
+                          -69.5443 -39.8924 -0.695876,
+                          -230.971 -39.4796 -8.55514,
+                          -69.4528 -38.992 -9.49592,
+                          -69.4528 -38.992 -9.49592,
+                          -230.886 -37.3357 -16.7921,
+                          -69.3657 -36.157 -17.8721,
+                          -69.1468 -0.78511 -39.0978,
+                          -69.142 -9.58068 -39.5166,
+                          -69.1312 -0.800529 -40.5977,
+                          -157.39 -0.80567 -41.5165,
+                          -69.1312 -0.800529 -40.5977,
+                          -69.142 -9.58068 -39.5166,
+                          -157.39 -0.80567 -41.5165,
+                          -69.1468 -0.78511 -39.0978,
+                          -69.1312 -0.800529 -40.5977,
+                          -69.1468 -0.78511 -39.0978,
+                          -69.1728 -17.8972 -36.5102,
+                          -69.142 -9.58068 -39.5166,
+                          -171.765 -15.3191 -38.7424,
+                          -69.142 -9.58068 -39.5166,
+                          -69.1728 -17.8972 -36.5102,
+                          -162.894 -8.90623 -40.649,
+                          -157.39 -0.80567 -41.5165,
+                          -69.142 -9.58068 -39.5166,
+                          -171.765 -15.3191 -38.7424,
+                          -162.894 -8.90623 -40.649,
+                          -69.142 -9.58068 -39.5166,
+                          -69.1868 -17.2326 -35.1656,
+                          -69.2221 -25.3374 -31.7286,
+                          -69.1728 -17.8972 -36.5102,
+                          -187.07 -22.3418 -35.1733,
+                          -69.1728 -17.8972 -36.5102,
+                          -69.2221 -25.3374 -31.7286,
+                          -69.1468 -0.78511 -39.0978,
+                          -69.1868 -17.2326 -35.1656,
+                          -69.1728 -17.8972 -36.5102,
+                          -187.07 -22.3418 -35.1733,
+                          -171.765 -15.3191 -38.7424,
+                          -69.1728 -17.8972 -36.5102,
+                          -69.2972 -30.3468 -24.4856,
+                          -69.2876 -31.5291 -25.4086,
+                          -69.2221 -25.3374 -31.7286,
+                          -204.574 -27.8362 -30.9281,
+                          -69.2221 -25.3374 -31.7286,
+                          -69.2876 -31.5291 -25.4086,
+                          -69.1868 -17.2326 -35.1656,
+                          -69.2972 -30.3468 -24.4856,
+                          -69.2221 -25.3374 -31.7286,
+                          -204.574 -27.8362 -30.9281,
+                          -187.07 -22.3418 -35.1733,
+                          -69.2221 -25.3374 -31.7286,
+                          -69.2972 -30.3468 -24.4856,
+                          -69.3657 -36.157 -17.8721,
+                          -69.2876 -31.5291 -25.4086,
+                          -69.4562 -37.5263 -9.17716,
+                          -69.4528 -38.992 -9.49592,
+                          -69.3657 -36.157 -17.8721,
+                          -69.2972 -30.3468 -24.4856,
+                          -69.4562 -37.5263 -9.17716,
+                          -69.3657 -36.157 -17.8721,
+                          -69.4562 -37.5263 -9.17716,
+                          -69.5443 -39.8924 -0.695876,
+                          -69.4528 -38.992 -9.49592,
+                          -69.6323 -37.3524 7.73497,
+                          -69.6358 -38.8113 8.0838,
+                          -69.5443 -39.8924 -0.695876,
+                          -69.4562 -37.5263 -9.17716,
+                          -69.6323 -37.3524 7.73497,
+                          -69.5443 -39.8924 -0.695876,
+                          -69.7905 -29.8597 22.8926,
+                          -69.7225 -35.8047 16.3999,
+                          -69.6358 -38.8113 8.0838,
+                          -69.6323 -37.3524 7.73497,
+                          -69.7905 -29.8597 22.8926,
+                          -69.6358 -38.8113 8.0838,
+                          -69.7905 -29.8597 22.8926,
+                          -69.8003 -31.0228 23.8397,
+                          -69.7225 -35.8047 16.3999,
+                          -69.8996 -16.5287 33.3007,
+                          -69.8651 -24.7025 30.031,
+                          -69.8003 -31.0228 23.8397,
+                          -69.7905 -29.8597 22.8926,
+                          -69.8996 -16.5287 33.3007,
+                          -69.8003 -31.0228 23.8397,
+                          -69.8996 -16.5287 33.3007,
+                          -69.9137 -17.1656 34.6587,
+                          -69.8651 -24.7025 30.031,
+                          -69.938 -0.00387389 36.894,
+                          -69.9437 -8.78897 37.4935,
+                          -69.9137 -17.1656 34.6587,
+                          -69.8996 -16.5287 33.3007,
+                          -69.938 -0.00387389 36.894,
+                          -69.9137 -17.1656 34.6587,
+                          -69.938 -0.00387389 36.894,
+                          -69.9536 0.0115452 38.3939,
+                          -69.9437 -8.78897 37.4935,
+                          -205.723 -27.1561 -29.507,
+                          -69.2972 -30.3468 -24.4856,
+                          -69.1868 -17.2326 -35.1656,
+                          -174.533 -15.2733 -37.1654,
+                          -69.1868 -17.2326 -35.1656,
+                          -69.1468 -0.78511 -39.0978,
+                          -189.184 -21.9425 -33.6538,
+                          -205.723 -27.1561 -29.507,
+                          -69.1868 -17.2326 -35.1656,
+                          -174.533 -15.2733 -37.1654,
+                          -189.184 -21.9425 -33.6538,
+                          -69.1868 -17.2326 -35.1656,
+                          -160.003 -0.790402 -40.0437,
+                          -69.1468 -0.78511 -39.0978,
+                          -157.39 -0.80567 -41.5165,
+                          -165.511 -8.83752 -39.1544,
+                          -174.533 -15.2733 -37.1654,
+                          -69.1468 -0.78511 -39.0978,
+                          -160.003 -0.790402 -40.0437,
+                          -165.511 -8.83752 -39.1544,
+                          -69.1468 -0.78511 -39.0978,
+                          -160.003 -0.790402 -40.0437,
+                          -157.39 -0.80567 -41.5165,
+                          -162.894 -8.90623 -40.649,
+                          -174.533 -15.2733 -37.1654,
+                          -162.894 -8.90623 -40.649,
+                          -171.765 -15.3191 -38.7424,
+                          -165.511 -8.83752 -39.1544,
+                          -162.894 -8.90623 -40.649,
+                          -174.533 -15.2733 -37.1654,
+                          -160.003 -0.790402 -40.0437,
+                          -162.894 -8.90623 -40.649,
+                          -165.511 -8.83752 -39.1544,
+                          -189.184 -21.9425 -33.6538,
+                          -171.765 -15.3191 -38.7424,
+                          -187.07 -22.3418 -35.1733,
+                          -174.533 -15.2733 -37.1654,
+                          -171.765 -15.3191 -38.7424,
+                          -189.184 -21.9425 -33.6538,
+                          -205.723 -27.1561 -29.507,
+                          -187.07 -22.3418 -35.1733,
+                          -204.574 -27.8362 -30.9281,
+                          -189.184 -21.9425 -33.6538,
+                          -187.07 -22.3418 -35.1733,
+                          -205.723 -27.1561 -29.507 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+    Separator {
+        Normal {
+            vector      [ -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          4.87624e-05 0.999947 -0.0102795,
+                          0.00262292 0.966311 -0.257366,
+                          -0.00113692 0.994613 0.103647,
+                          -0.408177 -0.56317 -0.718493,
+                          -0.379766 -0.640721 -0.667273,
+                          -0.372635 -0.657915 -0.65444,
+                          0.00402864 0.919897 -0.392139,
+                          0.00262292 0.966311 -0.257366,
+                          4.87624e-05 0.999947 -0.0102795,
+                          0.0054507 0.849011 -0.528346,
+                          0.00262292 0.966311 -0.257366,
+                          0.00402864 0.919897 -0.392139,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.00393854 0.927764 0.373145,
+                          -0.00113692 0.994613 0.103647,
+                          -0.0047477 0.892475 0.451071,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          4.87624e-05 0.999947 -0.0102795,
+                          -0.00113692 0.994613 0.103647,
+                          -0.00393854 0.927764 0.373145,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.00732624 0.714338 0.699762,
+                          -0.0047477 0.892475 0.451071,
+                          -0.00773588 0.673285 0.739343,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.00393854 0.927764 0.373145,
+                          -0.0047477 0.892475 0.451071,
+                          -0.00732624 0.714338 0.699762,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.00959858 0.39216 0.919847,
+                          -0.00773588 0.673285 0.739343,
+                          -0.00970952 0.365779 0.930651,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.00732624 0.714338 0.699762,
+                          -0.00773588 0.673285 0.739343,
+                          -0.00959858 0.39216 0.919847,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.00959858 0.39216 0.919847,
+                          -0.00970952 0.365779 0.930651,
+                          -0.0104096 0.0102794 0.999893,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -0.999946 -5.82483e-05 -0.0104096,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -0.00959858 0.39216 0.919847,
+                          -0.0104096 0.0102794 0.999893,
+                          -0.0104096 0.0102794 0.999893,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.00936197 -0.442261 -0.896838,
+                          0.00935759 -0.443122 -0.896412,
+                          0.00936197 -0.442261 -0.896838,
+                          0.00646795 -0.787008 -0.616909,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.00936197 -0.442261 -0.896838,
+                          0.00935759 -0.443122 -0.896412,
+                          0.00645217 -0.788199 -0.615386,
+                          0.00646795 -0.787008 -0.616909,
+                          0.00229843 -0.97654 -0.215324,
+                          0.00935759 -0.443122 -0.896412,
+                          0.00646795 -0.787008 -0.616909,
+                          0.00645217 -0.788199 -0.615386,
+                          0.00226882 -0.977164 -0.212475,
+                          0.00229843 -0.97654 -0.215324,
+                          -0.00232429 -0.97349 0.228719,
+                          0.00645217 -0.788199 -0.615386,
+                          0.00229843 -0.97654 -0.215324,
+                          0.00226882 -0.977164 -0.212475,
+                          -0.408177 -0.56317 -0.718493,
+                          -0.386684 -0.623251 -0.67973,
+                          -0.379766 -0.640721 -0.667273,
+                          0.00226882 -0.977164 -0.212475,
+                          -0.00232429 -0.97349 0.228719,
+                          -0.0023639 -0.972589 0.232519,
+                          -0.0034619 -0.941205 0.337818,
+                          -0.0023639 -0.972589 0.232519,
+                          -0.00232429 -0.97349 0.228719,
+                          -0.395861 -0.598752 -0.696269,
+                          -0.386684 -0.623251 -0.67973,
+                          -0.408177 -0.56317 -0.718493,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.0054507 0.849011 -0.528346,
+                          0.00402864 0.919897 -0.392139,
+                          0.0073952 0.699801 -0.7143,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.00869931 0.544518 -0.838704,
+                          0.0073952 0.699801 -0.7143,
+                          0.0096359 0.373166 -0.927714,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.00736211 0.703012 -0.71114,
+                          0.0054507 0.849011 -0.528346,
+                          0.0073952 0.699801 -0.7143,
+                          0.00869931 0.544518 -0.838704,
+                          0.00736211 0.703012 -0.71114,
+                          0.0073952 0.699801 -0.7143,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.0100562 0.253008 -0.967412,
+                          0.0096359 0.373166 -0.927714,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.999946 5.82483e-05 0.0104096,
+                          0.00954419 0.39409 -0.919022,
+                          0.00869931 0.544518 -0.838704,
+                          0.0096359 0.373166 -0.927714,
+                          0.0100562 0.253008 -0.967412,
+                          0.00954419 0.39409 -0.919022,
+                          0.0096359 0.373166 -0.927714,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          0.0103227 0.123491 -0.992292,
+                          0.0100562 0.253008 -0.967412,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0104096 -0.0102794 -0.999893,
+                          0.0103227 0.123491 -0.992292,
+                          0.0104096 -0.0102794 -0.999893,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -4.87624e-05 -0.999947 0.0102795,
+                          -0.0104096 0.0102794 0.999893,
+                          -0.0104096 0.0102794 0.999893,
+                          -0.0093999 -0.424599 0.905333,
+                          -0.00855008 -0.565814 0.824488,
+                          -0.0093999 -0.424599 0.905333,
+                          -0.00652842 -0.775381 0.63146,
+                          -0.0102402 -0.17424 0.98465,
+                          -0.0104096 0.0102794 0.999893,
+                          -0.0093999 -0.424599 0.905333,
+                          -0.00968579 -0.361194 0.932441,
+                          -0.0102402 -0.17424 0.98465,
+                          -0.0093999 -0.424599 0.905333,
+                          -0.00855008 -0.565814 0.824488,
+                          -0.00968579 -0.361194 0.932441,
+                          -0.0093999 -0.424599 0.905333,
+                          -0.00472358 -0.888568 0.45872,
+                          -0.00652842 -0.775381 0.63146,
+                          -0.0023639 -0.972589 0.232519,
+                          -0.00659644 -0.770038 0.637964,
+                          -0.00855008 -0.565814 0.824488,
+                          -0.00652842 -0.775381 0.63146,
+                          -0.00472358 -0.888568 0.45872,
+                          -0.00659644 -0.770038 0.637964,
+                          -0.00652842 -0.775381 0.63146,
+                          -0.0034619 -0.941205 0.337818,
+                          -0.00472358 -0.888568 0.45872,
+                          -0.0023639 -0.972589 0.232519,
+                          -0.409766 -0.558325 -0.721363,
+                          -0.408177 -0.56317 -0.718493,
+                          -0.441939 -0.44367 -0.779645,
+                          -0.395861 -0.598752 -0.696269,
+                          -0.408177 -0.56317 -0.718493,
+                          -0.409766 -0.558325 -0.721363,
+                          -0.436329 -0.466432 -0.769453,
+                          -0.441939 -0.44367 -0.779645,
+                          -0.467631 -0.313162 -0.82659,
+                          -0.409766 -0.558325 -0.721363,
+                          -0.441939 -0.44367 -0.779645,
+                          -0.436329 -0.466432 -0.769453,
+                          -0.46861 -0.306877 -0.828391,
+                          -0.467631 -0.313162 -0.82659,
+                          -0.482946 -0.188791 -0.855056,
+                          -0.436329 -0.466432 -0.769453,
+                          -0.467631 -0.313162 -0.82659,
+                          -0.46861 -0.306877 -0.828391,
+                          -0.486317 -0.146109 -0.86148,
+                          -0.482946 -0.188791 -0.855056,
+                          -0.48999 -0.0717777 -0.868768,
+                          -0.46861 -0.306877 -0.828391,
+                          -0.482946 -0.188791 -0.855056,
+                          -0.486317 -0.146109 -0.86148,
+                          -0.490931 0.0013717 -0.871197,
+                          -0.48999 -0.0717777 -0.868768,
+                          -0.490462 0.0359206 -0.870722,
+                          -0.486317 -0.146109 -0.86148,
+                          -0.48999 -0.0717777 -0.868768,
+                          -0.490931 0.0013717 -0.871197,
+                          -0.490931 0.0013717 -0.871197,
+                          -0.490462 0.0359206 -0.870722,
+                          -0.48492 0.14742 -0.862044,
+                          -0.490931 0.0013717 -0.871197,
+                          -0.48492 0.14742 -0.862044,
+                          -0.48492 0.14742 -0.862044 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -230.937 37.4253 -12.264,
+                          -231.079 39.3806 1.36284,
+                          -230.929 38.2485 -13.0777,
+                          -69.5405 39.6032 -1.51309,
+                          -230.929 38.2485 -13.0777,
+                          -231.079 39.3806 1.36284,
+                          -205.008 33.5581 -23.6483,
+                          -230.937 37.4253 -12.264,
+                          -230.929 38.2485 -13.0777,
+                          -69.3813 36.4009 -16.7881,
+                          -230.929 38.2485 -13.0777,
+                          -69.5405 39.6032 -1.51309,
+                          -205.008 33.5581 -23.6483,
+                          -230.929 38.2485 -13.0777,
+                          -69.3813 36.4009 -16.7881,
+                          -231.121 36.7044 5.39919,
+                          -231.224 35.2951 15.2598,
+                          -231.079 39.3806 1.36284,
+                          -69.7 36.7156 13.8245,
+                          -231.079 39.3806 1.36284,
+                          -231.224 35.2951 15.2598,
+                          -230.945 36.5887 -11.4744,
+                          -231.121 36.7044 5.39919,
+                          -231.079 39.3806 1.36284,
+                          -230.937 37.4253 -12.264,
+                          -230.945 36.5887 -11.4744,
+                          -231.079 39.3806 1.36284,
+                          -69.5405 39.6032 -1.51309,
+                          -231.079 39.3806 1.36284,
+                          -69.7 36.7156 13.8245,
+                          -231.279 29.5024 20.6595,
+                          -231.343 26.5275 26.7907,
+                          -231.224 35.2951 15.2598,
+                          -69.8355 28.1781 26.8894,
+                          -231.224 35.2951 15.2598,
+                          -231.343 26.5275 26.7907,
+                          -231.121 36.7044 5.39919,
+                          -231.279 29.5024 20.6595,
+                          -231.224 35.2951 15.2598,
+                          -69.7 36.7156 13.8245,
+                          -231.224 35.2951 15.2598,
+                          -69.8355 28.1781 26.8894,
+                          -231.389 16.4019 31.2966,
+                          -231.422 14.2272 34.443,
+                          -231.343 26.5275 26.7907,
+                          -69.9264 15.2909 35.6923,
+                          -231.343 26.5275 26.7907,
+                          -231.422 14.2272 34.443,
+                          -231.279 29.5024 20.6595,
+                          -231.389 16.4019 31.2966,
+                          -231.343 26.5275 26.7907,
+                          -69.8355 28.1781 26.8894,
+                          -231.343 26.5275 26.7907,
+                          -69.9264 15.2909 35.6923,
+                          -231.429 -0.013281 35.2129,
+                          -231.45 0.00727786 37.2127,
+                          -231.422 14.2272 34.443,
+                          -69.9264 15.2909 35.6923,
+                          -231.422 14.2272 34.443,
+                          -231.45 0.00727786 37.2127,
+                          -231.389 16.4019 31.2966,
+                          -231.429 -0.013281 35.2129,
+                          -231.422 14.2272 34.443,
+                          -69.938 -0.00387389 36.894,
+                          -231.45 0.00727786 37.2127,
+                          -231.429 -0.013281 35.2129,
+                          -69.9264 15.2909 35.6923,
+                          -231.45 0.00727786 37.2127,
+                          -69.9588 0.016685 38.8938,
+                          -69.938 -0.00387389 36.894,
+                          -69.9588 0.016685 38.8938,
+                          -231.45 0.00727786 37.2127,
+                          -69.938 -0.00387389 36.894,
+                          -231.429 -0.013281 35.2129,
+                          -231.389 16.4019 31.2966,
+                          -69.898 16.4436 32.9618,
+                          -231.389 16.4019 31.2966,
+                          -231.279 29.5024 20.6595,
+                          -69.938 -0.00387389 36.894,
+                          -231.389 16.4019 31.2966,
+                          -69.898 16.4436 32.9618,
+                          -69.7876 29.5578 22.2817,
+                          -231.279 29.5024 20.6595,
+                          -231.121 36.7044 5.39919,
+                          -69.898 16.4436 32.9618,
+                          -231.279 29.5024 20.6595,
+                          -69.7876 29.5578 22.2817,
+                          -69.6286 36.7373 6.97333,
+                          -231.121 36.7044 5.39919,
+                          -230.945 36.5887 -11.4744,
+                          -69.7876 29.5578 22.2817,
+                          -231.121 36.7044 5.39919,
+                          -69.6286 36.7373 6.97333,
+                          -205.008 33.5581 -23.6483,
+                          -230.945 36.5887 -11.4744,
+                          -230.937 37.4253 -12.264,
+                          -69.6286 36.7373 6.97333,
+                          -230.945 36.5887 -11.4744,
+                          -69.4526 36.5634 -9.9388,
+                          -221.905 35.3624 -15.5265,
+                          -69.4526 36.5634 -9.9388,
+                          -230.945 36.5887 -11.4744,
+                          -221.905 35.3624 -15.5265,
+                          -230.945 36.5887 -11.4744,
+                          -205.008 33.5581 -23.6483,
+                          -69.938 -0.00387389 36.894,
+                          -69.9264 15.2909 35.6923,
+                          -69.9588 0.016685 38.8938,
+                          -69.898 16.4436 32.9618,
+                          -69.8355 28.1781 26.8894,
+                          -69.9264 15.2909 35.6923,
+                          -69.938 -0.00387389 36.894,
+                          -69.898 16.4436 32.9618,
+                          -69.9264 15.2909 35.6923,
+                          -69.7876 29.5578 22.2817,
+                          -69.7 36.7156 13.8245,
+                          -69.8355 28.1781 26.8894,
+                          -69.898 16.4436 32.9618,
+                          -69.7876 29.5578 22.2817,
+                          -69.8355 28.1781 26.8894,
+                          -69.6286 36.7373 6.97333,
+                          -69.5405 39.6032 -1.51309,
+                          -69.7 36.7156 13.8245,
+                          -69.7876 29.5578 22.2817,
+                          -69.6286 36.7373 6.97333,
+                          -69.7 36.7156 13.8245,
+                          -69.4526 36.5634 -9.9388,
+                          -69.3813 36.4009 -16.7881,
+                          -69.5405 39.6032 -1.51309,
+                          -69.6286 36.7373 6.97333,
+                          -69.4526 36.5634 -9.9388,
+                          -69.5405 39.6032 -1.51309,
+                          -69.2943 29.0707 -25.0964,
+                          -69.2466 27.5966 -29.6747,
+                          -69.3813 36.4009 -16.7881,
+                          -205.008 33.5581 -23.6483,
+                          -69.3813 36.4009 -16.7881,
+                          -69.2466 27.5966 -29.6747,
+                          -69.4526 36.5634 -9.9388,
+                          -69.2943 29.0707 -25.0964,
+                          -69.3813 36.4009 -16.7881,
+                          -69.1852 15.7397 -35.5045,
+                          -69.157 14.5311 -38.2109,
+                          -69.2466 27.5966 -29.6747,
+                          -171.534 21.3803 -35.7155,
+                          -69.2466 27.5966 -29.6747,
+                          -69.157 14.5311 -38.2109,
+                          -69.2943 29.0707 -25.0964,
+                          -69.1852 15.7397 -35.5045,
+                          -69.2466 27.5966 -29.6747,
+                          -185.562 27.7192 -30.7583,
+                          -205.008 33.5581 -23.6483,
+                          -69.2466 27.5966 -29.6747,
+                          -171.534 21.3803 -35.7155,
+                          -185.562 27.7192 -30.7583,
+                          -69.2466 27.5966 -29.6747,
+                          -69.1468 -0.78511 -39.0978,
+                          -69.126 -0.805669 -41.0976,
+                          -69.157 14.5311 -38.2109,
+                          -157.981 9.72065 -40.7232,
+                          -69.157 14.5311 -38.2109,
+                          -69.126 -0.805669 -41.0976,
+                          -69.1852 15.7397 -35.5045,
+                          -69.1468 -0.78511 -39.0978,
+                          -69.157 14.5311 -38.2109,
+                          -162.833 15.3637 -38.8379,
+                          -171.534 21.3803 -35.7155,
+                          -69.157 14.5311 -38.2109,
+                          -157.981 9.72065 -40.7232,
+                          -162.833 15.3637 -38.8379,
+                          -69.157 14.5311 -38.2109,
+                          -160.003 -0.790402 -40.0437,
+                          -69.126 -0.805669 -41.0976,
+                          -69.1468 -0.78511 -39.0978,
+                          -156.061 4.5401 -41.6986,
+                          -157.981 9.72065 -40.7232,
+                          -69.126 -0.805669 -41.0976,
+                          -156.518 -0.81076 -42.0074,
+                          -156.061 4.5401 -41.6986,
+                          -69.126 -0.805669 -41.0976,
+                          -160.003 -0.790402 -40.0437,
+                          -156.518 -0.81076 -42.0074,
+                          -69.126 -0.805669 -41.0976,
+                          -160.003 -0.790402 -40.0437,
+                          -69.1468 -0.78511 -39.0978,
+                          -69.1852 15.7397 -35.5045,
+                          -175.202 21.1003 -33.5358,
+                          -69.1852 15.7397 -35.5045,
+                          -69.2943 29.0707 -25.0964,
+                          -159.963 6.22134 -39.464,
+                          -160.003 -0.790402 -40.0437,
+                          -69.1852 15.7397 -35.5045,
+                          -164.451 13.3253 -37.5265,
+                          -159.963 6.22134 -39.464,
+                          -69.1852 15.7397 -35.5045,
+                          -175.202 21.1003 -33.5358,
+                          -164.451 13.3253 -37.5265,
+                          -69.1852 15.7397 -35.5045,
+                          -211.145 33.3628 -20.0093,
+                          -69.2943 29.0707 -25.0964,
+                          -69.4526 36.5634 -9.9388,
+                          -194.004 28.8597 -26.6428,
+                          -175.202 21.1003 -33.5358,
+                          -69.2943 29.0707 -25.0964,
+                          -211.145 33.3628 -20.0093,
+                          -194.004 28.8597 -26.6428,
+                          -69.2943 29.0707 -25.0964,
+                          -221.905 35.3624 -15.5265,
+                          -211.145 33.3628 -20.0093,
+                          -69.4526 36.5634 -9.9388,
+                          -211.145 33.3628 -20.0093,
+                          -205.008 33.5581 -23.6483,
+                          -185.562 27.7192 -30.7583,
+                          -221.905 35.3624 -15.5265,
+                          -205.008 33.5581 -23.6483,
+                          -211.145 33.3628 -20.0093,
+                          -194.004 28.8597 -26.6428,
+                          -185.562 27.7192 -30.7583,
+                          -171.534 21.3803 -35.7155,
+                          -211.145 33.3628 -20.0093,
+                          -185.562 27.7192 -30.7583,
+                          -194.004 28.8597 -26.6428,
+                          -175.202 21.1003 -33.5358,
+                          -171.534 21.3803 -35.7155,
+                          -162.833 15.3637 -38.8379,
+                          -194.004 28.8597 -26.6428,
+                          -171.534 21.3803 -35.7155,
+                          -175.202 21.1003 -33.5358,
+                          -164.451 13.3253 -37.5265,
+                          -162.833 15.3637 -38.8379,
+                          -157.981 9.72065 -40.7232,
+                          -175.202 21.1003 -33.5358,
+                          -162.833 15.3637 -38.8379,
+                          -164.451 13.3253 -37.5265,
+                          -159.963 6.22134 -39.464,
+                          -157.981 9.72065 -40.7232,
+                          -156.061 4.5401 -41.6986,
+                          -164.451 13.3253 -37.5265,
+                          -157.981 9.72065 -40.7232,
+                          -159.963 6.22134 -39.464,
+                          -159.963 6.22134 -39.464,
+                          -156.061 4.5401 -41.6986,
+                          -156.518 -0.81076 -42.0074,
+                          -159.963 6.22134 -39.464,
+                          -156.518 -0.81076 -42.0074,
+                          -160.003 -0.790402 -40.0437 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/neck/neck_pitch_link.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/neck/neck_pitch_link.iv
new file mode 100644
index 0000000000000000000000000000000000000000..60ecb2f600678c147c78d848eccb844ed1279127
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/neck/neck_pitch_link.iv
@@ -0,0 +1,2880 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.4 0.4 0.4
+    }
+    Separator {
+        Normal {
+            vector      [ 0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          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.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          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,
+                          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,
+                          -1.22461e-16 0 -1,
+                          -1.22461e-16 0 -1,
+                          0.707107 0 -0.707107,
+                          -0.707107 0 -0.707107,
+                          -0.707107 0 -0.707107,
+                          -1.22461e-16 0 -1,
+                          -0.707107 0 -0.707107,
+                          -1.22461e-16 0 -1,
+                          -1.22461e-16 0 -1,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          1 0 -1.83691e-16,
+                          0.707107 0 -0.707107,
+                          -1.22461e-16 0 -1,
+                          0.707107 0 -0.707107,
+                          1 0 -1.83691e-16,
+                          1 0 -1.83691e-16,
+                          0.707107 0 0.707107,
+                          0.707107 0 -0.707107,
+                          1 0 -1.83691e-16,
+                          1 0 -1.83691e-16,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          2.44921e-16 0 1,
+                          1 0 -1.83691e-16,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          0 0 1,
+                          0 0 1,
+                          -0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          2.44921e-16 0 1,
+                          2.44921e-16 0 1,
+                          -0.707107 0 0.707107,
+                          -0.707107 0 0.707107,
+                          -1 0 6.12303e-17,
+                          0 0 1,
+                          -0.707107 0 0.707107,
+                          -0.707107 0 0.707107,
+                          -1 0 6.12303e-17,
+                          -1 0 6.12303e-17,
+                          -0.707107 0 -0.707107,
+                          -0.707107 0 0.707107,
+                          -1 0 6.12303e-17,
+                          -1 0 6.12303e-17,
+                          -1 0 6.12303e-17,
+                          -0.707107 0 -0.707107,
+                          -0.707107 0 -0.707107,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -1.22461e-16 0 -1,
+                          -1.22461e-16 0 -1,
+                          0.707107 0 -0.707107,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.707107 0 -0.707107,
+                          -0.707107 0 -0.707107,
+                          -1.22461e-16 0 -1,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.707107 0 -0.707107,
+                          -1.22461e-16 0 -1,
+                          -1.22461e-16 0 -1,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          1 0 -1.83691e-16,
+                          0.707107 0 -0.707107,
+                          -1.22461e-16 0 -1,
+                          0.707107 0 -0.707107,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          1 0 -1.83691e-16,
+                          1 0 -1.83691e-16,
+                          0.707107 0 0.707107,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.707107 0 -0.707107,
+                          1 0 -1.83691e-16,
+                          1 0 -1.83691e-16,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          2.44921e-16 0 1,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          1 0 -1.83691e-16,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 0 1,
+                          0 0 1,
+                          -0.707107 0 0.707107,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.707107 0 0.707107,
+                          2.44921e-16 0 1,
+                          2.44921e-16 0 1,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.707107 0 0.707107,
+                          -0.707107 0 0.707107,
+                          -1 0 6.12303e-17,
+                          0 0 1,
+                          -0.707107 0 0.707107,
+                          -0.707107 0 0.707107,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -1 0 6.12303e-17,
+                          -1 0 6.12303e-17,
+                          -0.707107 0 -0.707107,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.707107 0 0.707107,
+                          -1 0 6.12303e-17,
+                          -1 0 6.12303e-17,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -1 0 6.12303e-17,
+                          -0.707107 0 -0.707107,
+                          -0.707107 0 -0.707107,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -1.22461e-16 0 -1,
+                          -1.22461e-16 0 -1,
+                          0.707107 0 -0.707107,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.707107 0 -0.707107,
+                          -0.707107 0 -0.707107,
+                          -1.22461e-16 0 -1,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.707107 0 -0.707107,
+                          -1.22461e-16 0 -1,
+                          -1.22461e-16 0 -1,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          1 0 -1.83691e-16,
+                          0.707107 0 -0.707107,
+                          -1.22461e-16 0 -1,
+                          0.707107 0 -0.707107,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          1 0 -1.83691e-16,
+                          1 0 -1.83691e-16,
+                          0.707107 0 0.707107,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.707107 0 -0.707107,
+                          1 0 -1.83691e-16,
+                          1 0 -1.83691e-16,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          2.44921e-16 0 1,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          1 0 -1.83691e-16,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 0 1,
+                          0 0 1,
+                          -0.707107 0 0.707107,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.707107 0 0.707107,
+                          2.44921e-16 0 1,
+                          2.44921e-16 0 1,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.707107 0 0.707107,
+                          -0.707107 0 0.707107,
+                          -1 0 6.12303e-17,
+                          0 0 1,
+                          -0.707107 0 0.707107,
+                          -0.707107 0 0.707107,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -1 0 6.12303e-17,
+                          -1 0 6.12303e-17,
+                          -0.707107 0 -0.707107,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.707107 0 0.707107,
+                          -1 0 6.12303e-17,
+                          -1 0 6.12303e-17,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -1 0 6.12303e-17,
+                          -0.707107 0 -0.707107,
+                          -0.707107 0 -0.707107,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          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,
+                          0 -0.707107 -0.707107,
+                          0 -0.707107 -0.707107,
+                          0 -0.707107 -0.707107,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.707107 -0.707107,
+                          0 -0.707107 -0.707107,
+                          0 -0.707107 -0.707107,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.707107 -0.707107,
+                          0 0.707107 -0.707107,
+                          0 0.707107 -0.707107,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.707107 -0.707107,
+                          0 0.707107 -0.707107,
+                          0 0.707107 -0.707107,
+                          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 -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,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.707107 0.707107,
+                          0 0.707107 0.707107,
+                          0 0.707107 0.707107,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.707107 0.707107,
+                          0 0.707107 0.707107,
+                          0 0.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 -0.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          0 0 -1,
+                          0 0 -1,
+                          0 -0.707107 -0.707107,
+                          0 0.707107 -0.707107,
+                          0 0.707107 -0.707107,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0.707107 -0.707107,
+                          0 0 -1,
+                          0 -0.707107 -0.707107,
+                          0 -0.707107 -0.707107,
+                          0 -1 1.60814e-16,
+                          0 -0.707107 -0.707107,
+                          0 0 -1,
+                          0 -0.707107 -0.707107,
+                          0 -1 -6.12303e-17,
+                          0 -1 1.60814e-16,
+                          0 -0.707107 0.707107,
+                          0 -0.707107 -0.707107,
+                          0 -1 1.60814e-16,
+                          0 -1 -6.12303e-17,
+                          0 -0.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          0 -1.22461e-16 1,
+                          0 -1 -6.12303e-17,
+                          0 -0.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 0.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          0 -1.22461e-16 1,
+                          0 -1.22461e-16 1,
+                          0 0.707107 0.707107,
+                          0 0.707107 0.707107,
+                          0 1 -2.83275e-16,
+                          0 0.707107 0.707107,
+                          0 1.22461e-16 1,
+                          0 0.707107 0.707107,
+                          0 1 -6.12303e-17,
+                          0 1 -2.83275e-16,
+                          0 0.707107 -0.707107,
+                          0 1 -6.12303e-17,
+                          0 0.707107 0.707107,
+                          0 1 -2.83275e-16,
+                          0 0.707107 -0.707107,
+                          0 1 -6.12303e-17,
+                          0 0.707107 -0.707107,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          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 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0.707107 -0.707107,
+                          0 -0.707107 -0.707107,
+                          0 -0.707107 -0.707107,
+                          0 0 -1,
+                          0 -0.707107 -0.707107,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0.707107 -0.707107,
+                          0 0.707107 -0.707107,
+                          0 1 -5.0532e-16,
+                          0 0.707107 -0.707107,
+                          0 0 -1,
+                          0 0.707107 -0.707107,
+                          0 1 -6.12303e-17,
+                          0 1 -5.0532e-16,
+                          0 0.707107 0.707107,
+                          0 0.707107 -0.707107,
+                          0 1 -5.0532e-16,
+                          0 1 -6.12303e-17,
+                          0 0.707107 0.707107,
+                          0 0.707107 0.707107,
+                          0 1.22461e-16 1,
+                          0 1 -6.12303e-17,
+                          0 0.707107 0.707107,
+                          0 0.707107 0.707107,
+                          0 -1.22461e-16 1,
+                          0 -1.22461e-16 1,
+                          0 -0.707107 0.707107,
+                          0 0.707107 0.707107,
+                          0 1.22461e-16 1,
+                          0 1.22461e-16 1,
+                          0 -0.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          0 -1 -6.12303e-17,
+                          0 -1.22461e-16 1,
+                          0 -0.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          0 -1 -6.12303e-17,
+                          0 -1 -6.12303e-17,
+                          0 -0.707107 -0.707107,
+                          0 -0.707107 0.707107,
+                          0 -1 -6.12303e-17,
+                          0 -1 -6.12303e-17,
+                          0 -1 -6.12303e-17,
+                          0 -0.707107 -0.707107,
+                          0 -0.707107 -0.707107,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          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,
+                          -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 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          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.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -1.22461e-16 0 -1,
+                          -1.22461e-16 0 -1,
+                          -0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          -1.22461e-16 0 -1,
+                          0.707107 0 -0.707107,
+                          -1.22461e-16 0 -1,
+                          -1.22461e-16 0 -1,
+                          -0.707107 0 -0.707107,
+                          -0.707107 0 -0.707107,
+                          -1 0 6.12303e-17,
+                          -0.707107 0 -0.707107,
+                          -1.22461e-16 0 -1,
+                          -0.707107 0 -0.707107,
+                          -1 0 6.12303e-17,
+                          -1 0 6.12303e-17,
+                          -0.707107 0 0.707107,
+                          -0.707107 0 -0.707107,
+                          -1 0 6.12303e-17,
+                          -1 0 6.12303e-17,
+                          -0.707107 0 0.707107,
+                          -0.707107 0 0.707107,
+                          0 0 1,
+                          -1 0 6.12303e-17,
+                          -0.707107 0 0.707107,
+                          -0.707107 0 0.707107,
+                          2.44921e-16 0 1,
+                          2.44921e-16 0 1,
+                          0.707107 0 0.707107,
+                          -0.707107 0 0.707107,
+                          0 0 1,
+                          0 0 1,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          1 0 -1.83691e-16,
+                          2.44921e-16 0 1,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          1 0 -1.83691e-16,
+                          1 0 -1.83691e-16,
+                          0.707107 0 -0.707107,
+                          0.707107 0 0.707107,
+                          1 0 -1.83691e-16,
+                          1 0 -1.83691e-16,
+                          1 0 -1.83691e-16,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -1.22461e-16 0 -1,
+                          -1.22461e-16 0 -1,
+                          0.707107 0 -0.707107,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.707107 0 -0.707107,
+                          -0.707107 0 -0.707107,
+                          -1.22461e-16 0 -1,
+                          -0.707107 0 -0.707107,
+                          -1.22461e-16 0 -1,
+                          -1.22461e-16 0 -1,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          1 0 -1.83691e-16,
+                          0.707107 0 -0.707107,
+                          -1.22461e-16 0 -1,
+                          0.707107 0 -0.707107,
+                          1 0 -1.83691e-16,
+                          1 0 -1.83691e-16,
+                          0.707107 0 0.707107,
+                          0.707107 0 -0.707107,
+                          1 0 -1.83691e-16,
+                          1 0 -1.83691e-16,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          2.44921e-16 0 1,
+                          1 0 -1.83691e-16,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 0 1,
+                          0 0 1,
+                          -0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          2.44921e-16 0 1,
+                          2.44921e-16 0 1,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.707107 0 0.707107,
+                          -0.707107 0 0.707107,
+                          -1 0 6.12303e-17,
+                          0 0 1,
+                          -0.707107 0 0.707107,
+                          -0.707107 0 0.707107,
+                          -1 0 6.12303e-17,
+                          -1 0 6.12303e-17,
+                          -0.707107 0 -0.707107,
+                          -0.707107 0 0.707107,
+                          -1 0 6.12303e-17,
+                          -1 0 6.12303e-17,
+                          -1 0 6.12303e-17,
+                          -0.707107 0 -0.707107,
+                          -0.707107 0 -0.707107,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          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.22461e-16 0 -1,
+                          -1.22461e-16 0 -1,
+                          0.707107 0 -0.707107,
+                          -0.707107 0 -0.707107,
+                          -0.707107 0 -0.707107,
+                          -1.22461e-16 0 -1,
+                          -0.707107 0 -0.707107,
+                          -1.22461e-16 0 -1,
+                          -1.22461e-16 0 -1,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          1 0 -1.83691e-16,
+                          0.707107 0 -0.707107,
+                          -1.22461e-16 0 -1,
+                          0.707107 0 -0.707107,
+                          1 0 -1.83691e-16,
+                          1 0 -1.83691e-16,
+                          0.707107 0 0.707107,
+                          0.707107 0 -0.707107,
+                          1 0 -1.83691e-16,
+                          1 0 -1.83691e-16,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          2.44921e-16 0 1,
+                          1 0 -1.83691e-16,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          0 0 1,
+                          0 0 1,
+                          -0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          2.44921e-16 0 1,
+                          2.44921e-16 0 1,
+                          -0.707107 0 0.707107,
+                          -0.707107 0 0.707107,
+                          -1 0 6.12303e-17,
+                          0 0 1,
+                          -0.707107 0 0.707107,
+                          -0.707107 0 0.707107,
+                          -1 0 6.12303e-17,
+                          -1 0 6.12303e-17,
+                          -0.707107 0 -0.707107,
+                          -0.707107 0 0.707107,
+                          -1 0 6.12303e-17,
+                          -1 0 6.12303e-17,
+                          -1 0 6.12303e-17,
+                          -0.707107 0 -0.707107,
+                          -0.707107 0 -0.707107,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -18.5 -30.5 -10,
+                          -18.5 -30.5 10,
+                          8 -30.5 10,
+                          -18.5 -36 10,
+                          8 -30.5 10,
+                          -18.5 -30.5 10,
+                          8 -30.5 -10,
+                          -18.5 -30.5 -10,
+                          8 -30.5 10,
+                          13 -30.5 5,
+                          8 -30.5 -10,
+                          8 -30.5 10,
+                          8 -36 10,
+                          13 -30.5 5,
+                          8 -30.5 10,
+                          -18.5 -36 10,
+                          8 -36 10,
+                          8 -30.5 10,
+                          -18.5 -36 10,
+                          -18.5 -30.5 10,
+                          -18.5 -30.5 -10,
+                          8 -36 -10,
+                          -18.5 -30.5 -10,
+                          8 -30.5 -10,
+                          -18.5 -36 -10,
+                          -18.5 -30.5 -10,
+                          8 -36 -10,
+                          -18.5 -36 10,
+                          -18.5 -30.5 -10,
+                          -18.5 -36 -10,
+                          13 -30.5 5,
+                          13 -30.5 -5,
+                          8 -30.5 -10,
+                          13 -36 -5,
+                          8 -30.5 -10,
+                          13 -30.5 -5,
+                          8 -36 -10,
+                          8 -30.5 -10,
+                          13 -36 -5,
+                          18.5 -30.5 5,
+                          18.5 -30.5 -5,
+                          13 -30.5 -5,
+                          24.5 -36 -5,
+                          13 -30.5 -5,
+                          18.5 -30.5 -5,
+                          13 -30.5 5,
+                          18.5 -30.5 5,
+                          13 -30.5 -5,
+                          13 -36 -5,
+                          13 -30.5 -5,
+                          24.5 -36 -5,
+                          18.5 -11 5,
+                          18.5 -30.5 -5,
+                          18.5 -30.5 5,
+                          18.5 -11 -5,
+                          24.5 -36 -5,
+                          18.5 -30.5 -5,
+                          18.5 -11 5,
+                          18.5 -11 -5,
+                          18.5 -30.5 -5,
+                          13 -36 5,
+                          18.5 -30.5 5,
+                          13 -30.5 5,
+                          24.5 -36 5,
+                          18.5 -30.5 5,
+                          13 -36 5,
+                          24.5 -11 5,
+                          18.5 -30.5 5,
+                          24.5 -36 5,
+                          24.5 -11 5,
+                          18.5 -11 5,
+                          18.5 -30.5 5,
+                          13 -36 5,
+                          13 -30.5 5,
+                          8 -36 10,
+                          13 -36 -5,
+                          13 -36 5,
+                          8 -36 10,
+                          8 -36 -10,
+                          13 -36 -5,
+                          8 -36 10,
+                          6.5 -36 -1.77636e-15,
+                          8 -36 -10,
+                          8 -36 10,
+                          0 -36 6.5,
+                          8 -36 10,
+                          -18.5 -36 10,
+                          4.59619 -36 4.59619,
+                          6.5 -36 -1.77636e-15,
+                          8 -36 10,
+                          0 -36 6.5,
+                          4.59619 -36 4.59619,
+                          8 -36 10,
+                          24.5 -36 -5,
+                          24.5 -36 5,
+                          13 -36 5,
+                          13 -36 -5,
+                          24.5 -36 -5,
+                          13 -36 5,
+                          24.5 -11 -5,
+                          24.5 -36 5,
+                          24.5 -36 -5,
+                          24.5 -11 5,
+                          24.5 -36 5,
+                          24.5 -11 -5,
+                          24.5 -11 -5,
+                          24.5 -36 -5,
+                          18.5 -11 -5,
+                          -4.59619 -36 -4.59619,
+                          -18.5 -36 -10,
+                          8 -36 -10,
+                          4.59619 -36 -4.59619,
+                          0 -36 -6.5,
+                          8 -36 -10,
+                          -4.59619 -36 -4.59619,
+                          8 -36 -10,
+                          0 -36 -6.5,
+                          6.5 -36 -1.77636e-15,
+                          4.59619 -36 -4.59619,
+                          8 -36 -10,
+                          -4.59619 -36 -4.59619,
+                          -18.5 -36 10,
+                          -18.5 -36 -10,
+                          -4.59619 -36 4.59619,
+                          0 -36 6.5,
+                          -18.5 -36 10,
+                          -6.5 -36 0,
+                          -4.59619 -36 4.59619,
+                          -18.5 -36 10,
+                          -4.59619 -36 -4.59619,
+                          -6.5 -36 0,
+                          -18.5 -36 10,
+                          0 -37.5 -6.5,
+                          0 -36 -6.5,
+                          4.59619 -36 -4.59619,
+                          -4.59674 -37.5 -4.59542,
+                          -4.59619 -36 -4.59619,
+                          0 -36 -6.5,
+                          -4.59674 -37.5 -4.59542,
+                          0 -36 -6.5,
+                          0 -37.5 -6.5,
+                          4.59674 -37.5 -4.59542,
+                          4.59619 -36 -4.59619,
+                          6.5 -36 -1.77636e-15,
+                          4.59674 -37.5 -4.59542,
+                          0 -37.5 -6.5,
+                          4.59619 -36 -4.59619,
+                          6.49971 -37.5 -3.88578e-16,
+                          6.5 -36 -1.77636e-15,
+                          4.59619 -36 4.59619,
+                          4.59674 -37.5 -4.59542,
+                          6.5 -36 -1.77636e-15,
+                          6.49971 -37.5 -3.88578e-16,
+                          4.59674 -37.5 4.59542,
+                          4.59619 -36 4.59619,
+                          0 -36 6.5,
+                          6.49971 -37.5 -3.88578e-16,
+                          4.59619 -36 4.59619,
+                          4.59674 -37.5 4.59542,
+                          0 -37.5 6.5,
+                          0 -36 6.5,
+                          -4.59619 -36 4.59619,
+                          4.59674 -37.5 4.59542,
+                          0 -36 6.5,
+                          0 -37.5 6.5,
+                          -4.59674 -37.5 4.59542,
+                          -4.59619 -36 4.59619,
+                          -6.5 -36 0,
+                          0 -37.5 6.5,
+                          -4.59619 -36 4.59619,
+                          -4.59674 -37.5 4.59542,
+                          -6.49971 -37.5 -3.88578e-16,
+                          -6.5 -36 0,
+                          -4.59619 -36 -4.59619,
+                          -4.59674 -37.5 4.59542,
+                          -6.5 -36 0,
+                          -6.49971 -37.5 -3.88578e-16,
+                          -6.49971 -37.5 -3.88578e-16,
+                          -4.59619 -36 -4.59619,
+                          -4.59674 -37.5 -4.59542,
+                          4.59674 -37.5 -4.59542,
+                          3.53532 -37.5 -3.53532,
+                          0 -37.5 -5,
+                          0 -46 -5,
+                          0 -37.5 -5,
+                          3.53532 -37.5 -3.53532,
+                          0 -37.5 -6.5,
+                          0 -37.5 -5,
+                          -3.53532 -37.5 -3.53532,
+                          -3.53532 -46 -3.53532,
+                          -3.53532 -37.5 -3.53532,
+                          0 -37.5 -5,
+                          4.59674 -37.5 -4.59542,
+                          0 -37.5 -5,
+                          0 -37.5 -6.5,
+                          -3.53532 -46 -3.53532,
+                          0 -37.5 -5,
+                          0 -46 -5,
+                          4.59674 -37.5 -4.59542,
+                          5 -37.5 0,
+                          3.53532 -37.5 -3.53532,
+                          3.53532 -46 -3.53532,
+                          3.53532 -37.5 -3.53532,
+                          5 -37.5 0,
+                          3.53532 -46 -3.53532,
+                          0 -46 -5,
+                          3.53532 -37.5 -3.53532,
+                          4.59674 -37.5 4.59542,
+                          3.53532 -37.5 3.53532,
+                          5 -37.5 0,
+                          5 -46 0,
+                          5 -37.5 0,
+                          3.53532 -37.5 3.53532,
+                          6.49971 -37.5 -3.88578e-16,
+                          4.59674 -37.5 4.59542,
+                          5 -37.5 0,
+                          4.59674 -37.5 -4.59542,
+                          6.49971 -37.5 -3.88578e-16,
+                          5 -37.5 0,
+                          3.53532 -46 -3.53532,
+                          5 -37.5 0,
+                          5 -46 0,
+                          0 -37.5 6.5,
+                          0 -37.5 5,
+                          3.53532 -37.5 3.53532,
+                          3.53532 -46 3.53532,
+                          3.53532 -37.5 3.53532,
+                          0 -37.5 5,
+                          4.59674 -37.5 4.59542,
+                          0 -37.5 6.5,
+                          3.53532 -37.5 3.53532,
+                          5 -46 0,
+                          3.53532 -37.5 3.53532,
+                          3.53532 -46 3.53532,
+                          -4.59674 -37.5 4.59542,
+                          -3.53532 -37.5 3.53532,
+                          0 -37.5 5,
+                          0 -46 5,
+                          0 -37.5 5,
+                          -3.53532 -37.5 3.53532,
+                          0 -37.5 6.5,
+                          -4.59674 -37.5 4.59542,
+                          0 -37.5 5,
+                          3.53532 -46 3.53532,
+                          0 -37.5 5,
+                          0 -46 5,
+                          -4.59674 -37.5 4.59542,
+                          -5 -37.5 0,
+                          -3.53532 -37.5 3.53532,
+                          -3.53532 -46 3.53532,
+                          -3.53532 -37.5 3.53532,
+                          -5 -37.5 0,
+                          0 -46 5,
+                          -3.53532 -37.5 3.53532,
+                          -3.53532 -46 3.53532,
+                          -4.59674 -37.5 -4.59542,
+                          -3.53532 -37.5 -3.53532,
+                          -5 -37.5 0,
+                          -5 -46 0,
+                          -5 -37.5 0,
+                          -3.53532 -37.5 -3.53532,
+                          -6.49971 -37.5 -3.88578e-16,
+                          -4.59674 -37.5 -4.59542,
+                          -5 -37.5 0,
+                          -4.59674 -37.5 4.59542,
+                          -6.49971 -37.5 -3.88578e-16,
+                          -5 -37.5 0,
+                          -3.53532 -46 3.53532,
+                          -5 -37.5 0,
+                          -5 -46 0,
+                          -4.59674 -37.5 -4.59542,
+                          0 -37.5 -6.5,
+                          -3.53532 -37.5 -3.53532,
+                          -5 -46 0,
+                          -3.53532 -37.5 -3.53532,
+                          -3.53532 -46 -3.53532,
+                          3.53532 -46 -3.53532,
+                          2.82767 -46 -2.82893,
+                          0 -46 -4,
+                          0 -78 -4,
+                          0 -46 -4,
+                          2.82767 -46 -2.82893,
+                          0 -46 -5,
+                          0 -46 -4,
+                          -2.82767 -46 -2.82893,
+                          -2.82767 -78 -2.82893,
+                          -2.82767 -46 -2.82893,
+                          0 -46 -4,
+                          3.53532 -46 -3.53532,
+                          0 -46 -4,
+                          0 -46 -5,
+                          -2.82767 -78 -2.82893,
+                          0 -46 -4,
+                          0 -78 -4,
+                          3.53532 -46 -3.53532,
+                          3.99968 -46 -3.05311e-16,
+                          2.82767 -46 -2.82893,
+                          2.82767 -78 -2.82893,
+                          2.82767 -46 -2.82893,
+                          3.99968 -46 -3.05311e-16,
+                          2.82767 -78 -2.82893,
+                          0 -78 -4,
+                          2.82767 -46 -2.82893,
+                          3.53532 -46 3.53532,
+                          2.82767 -46 2.82893,
+                          3.99968 -46 -3.05311e-16,
+                          3.99968 -78 -3.05311e-16,
+                          3.99968 -46 -3.05311e-16,
+                          2.82767 -46 2.82893,
+                          5 -46 0,
+                          3.53532 -46 3.53532,
+                          3.99968 -46 -3.05311e-16,
+                          3.53532 -46 -3.53532,
+                          5 -46 0,
+                          3.99968 -46 -3.05311e-16,
+                          2.82767 -78 -2.82893,
+                          3.99968 -46 -3.05311e-16,
+                          3.99968 -78 -3.05311e-16,
+                          0 -46 5,
+                          0 -46 4,
+                          2.82767 -46 2.82893,
+                          2.82767 -78 2.82893,
+                          2.82767 -46 2.82893,
+                          0 -46 4,
+                          3.53532 -46 3.53532,
+                          0 -46 5,
+                          2.82767 -46 2.82893,
+                          3.99968 -78 -3.05311e-16,
+                          2.82767 -46 2.82893,
+                          2.82767 -78 2.82893,
+                          -3.53532 -46 3.53532,
+                          -2.82767 -46 2.82893,
+                          0 -46 4,
+                          0 -78 4,
+                          0 -46 4,
+                          -2.82767 -46 2.82893,
+                          0 -46 5,
+                          -3.53532 -46 3.53532,
+                          0 -46 4,
+                          2.82767 -78 2.82893,
+                          0 -46 4,
+                          0 -78 4,
+                          -3.53532 -46 3.53532,
+                          -3.99968 -46 -3.05311e-16,
+                          -2.82767 -46 2.82893,
+                          -2.82767 -78 2.82893,
+                          -2.82767 -46 2.82893,
+                          -3.99968 -46 -3.05311e-16,
+                          0 -78 4,
+                          -2.82767 -46 2.82893,
+                          -2.82767 -78 2.82893,
+                          -3.53532 -46 -3.53532,
+                          -2.82767 -46 -2.82893,
+                          -3.99968 -46 -3.05311e-16,
+                          -3.99968 -78 -3.05311e-16,
+                          -3.99968 -46 -3.05311e-16,
+                          -2.82767 -46 -2.82893,
+                          -5 -46 0,
+                          -3.53532 -46 -3.53532,
+                          -3.99968 -46 -3.05311e-16,
+                          -3.53532 -46 3.53532,
+                          -5 -46 0,
+                          -3.99968 -46 -3.05311e-16,
+                          -2.82767 -78 2.82893,
+                          -3.99968 -46 -3.05311e-16,
+                          -3.99968 -78 -3.05311e-16,
+                          -3.53532 -46 -3.53532,
+                          0 -46 -5,
+                          -2.82767 -46 -2.82893,
+                          -3.99968 -78 -3.05311e-16,
+                          -2.82767 -46 -2.82893,
+                          -2.82767 -78 -2.82893,
+                          -2.82767 -78 2.82893,
+                          -2.82767 -78 -2.82893,
+                          0 -78 -4,
+                          0 -78 4,
+                          -2.82767 -78 2.82893,
+                          0 -78 -4,
+                          2.82767 -78 -2.82893,
+                          0 -78 4,
+                          0 -78 -4,
+                          -2.82767 -78 2.82893,
+                          -3.99968 -78 -3.05311e-16,
+                          -2.82767 -78 -2.82893,
+                          2.82767 -78 -2.82893,
+                          2.82767 -78 2.82893,
+                          0 -78 4,
+                          2.82767 -78 -2.82893,
+                          3.99968 -78 -3.05311e-16,
+                          2.82767 -78 2.82893,
+                          18.5 -5.30299 -5.30299,
+                          18.5 -5 -11,
+                          18.5 -11 -5,
+                          24.5 -11 -5,
+                          18.5 -11 -5,
+                          18.5 -5 -11,
+                          18.5 -11 5,
+                          18.5 -5 11,
+                          18.5 -11 -5,
+                          18.5 -7.5 0,
+                          18.5 -11 -5,
+                          18.5 -5 11,
+                          18.5 -7.5 0,
+                          18.5 -5.30299 -5.30299,
+                          18.5 -11 -5,
+                          18.5 0 -7.5,
+                          18.5 5 -11,
+                          18.5 -5 -11,
+                          24.5 -5 -11,
+                          18.5 -5 -11,
+                          18.5 5 -11,
+                          18.5 -5.30299 -5.30299,
+                          18.5 0 -7.5,
+                          18.5 -5 -11,
+                          24.5 -11 -5,
+                          18.5 -5 -11,
+                          24.5 -5 -11,
+                          18.5 11 5,
+                          18.5 11 -5,
+                          18.5 5 -11,
+                          24.5 5 -11,
+                          18.5 5 -11,
+                          18.5 11 -5,
+                          18.5 7.5 -1.77636e-15,
+                          18.5 11 5,
+                          18.5 5 -11,
+                          18.5 5.30299 -5.30299,
+                          18.5 7.5 -1.77636e-15,
+                          18.5 5 -11,
+                          18.5 0 -7.5,
+                          18.5 5.30299 -5.30299,
+                          18.5 5 -11,
+                          24.5 -5 -11,
+                          18.5 5 -11,
+                          24.5 5 -11,
+                          18.5 30.5 5,
+                          18.5 30.5 -5,
+                          18.5 11 -5,
+                          24.5 11 -5,
+                          18.5 11 -5,
+                          18.5 30.5 -5,
+                          18.5 11 5,
+                          18.5 30.5 5,
+                          18.5 11 -5,
+                          24.5 5 -11,
+                          18.5 11 -5,
+                          24.5 11 -5,
+                          13 30.5 5,
+                          18.5 30.5 -5,
+                          18.5 30.5 5,
+                          24.5 36 -5,
+                          24.5 11 -5,
+                          18.5 30.5 -5,
+                          13 36 -5,
+                          24.5 36 -5,
+                          18.5 30.5 -5,
+                          13 30.5 -5,
+                          18.5 30.5 -5,
+                          13 30.5 5,
+                          13 30.5 -5,
+                          13 36 -5,
+                          18.5 30.5 -5,
+                          24.5 36 5,
+                          18.5 30.5 5,
+                          18.5 11 5,
+                          13 30.5 5,
+                          18.5 30.5 5,
+                          24.5 36 5,
+                          18.5 5.30299 5.30299,
+                          18.5 5 11,
+                          18.5 11 5,
+                          24.5 11 5,
+                          18.5 11 5,
+                          18.5 5 11,
+                          18.5 7.5 -1.77636e-15,
+                          18.5 5.30299 5.30299,
+                          18.5 11 5,
+                          24.5 36 5,
+                          18.5 11 5,
+                          24.5 11 5,
+                          18.5 0 7.5,
+                          18.5 -5 11,
+                          18.5 5 11,
+                          24.5 5 11,
+                          18.5 5 11,
+                          18.5 -5 11,
+                          18.5 5.30299 5.30299,
+                          18.5 0 7.5,
+                          18.5 5 11,
+                          24.5 11 5,
+                          18.5 5 11,
+                          24.5 5 11,
+                          24.5 -5 11,
+                          18.5 -5 11,
+                          18.5 -11 5,
+                          18.5 -5.30299 5.30299,
+                          18.5 -5 11,
+                          18.5 0 7.5,
+                          18.5 -5.30299 5.30299,
+                          18.5 -7.5 0,
+                          18.5 -5 11,
+                          24.5 5 11,
+                          18.5 -5 11,
+                          24.5 -5 11,
+                          24.5 -5 11,
+                          18.5 -11 5,
+                          24.5 -11 5,
+                          23.5 0 7.5,
+                          18.5 0 7.5,
+                          18.5 5.30299 5.30299,
+                          23.5 -5.30189 5.30424,
+                          18.5 -5.30299 5.30299,
+                          18.5 0 7.5,
+                          23.5 0 7.5,
+                          23.5 -5.30189 5.30424,
+                          18.5 0 7.5,
+                          23.5 5.30189 5.30424,
+                          18.5 5.30299 5.30299,
+                          18.5 7.5 -1.77636e-15,
+                          23.5 5.30189 5.30424,
+                          23.5 0 7.5,
+                          18.5 5.30299 5.30299,
+                          23.5 7.4994 6.10623e-16,
+                          18.5 7.5 -1.77636e-15,
+                          18.5 5.30299 -5.30299,
+                          23.5 5.30189 5.30424,
+                          18.5 7.5 -1.77636e-15,
+                          23.5 7.4994 6.10623e-16,
+                          23.5 5.30189 -5.30424,
+                          18.5 5.30299 -5.30299,
+                          18.5 0 -7.5,
+                          23.5 7.4994 6.10623e-16,
+                          18.5 5.30299 -5.30299,
+                          23.5 5.30189 -5.30424,
+                          23.5 0 -7.5,
+                          18.5 0 -7.5,
+                          18.5 -5.30299 -5.30299,
+                          23.5 5.30189 -5.30424,
+                          18.5 0 -7.5,
+                          23.5 0 -7.5,
+                          23.5 -5.30189 -5.30424,
+                          18.5 -5.30299 -5.30299,
+                          18.5 -7.5 0,
+                          23.5 -5.30189 -5.30424,
+                          23.5 0 -7.5,
+                          18.5 -5.30299 -5.30299,
+                          23.5 -7.4994 6.10623e-16,
+                          18.5 -7.5 0,
+                          18.5 -5.30299 5.30299,
+                          23.5 -7.4994 6.10623e-16,
+                          23.5 -5.30189 -5.30424,
+                          18.5 -7.5 0,
+                          23.5 -5.30189 5.30424,
+                          23.5 -7.4994 6.10623e-16,
+                          18.5 -5.30299 5.30299,
+                          24.5 6 0,
+                          24.5 5 -11,
+                          24.5 11 -5,
+                          24.5 11 5,
+                          24.5 5 11,
+                          24.5 11 -5,
+                          24.5 6 0,
+                          24.5 11 -5,
+                          24.5 5 11,
+                          24.5 36 -5,
+                          24.5 11 5,
+                          24.5 11 -5,
+                          24.5 -4.24239 -4.24239,
+                          24.5 -5 -11,
+                          24.5 5 -11,
+                          24.5 0 -6,
+                          24.5 -4.24239 -4.24239,
+                          24.5 5 -11,
+                          24.5 4.24239 -4.24239,
+                          24.5 0 -6,
+                          24.5 5 -11,
+                          24.5 6 0,
+                          24.5 4.24239 -4.24239,
+                          24.5 5 -11,
+                          24.5 -11 5,
+                          24.5 -11 -5,
+                          24.5 -5 -11,
+                          24.5 -6 0,
+                          24.5 -11 5,
+                          24.5 -5 -11,
+                          24.5 -4.24239 -4.24239,
+                          24.5 -6 0,
+                          24.5 -5 -11,
+                          24.5 -6 0,
+                          24.5 -5 11,
+                          24.5 -11 5,
+                          24.5 4.24239 4.24239,
+                          24.5 5 11,
+                          24.5 -5 11,
+                          24.5 -4.24239 4.24239,
+                          24.5 0 6,
+                          24.5 -5 11,
+                          24.5 4.24239 4.24239,
+                          24.5 -5 11,
+                          24.5 0 6,
+                          24.5 -6 0,
+                          24.5 -4.24239 4.24239,
+                          24.5 -5 11,
+                          24.5 4.24239 4.24239,
+                          24.5 6 0,
+                          24.5 5 11,
+                          24.5 36 -5,
+                          24.5 36 5,
+                          24.5 11 5,
+                          13 36 -5,
+                          24.5 36 5,
+                          24.5 36 -5,
+                          13 30.5 5,
+                          24.5 36 5,
+                          13 36 5,
+                          13 36 -5,
+                          13 36 5,
+                          24.5 36 5,
+                          23.5 0 6,
+                          24.5 0 6,
+                          24.5 -4.24239 4.24239,
+                          23.5 4.24151 4.24339,
+                          24.5 4.24239 4.24239,
+                          24.5 0 6,
+                          23.5 4.24151 4.24339,
+                          24.5 0 6,
+                          23.5 0 6,
+                          23.5 -4.24151 4.24339,
+                          24.5 -4.24239 4.24239,
+                          24.5 -6 0,
+                          23.5 -4.24151 4.24339,
+                          23.5 0 6,
+                          24.5 -4.24239 4.24239,
+                          23.5 -5.99952 4.996e-16,
+                          24.5 -6 0,
+                          24.5 -4.24239 -4.24239,
+                          23.5 -4.24151 4.24339,
+                          24.5 -6 0,
+                          23.5 -5.99952 4.996e-16,
+                          23.5 -4.24151 -4.24339,
+                          24.5 -4.24239 -4.24239,
+                          24.5 0 -6,
+                          23.5 -5.99952 4.996e-16,
+                          24.5 -4.24239 -4.24239,
+                          23.5 -4.24151 -4.24339,
+                          23.5 0 -6,
+                          24.5 0 -6,
+                          24.5 4.24239 -4.24239,
+                          23.5 -4.24151 -4.24339,
+                          24.5 0 -6,
+                          23.5 0 -6,
+                          23.5 4.24151 -4.24339,
+                          24.5 4.24239 -4.24239,
+                          24.5 6 0,
+                          23.5 0 -6,
+                          24.5 4.24239 -4.24239,
+                          23.5 4.24151 -4.24339,
+                          23.5 5.99952 4.996e-16,
+                          24.5 6 0,
+                          24.5 4.24239 4.24239,
+                          23.5 4.24151 -4.24339,
+                          24.5 6 0,
+                          23.5 5.99952 4.996e-16,
+                          23.5 5.99952 4.996e-16,
+                          24.5 4.24239 4.24239,
+                          23.5 4.24151 4.24339,
+                          23.5 0 -6,
+                          23.5 0 -7.5,
+                          23.5 -5.30189 -5.30424,
+                          23.5 0 -6,
+                          23.5 4.24151 -4.24339,
+                          23.5 0 -7.5,
+                          23.5 5.30189 -5.30424,
+                          23.5 0 -7.5,
+                          23.5 4.24151 -4.24339,
+                          23.5 -5.99952 4.996e-16,
+                          23.5 -5.30189 -5.30424,
+                          23.5 -7.4994 6.10623e-16,
+                          23.5 -4.24151 -4.24339,
+                          23.5 0 -6,
+                          23.5 -5.30189 -5.30424,
+                          23.5 -5.99952 4.996e-16,
+                          23.5 -4.24151 -4.24339,
+                          23.5 -5.30189 -5.30424,
+                          23.5 -5.99952 4.996e-16,
+                          23.5 -7.4994 6.10623e-16,
+                          23.5 -5.30189 5.30424,
+                          23.5 -4.24151 4.24339,
+                          23.5 -5.30189 5.30424,
+                          23.5 0 7.5,
+                          23.5 -4.24151 4.24339,
+                          23.5 -5.99952 4.996e-16,
+                          23.5 -5.30189 5.30424,
+                          23.5 -4.24151 4.24339,
+                          23.5 0 7.5,
+                          23.5 0 6,
+                          23.5 5.30189 5.30424,
+                          23.5 0 6,
+                          23.5 0 7.5,
+                          23.5 5.30189 5.30424,
+                          23.5 4.24151 4.24339,
+                          23.5 0 6,
+                          23.5 5.30189 5.30424,
+                          23.5 5.99952 4.996e-16,
+                          23.5 4.24151 4.24339,
+                          23.5 5.30189 -5.30424,
+                          23.5 4.24151 -4.24339,
+                          23.5 5.99952 4.996e-16,
+                          23.5 7.4994 6.10623e-16,
+                          23.5 5.30189 -5.30424,
+                          23.5 5.99952 4.996e-16,
+                          23.5 5.30189 5.30424,
+                          23.5 7.4994 6.10623e-16,
+                          23.5 5.99952 4.996e-16,
+                          8 30.5 -10,
+                          -18.5 36 -10,
+                          8 36 -10,
+                          0 36 -6.5,
+                          8 36 -10,
+                          -18.5 36 -10,
+                          13 30.5 -5,
+                          8 30.5 -10,
+                          8 36 -10,
+                          13 36 5,
+                          8 36 -10,
+                          8 36 10,
+                          6.5 36 -1.77636e-15,
+                          8 36 10,
+                          8 36 -10,
+                          13 36 -5,
+                          8 36 -10,
+                          13 36 5,
+                          13 30.5 -5,
+                          8 36 -10,
+                          13 36 -5,
+                          4.59619 36 -4.59619,
+                          8 36 -10,
+                          0 36 -6.5,
+                          4.59619 36 -4.59619,
+                          6.5 36 -1.77636e-15,
+                          8 36 -10,
+                          8 30.5 -10,
+                          -18.5 30.5 -10,
+                          -18.5 36 -10,
+                          -18.5 30.5 10,
+                          -18.5 36 -10,
+                          -18.5 30.5 -10,
+                          -18.5 36 10,
+                          -18.5 36 -10,
+                          -18.5 30.5 10,
+                          -4.59619 36 4.59619,
+                          -18.5 36 -10,
+                          -18.5 36 10,
+                          -4.59619 36 -4.59619,
+                          0 36 -6.5,
+                          -18.5 36 -10,
+                          -6.5 36 0,
+                          -4.59619 36 -4.59619,
+                          -18.5 36 -10,
+                          -4.59619 36 4.59619,
+                          -6.5 36 0,
+                          -18.5 36 -10,
+                          -18.5 30.5 10,
+                          -18.5 30.5 -10,
+                          8 30.5 -10,
+                          -18.5 30.5 10,
+                          8 30.5 -10,
+                          8 30.5 10,
+                          13 30.5 -5,
+                          8 30.5 10,
+                          8 30.5 -10,
+                          -18.5 30.5 10,
+                          8 30.5 10,
+                          8 36 10,
+                          13 36 5,
+                          8 36 10,
+                          8 30.5 10,
+                          -18.5 36 10,
+                          -18.5 30.5 10,
+                          8 36 10,
+                          -4.59619 36 4.59619,
+                          -18.5 36 10,
+                          8 36 10,
+                          0 36 6.5,
+                          -4.59619 36 4.59619,
+                          8 36 10,
+                          4.59619 36 4.59619,
+                          0 36 6.5,
+                          8 36 10,
+                          6.5 36 -1.77636e-15,
+                          4.59619 36 4.59619,
+                          8 36 10,
+                          13 30.5 5,
+                          13 36 5,
+                          8 30.5 10,
+                          13 30.5 -5,
+                          13 30.5 5,
+                          8 30.5 10,
+                          0 37.5 -6.5,
+                          0 36 -6.5,
+                          -4.59619 36 -4.59619,
+                          4.59674 37.5 -4.59542,
+                          4.59619 36 -4.59619,
+                          0 36 -6.5,
+                          4.59674 37.5 -4.59542,
+                          0 36 -6.5,
+                          0 37.5 -6.5,
+                          -4.59674 37.5 -4.59542,
+                          -4.59619 36 -4.59619,
+                          -6.5 36 0,
+                          -4.59674 37.5 -4.59542,
+                          0 37.5 -6.5,
+                          -4.59619 36 -4.59619,
+                          -6.49971 37.5 -3.88578e-16,
+                          -6.5 36 0,
+                          -4.59619 36 4.59619,
+                          -4.59674 37.5 -4.59542,
+                          -6.5 36 0,
+                          -6.49971 37.5 -3.88578e-16,
+                          -4.59674 37.5 4.59542,
+                          -4.59619 36 4.59619,
+                          0 36 6.5,
+                          -6.49971 37.5 -3.88578e-16,
+                          -4.59619 36 4.59619,
+                          -4.59674 37.5 4.59542,
+                          0 37.5 6.5,
+                          0 36 6.5,
+                          4.59619 36 4.59619,
+                          -4.59674 37.5 4.59542,
+                          0 36 6.5,
+                          0 37.5 6.5,
+                          4.59674 37.5 4.59542,
+                          4.59619 36 4.59619,
+                          6.5 36 -1.77636e-15,
+                          0 37.5 6.5,
+                          4.59619 36 4.59619,
+                          4.59674 37.5 4.59542,
+                          6.49971 37.5 -3.88578e-16,
+                          6.5 36 -1.77636e-15,
+                          4.59619 36 -4.59619,
+                          4.59674 37.5 4.59542,
+                          6.5 36 -1.77636e-15,
+                          6.49971 37.5 -3.88578e-16,
+                          6.49971 37.5 -3.88578e-16,
+                          4.59619 36 -4.59619,
+                          4.59674 37.5 -4.59542,
+                          2.82767 68 2.82893,
+                          2.82767 68 -2.82893,
+                          0 68 -4,
+                          0 46 -4,
+                          0 68 -4,
+                          2.82767 68 -2.82893,
+                          0 68 4,
+                          2.82767 68 2.82893,
+                          0 68 -4,
+                          -2.82767 68 -2.82893,
+                          0 68 4,
+                          0 68 -4,
+                          -2.82767 46 -2.82893,
+                          -2.82767 68 -2.82893,
+                          0 68 -4,
+                          -2.82767 46 -2.82893,
+                          0 68 -4,
+                          0 46 -4,
+                          2.82767 68 2.82893,
+                          3.99968 68 -3.05311e-16,
+                          2.82767 68 -2.82893,
+                          2.82767 46 -2.82893,
+                          2.82767 68 -2.82893,
+                          3.99968 68 -3.05311e-16,
+                          2.82767 46 -2.82893,
+                          0 46 -4,
+                          2.82767 68 -2.82893,
+                          3.99968 46 -3.05311e-16,
+                          3.99968 68 -3.05311e-16,
+                          2.82767 68 2.82893,
+                          2.82767 46 -2.82893,
+                          3.99968 68 -3.05311e-16,
+                          3.99968 46 -3.05311e-16,
+                          2.82767 46 2.82893,
+                          2.82767 68 2.82893,
+                          0 68 4,
+                          3.99968 46 -3.05311e-16,
+                          2.82767 68 2.82893,
+                          2.82767 46 2.82893,
+                          -2.82767 68 -2.82893,
+                          -2.82767 68 2.82893,
+                          0 68 4,
+                          0 46 4,
+                          0 68 4,
+                          -2.82767 68 2.82893,
+                          2.82767 46 2.82893,
+                          0 68 4,
+                          0 46 4,
+                          -2.82767 68 -2.82893,
+                          -3.99968 68 -3.05311e-16,
+                          -2.82767 68 2.82893,
+                          -2.82767 46 2.82893,
+                          -2.82767 68 2.82893,
+                          -3.99968 68 -3.05311e-16,
+                          0 46 4,
+                          -2.82767 68 2.82893,
+                          -2.82767 46 2.82893,
+                          -3.99968 46 -3.05311e-16,
+                          -3.99968 68 -3.05311e-16,
+                          -2.82767 68 -2.82893,
+                          -2.82767 46 2.82893,
+                          -3.99968 68 -3.05311e-16,
+                          -3.99968 46 -3.05311e-16,
+                          -3.99968 46 -3.05311e-16,
+                          -2.82767 68 -2.82893,
+                          -2.82767 46 -2.82893,
+                          -3.53532 46 -3.53532,
+                          -2.82767 46 -2.82893,
+                          0 46 -4,
+                          0 46 -5,
+                          0 46 -4,
+                          2.82767 46 -2.82893,
+                          -3.53532 46 -3.53532,
+                          0 46 -4,
+                          0 46 -5,
+                          -3.53532 46 -3.53532,
+                          -3.99968 46 -3.05311e-16,
+                          -2.82767 46 -2.82893,
+                          -3.53532 46 3.53532,
+                          -2.82767 46 2.82893,
+                          -3.99968 46 -3.05311e-16,
+                          -5 46 0,
+                          -3.53532 46 3.53532,
+                          -3.99968 46 -3.05311e-16,
+                          -3.53532 46 -3.53532,
+                          -5 46 0,
+                          -3.99968 46 -3.05311e-16,
+                          0 46 5,
+                          0 46 4,
+                          -2.82767 46 2.82893,
+                          -3.53532 46 3.53532,
+                          0 46 5,
+                          -2.82767 46 2.82893,
+                          3.53532 46 3.53532,
+                          2.82767 46 2.82893,
+                          0 46 4,
+                          0 46 5,
+                          3.53532 46 3.53532,
+                          0 46 4,
+                          3.53532 46 3.53532,
+                          3.99968 46 -3.05311e-16,
+                          2.82767 46 2.82893,
+                          3.53532 46 -3.53532,
+                          2.82767 46 -2.82893,
+                          3.99968 46 -3.05311e-16,
+                          5 46 0,
+                          3.53532 46 -3.53532,
+                          3.99968 46 -3.05311e-16,
+                          3.53532 46 3.53532,
+                          5 46 0,
+                          3.99968 46 -3.05311e-16,
+                          3.53532 46 -3.53532,
+                          0 46 -5,
+                          2.82767 46 -2.82893,
+                          0 37.5 -5,
+                          0 46 -5,
+                          3.53532 46 -3.53532,
+                          -3.53532 37.5 -3.53532,
+                          -3.53532 46 -3.53532,
+                          0 46 -5,
+                          -3.53532 37.5 -3.53532,
+                          0 46 -5,
+                          0 37.5 -5,
+                          3.53532 37.5 -3.53532,
+                          3.53532 46 -3.53532,
+                          5 46 0,
+                          3.53532 37.5 -3.53532,
+                          0 37.5 -5,
+                          3.53532 46 -3.53532,
+                          5 37.5 0,
+                          5 46 0,
+                          3.53532 46 3.53532,
+                          3.53532 37.5 -3.53532,
+                          5 46 0,
+                          5 37.5 0,
+                          3.53532 37.5 3.53532,
+                          3.53532 46 3.53532,
+                          0 46 5,
+                          5 37.5 0,
+                          3.53532 46 3.53532,
+                          3.53532 37.5 3.53532,
+                          0 37.5 5,
+                          0 46 5,
+                          -3.53532 46 3.53532,
+                          3.53532 37.5 3.53532,
+                          0 46 5,
+                          0 37.5 5,
+                          -3.53532 37.5 3.53532,
+                          -3.53532 46 3.53532,
+                          -5 46 0,
+                          0 37.5 5,
+                          -3.53532 46 3.53532,
+                          -3.53532 37.5 3.53532,
+                          -5 37.5 0,
+                          -5 46 0,
+                          -3.53532 46 -3.53532,
+                          -3.53532 37.5 3.53532,
+                          -5 46 0,
+                          -5 37.5 0,
+                          -5 37.5 0,
+                          -3.53532 46 -3.53532,
+                          -3.53532 37.5 -3.53532,
+                          -4.59674 37.5 -4.59542,
+                          -3.53532 37.5 -3.53532,
+                          0 37.5 -5,
+                          0 37.5 -6.5,
+                          0 37.5 -5,
+                          3.53532 37.5 -3.53532,
+                          -4.59674 37.5 -4.59542,
+                          0 37.5 -5,
+                          0 37.5 -6.5,
+                          -4.59674 37.5 -4.59542,
+                          -5 37.5 0,
+                          -3.53532 37.5 -3.53532,
+                          -4.59674 37.5 4.59542,
+                          -3.53532 37.5 3.53532,
+                          -5 37.5 0,
+                          -6.49971 37.5 -3.88578e-16,
+                          -4.59674 37.5 4.59542,
+                          -5 37.5 0,
+                          -4.59674 37.5 -4.59542,
+                          -6.49971 37.5 -3.88578e-16,
+                          -5 37.5 0,
+                          0 37.5 6.5,
+                          0 37.5 5,
+                          -3.53532 37.5 3.53532,
+                          -4.59674 37.5 4.59542,
+                          0 37.5 6.5,
+                          -3.53532 37.5 3.53532,
+                          4.59674 37.5 4.59542,
+                          3.53532 37.5 3.53532,
+                          0 37.5 5,
+                          0 37.5 6.5,
+                          4.59674 37.5 4.59542,
+                          0 37.5 5,
+                          4.59674 37.5 4.59542,
+                          5 37.5 0,
+                          3.53532 37.5 3.53532,
+                          4.59674 37.5 -4.59542,
+                          3.53532 37.5 -3.53532,
+                          5 37.5 0,
+                          6.49971 37.5 -3.88578e-16,
+                          4.59674 37.5 -4.59542,
+                          5 37.5 0,
+                          4.59674 37.5 4.59542,
+                          6.49971 37.5 -3.88578e-16,
+                          5 37.5 0,
+                          4.59674 37.5 -4.59542,
+                          0 37.5 -6.5,
+                          3.53532 37.5 -3.53532 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.65 0.65 0.65
+    }
+    Separator {
+        Normal {
+            vector      [ 1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          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,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.707107 -0.707107,
+                          0 0.707107 -0.707107,
+                          0 0.707107 -0.707107,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0.707107 -0.707107,
+                          0 0.707107 -0.707107,
+                          0 0.707107 -0.707107,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.707107 -0.707107,
+                          0 -0.707107 -0.707107,
+                          0 -0.707107 -0.707107,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.707107 -0.707107,
+                          0 -0.707107 -0.707107,
+                          0 -0.707107 -0.707107,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.984808 -0.173648,
+                          0 -0.984808 -0.173648,
+                          0 -0.984808 -0.173648,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 -0.984808 -0.173648,
+                          0 -0.984808 -0.173648,
+                          0 -0.984808 -0.173648,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          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 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 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.707107 0.707107,
+                          0 0.707107 0.707107,
+                          0 0.707107 0.707107,
+                          0 0 1,
+                          0 0.707107 0.707107,
+                          0 0 1,
+                          0 0 1,
+                          0 -0.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          0 -1 -3.82859e-16,
+                          0 -0.707107 0.707107,
+                          0 0 1,
+                          0 -0.707107 0.707107,
+                          0 -1 6.12303e-17,
+                          0 -1 -3.82859e-16,
+                          0 -0.707107 -0.707107,
+                          0 -0.707107 0.707107,
+                          0 -1 -3.82859e-16,
+                          0 -1 6.12303e-17,
+                          0 -0.707107 -0.707107,
+                          0 -0.707107 -0.707107,
+                          0 -1.22461e-16 -1,
+                          0 -1 6.12303e-17,
+                          0 -0.707107 -0.707107,
+                          0 -0.707107 -0.707107,
+                          0 1.22461e-16 -1,
+                          0 1.22461e-16 -1,
+                          0 0.707107 -0.707107,
+                          0 -0.707107 -0.707107,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0 0.707107 -0.707107,
+                          0 0.707107 -0.707107,
+                          0 1 5.0532e-16,
+                          0 1.22461e-16 -1,
+                          0 0.707107 -0.707107,
+                          0 0.707107 -0.707107,
+                          0 1 6.12303e-17,
+                          0 1 5.0532e-16,
+                          0 0.707107 0.707107,
+                          0 0.707107 -0.707107,
+                          0 1 5.0532e-16,
+                          0 1 6.12303e-17,
+                          0 1 6.12303e-17,
+                          0 0.707107 0.707107,
+                          0 0.707107 0.707107,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          0 0 1,
+                          0 -0.707107 0.707107,
+                          0 0 1,
+                          0 0 1,
+                          0 0.707107 0.707107,
+                          0 0.707107 0.707107,
+                          0 1 2.83275e-16,
+                          0 0.707107 0.707107,
+                          0 0 1,
+                          0 0.707107 0.707107,
+                          0 1 6.12303e-17,
+                          0 1 2.83275e-16,
+                          0 0.707107 -0.707107,
+                          0 0.707107 0.707107,
+                          0 1 2.83275e-16,
+                          0 1 6.12303e-17,
+                          0 0.707107 -0.707107,
+                          0 0.707107 -0.707107,
+                          0 1.22461e-16 -1,
+                          0 1 6.12303e-17,
+                          0 0.707107 -0.707107,
+                          0 0.707107 -0.707107,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0 -0.707107 -0.707107,
+                          0 0.707107 -0.707107,
+                          0 1.22461e-16 -1,
+                          0 1.22461e-16 -1,
+                          0 -0.707107 -0.707107,
+                          0 -0.707107 -0.707107,
+                          0 -1 -3.82859e-16,
+                          0 -1.22461e-16 -1,
+                          0 -0.707107 -0.707107,
+                          0 -0.707107 -0.707107,
+                          0 -1 6.12303e-17,
+                          0 -1 -3.82859e-16,
+                          0 -0.707107 0.707107,
+                          0 -0.707107 -0.707107,
+                          0 -1 -3.82859e-16,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -0.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -18.5 23 10,
+                          -18.5 11.5 -10,
+                          -18.5 36 -10,
+                          -25 36 -10,
+                          -18.5 36 -10,
+                          -18.5 11.5 -10,
+                          -18.5 36 10,
+                          -18.5 23 10,
+                          -18.5 36 -10,
+                          -25 36 10,
+                          -18.5 36 10,
+                          -18.5 36 -10,
+                          -25 36 10,
+                          -18.5 36 -10,
+                          -25 36 -10,
+                          -18.5 9.49974 2.55352e-15,
+                          -18.5 7.5 -14,
+                          -18.5 11.5 -10,
+                          -25 7.5 -14,
+                          -18.5 11.5 -10,
+                          -18.5 7.5 -14,
+                          -18.5 9.49974 2.55352e-15,
+                          -18.5 11.5 -10,
+                          -18.5 23 10,
+                          -25 11.5 -10,
+                          -25 36 -10,
+                          -18.5 11.5 -10,
+                          -25 11.5 -10,
+                          -18.5 11.5 -10,
+                          -25 7.5 -14,
+                          -18.5 -6.71675 -6.71808,
+                          -18.5 -7.5 -14,
+                          -18.5 7.5 -14,
+                          -25 7.5 -14,
+                          -18.5 7.5 -14,
+                          -18.5 -7.5 -14,
+                          -18.5 6.71675 -6.71808,
+                          -18.5 -1e-20 -9.5,
+                          -18.5 7.5 -14,
+                          -18.5 -6.71675 -6.71808,
+                          -18.5 7.5 -14,
+                          -18.5 -1e-20 -9.5,
+                          -18.5 9.49974 2.55352e-15,
+                          -18.5 6.71675 -6.71808,
+                          -18.5 7.5 -14,
+                          -18.5 -9.49974 -4.99599e-15,
+                          -18.5 -11.5 -10,
+                          -18.5 -7.5 -14,
+                          -25 -11.5 -10,
+                          -18.5 -7.5 -14,
+                          -18.5 -11.5 -10,
+                          -18.5 -6.71675 -6.71808,
+                          -18.5 -9.49974 -4.99599e-15,
+                          -18.5 -7.5 -14,
+                          -25 -7.5 -14,
+                          -18.5 -7.5 -14,
+                          -25 -11.5 -10,
+                          -25 7.5 -14,
+                          -18.5 -7.5 -14,
+                          -25 -7.5 -14,
+                          -18.5 -23 10,
+                          -18.5 -39.9735 -10,
+                          -18.5 -11.5 -10,
+                          -25 -11.5 -10,
+                          -18.5 -11.5 -10,
+                          -18.5 -39.9735 -10,
+                          -18.5 -23 25,
+                          -18.5 -23 10,
+                          -18.5 -11.5 -10,
+                          -18.5 -9.49974 -4.99599e-15,
+                          -18.5 -23 25,
+                          -18.5 -11.5 -10,
+                          -18.5 -23 10,
+                          -18.5 -43.5 10,
+                          -18.5 -39.9735 -10,
+                          -25 -39.9735 -10,
+                          -18.5 -39.9735 -10,
+                          -18.5 -43.5 10,
+                          -25 -11.5 -10,
+                          -18.5 -39.9735 -10,
+                          -25 -39.9735 -10,
+                          -25 -43.5 10,
+                          -18.5 -43.5 10,
+                          -18.5 -23 10,
+                          -25 -39.9735 -10,
+                          -18.5 -43.5 10,
+                          -25 -43.5 10,
+                          -25 -23 10,
+                          -18.5 -23 10,
+                          -18.5 -23 25,
+                          -25 -43.5 10,
+                          -18.5 -23 10,
+                          -25 -23 10,
+                          -18.5 23 10,
+                          -18.5 23 25,
+                          -18.5 -23 25,
+                          -25 -23 25,
+                          -18.5 -23 25,
+                          -18.5 23 25,
+                          -18.5 6.71675 6.71808,
+                          -18.5 23 10,
+                          -18.5 -23 25,
+                          -18.5 -1e-20 9.5,
+                          -18.5 6.71675 6.71808,
+                          -18.5 -23 25,
+                          -18.5 -6.71675 6.71808,
+                          -18.5 -1e-20 9.5,
+                          -18.5 -23 25,
+                          -18.5 -9.49974 -4.99599e-15,
+                          -18.5 -6.71675 6.71808,
+                          -18.5 -23 25,
+                          -25 -23 10,
+                          -18.5 -23 25,
+                          -25 -23 25,
+                          -25 23 25,
+                          -18.5 23 25,
+                          -18.5 23 10,
+                          -25 -23 25,
+                          -18.5 23 25,
+                          -25 23 25,
+                          -25 23 10,
+                          -18.5 23 10,
+                          -18.5 36 10,
+                          -18.5 6.71675 6.71808,
+                          -18.5 9.49974 2.55352e-15,
+                          -18.5 23 10,
+                          -25 23 25,
+                          -18.5 23 10,
+                          -25 23 10,
+                          -25 23 10,
+                          -18.5 36 10,
+                          -25 36 10,
+                          -23.5 -1e-20 -9.5,
+                          -18.5 -1e-20 -9.5,
+                          -18.5 6.71675 -6.71808,
+                          -23.5 -6.71751 -6.71751,
+                          -18.5 -6.71675 -6.71808,
+                          -18.5 -1e-20 -9.5,
+                          -23.5 -6.71751 -6.71751,
+                          -18.5 -1e-20 -9.5,
+                          -23.5 -1e-20 -9.5,
+                          -23.5 6.71751 -6.71751,
+                          -18.5 6.71675 -6.71808,
+                          -18.5 9.49974 2.55352e-15,
+                          -23.5 6.71751 -6.71751,
+                          -23.5 -1e-20 -9.5,
+                          -18.5 6.71675 -6.71808,
+                          -23.5 9.5 1e-20,
+                          -18.5 9.49974 2.55352e-15,
+                          -18.5 6.71675 6.71808,
+                          -23.5 6.71751 -6.71751,
+                          -18.5 9.49974 2.55352e-15,
+                          -23.5 9.5 1e-20,
+                          -23.5 6.71751 6.71751,
+                          -18.5 6.71675 6.71808,
+                          -18.5 -1e-20 9.5,
+                          -23.5 9.5 1e-20,
+                          -18.5 6.71675 6.71808,
+                          -23.5 6.71751 6.71751,
+                          -23.5 -1e-20 9.5,
+                          -18.5 -1e-20 9.5,
+                          -18.5 -6.71675 6.71808,
+                          -23.5 6.71751 6.71751,
+                          -18.5 -1e-20 9.5,
+                          -23.5 -1e-20 9.5,
+                          -23.5 -6.71751 6.71751,
+                          -18.5 -6.71675 6.71808,
+                          -18.5 -9.49974 -4.99599e-15,
+                          -23.5 -1e-20 9.5,
+                          -18.5 -6.71675 6.71808,
+                          -23.5 -6.71751 6.71751,
+                          -23.5 -9.5 1e-20,
+                          -18.5 -9.49974 -4.99599e-15,
+                          -18.5 -6.71675 -6.71808,
+                          -23.5 -6.71751 6.71751,
+                          -18.5 -9.49974 -4.99599e-15,
+                          -23.5 -9.5 1e-20,
+                          -23.5 -9.5 1e-20,
+                          -18.5 -6.71675 -6.71808,
+                          -23.5 -6.71751 -6.71751,
+                          -25 11.5 -10,
+                          -25 36 10,
+                          -25 36 -10,
+                          -25 11.5 -10,
+                          -25 23 10,
+                          -25 36 10,
+                          -25 11.5 -10,
+                          -25 23 25,
+                          -25 23 10,
+                          -25 -23 10,
+                          -25 -23 25,
+                          -25 23 25,
+                          -25 -5.65621 5.65733,
+                          -25 -23 10,
+                          -25 23 25,
+                          -25 7.99978 4.10784e-15,
+                          -25 23 25,
+                          -25 11.5 -10,
+                          -25 -1e-20 8,
+                          -25 -5.65621 5.65733,
+                          -25 23 25,
+                          -25 5.65621 5.65733,
+                          -25 -1e-20 8,
+                          -25 23 25,
+                          -25 7.99978 4.10784e-15,
+                          -25 5.65621 5.65733,
+                          -25 23 25,
+                          -25 -39.9735 -10,
+                          -25 -43.5 10,
+                          -25 -23 10,
+                          -25 -11.5 -10,
+                          -25 -39.9735 -10,
+                          -25 -23 10,
+                          -25 -7.99978 -2.16492e-15,
+                          -25 -11.5 -10,
+                          -25 -23 10,
+                          -25 -5.65621 5.65733,
+                          -25 -7.99978 -2.16492e-15,
+                          -25 -23 10,
+                          -25 -7.99978 -2.16492e-15,
+                          -25 -7.5 -14,
+                          -25 -11.5 -10,
+                          -25 5.65621 -5.65733,
+                          -25 7.5 -14,
+                          -25 -7.5 -14,
+                          -25 -5.65621 -5.65733,
+                          -25 -1e-20 -8,
+                          -25 -7.5 -14,
+                          -25 5.65621 -5.65733,
+                          -25 -7.5 -14,
+                          -25 -1e-20 -8,
+                          -25 -7.99978 -2.16492e-15,
+                          -25 -5.65621 -5.65733,
+                          -25 -7.5 -14,
+                          -25 7.99978 4.10784e-15,
+                          -25 11.5 -10,
+                          -25 7.5 -14,
+                          -25 5.65621 -5.65733,
+                          -25 7.99978 4.10784e-15,
+                          -25 7.5 -14,
+                          -23.5 -1e-20 -8,
+                          -25 -1e-20 -8,
+                          -25 -5.65621 -5.65733,
+                          -23.5 5.65685 -5.65685,
+                          -25 5.65621 -5.65733,
+                          -25 -1e-20 -8,
+                          -23.5 5.65685 -5.65685,
+                          -25 -1e-20 -8,
+                          -23.5 -1e-20 -8,
+                          -23.5 -5.65685 -5.65685,
+                          -25 -5.65621 -5.65733,
+                          -25 -7.99978 -2.16492e-15,
+                          -23.5 -5.65685 -5.65685,
+                          -23.5 -1e-20 -8,
+                          -25 -5.65621 -5.65733,
+                          -23.5 -8 1e-20,
+                          -25 -7.99978 -2.16492e-15,
+                          -25 -5.65621 5.65733,
+                          -23.5 -5.65685 -5.65685,
+                          -25 -7.99978 -2.16492e-15,
+                          -23.5 -8 1e-20,
+                          -23.5 -5.65685 5.65685,
+                          -25 -5.65621 5.65733,
+                          -25 -1e-20 8,
+                          -23.5 -8 1e-20,
+                          -25 -5.65621 5.65733,
+                          -23.5 -5.65685 5.65685,
+                          -23.5 -1e-20 8,
+                          -25 -1e-20 8,
+                          -25 5.65621 5.65733,
+                          -23.5 -5.65685 5.65685,
+                          -25 -1e-20 8,
+                          -23.5 -1e-20 8,
+                          -23.5 5.65685 5.65685,
+                          -25 5.65621 5.65733,
+                          -25 7.99978 4.10784e-15,
+                          -23.5 -1e-20 8,
+                          -25 5.65621 5.65733,
+                          -23.5 5.65685 5.65685,
+                          -23.5 8 1e-20,
+                          -25 7.99978 4.10784e-15,
+                          -25 5.65621 -5.65733,
+                          -23.5 5.65685 5.65685,
+                          -25 7.99978 4.10784e-15,
+                          -23.5 8 1e-20,
+                          -23.5 8 1e-20,
+                          -25 5.65621 -5.65733,
+                          -23.5 5.65685 -5.65685,
+                          -23.5 -5.65685 -5.65685,
+                          -23.5 -6.71751 -6.71751,
+                          -23.5 -1e-20 -9.5,
+                          -23.5 -1e-20 -8,
+                          -23.5 -1e-20 -9.5,
+                          -23.5 6.71751 -6.71751,
+                          -23.5 -5.65685 -5.65685,
+                          -23.5 -1e-20 -9.5,
+                          -23.5 -1e-20 -8,
+                          -23.5 -8 1e-20,
+                          -23.5 -9.5 1e-20,
+                          -23.5 -6.71751 -6.71751,
+                          -23.5 -5.65685 -5.65685,
+                          -23.5 -8 1e-20,
+                          -23.5 -6.71751 -6.71751,
+                          -23.5 -8 1e-20,
+                          -23.5 -6.71751 6.71751,
+                          -23.5 -9.5 1e-20,
+                          -23.5 -1e-20 8,
+                          -23.5 -1e-20 9.5,
+                          -23.5 -6.71751 6.71751,
+                          -23.5 -5.65685 5.65685,
+                          -23.5 -1e-20 8,
+                          -23.5 -6.71751 6.71751,
+                          -23.5 -8 1e-20,
+                          -23.5 -5.65685 5.65685,
+                          -23.5 -6.71751 6.71751,
+                          -23.5 5.65685 5.65685,
+                          -23.5 6.71751 6.71751,
+                          -23.5 -1e-20 9.5,
+                          -23.5 -1e-20 8,
+                          -23.5 5.65685 5.65685,
+                          -23.5 -1e-20 9.5,
+                          -23.5 8 1e-20,
+                          -23.5 9.5 1e-20,
+                          -23.5 6.71751 6.71751,
+                          -23.5 5.65685 5.65685,
+                          -23.5 8 1e-20,
+                          -23.5 6.71751 6.71751,
+                          -23.5 8 1e-20,
+                          -23.5 6.71751 -6.71751,
+                          -23.5 9.5 1e-20,
+                          -23.5 5.65685 -5.65685,
+                          -23.5 -1e-20 -8,
+                          -23.5 6.71751 -6.71751,
+                          -23.5 8 1e-20,
+                          -23.5 5.65685 -5.65685,
+                          -23.5 6.71751 -6.71751 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/neck/neck_roll_link.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/neck/neck_roll_link.iv
new file mode 100644
index 0000000000000000000000000000000000000000..197a76d495f988f344ff9a22a57945051529341f
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/neck/neck_roll_link.iv
@@ -0,0 +1,1670 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.23 0.382 0.56
+    }
+    Separator {
+        Normal {
+            vector      [ 0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          1.22461e-16 -1 6.12303e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.866025 -0.5 3.06152e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.866025 -0.5 3.06152e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0.866025 -0.5 3.06152e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0.866025 0.5 -3.06152e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0 1 -6.12303e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0.866025 0.5 -3.06152e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -2.44921e-16 1 -6.12303e-17,
+                          -2.44921e-16 1 -6.12303e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 1 -6.12303e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0 1 -6.12303e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.866025 0.5 -3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -2.44921e-16 1 -6.12303e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.866025 -0.5 3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -2.44921e-16 1 -6.12303e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -2.44921e-16 1 -6.12303e-17,
+                          -2.44921e-16 1 -6.12303e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          0 1 -6.12303e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          1.22461e-16 -1 6.12303e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -2.44921e-16 1 -6.12303e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -2.44921e-16 1 -6.12303e-17,
+                          -2.44921e-16 1 -6.12303e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0 1 -6.12303e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          1.22461e-16 -1 6.12303e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.866025 -0.5 3.06152e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.866025 -0.5 3.06152e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0.866025 -0.5 3.06152e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0.866025 0.5 -3.06152e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0 1 -6.12303e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0.866025 -0.5 3.06152e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -2.44921e-16 1 -6.12303e-17,
+                          -2.44921e-16 1 -6.12303e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0.866025 0.5 -3.06152e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.866025 0.5 -3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -2.44921e-16 1 -6.12303e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.866025 0.5 -3.06152e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -2.44921e-16 1 -6.12303e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -2.44921e-16 1 -6.12303e-17,
+                          -2.44921e-16 1 -6.12303e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          0 1 -6.12303e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          1.22461e-16 -1 6.12303e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0 1 -6.12303e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          -2.44921e-16 1 -6.12303e-17,
+                          -2.44921e-16 1 -6.12303e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 0.707107 -0.707107,
+                          0 0.707107 -0.707107,
+                          0.612372 0.353553 -0.707107,
+                          -0.612372 0.353553 -0.707107,
+                          -1.73185e-16 0.707107 -0.707107,
+                          -1.73185e-16 0.707107 -0.707107,
+                          -0.612372 0.353553 -0.707107,
+                          -0.612372 0.353553 -0.707107,
+                          -1.73185e-16 0.707107 -0.707107,
+                          0.612372 0.353553 -0.707107,
+                          0.612372 0.353553 -0.707107,
+                          0.612372 -0.353553 -0.707107,
+                          0.612372 0.353553 -0.707107,
+                          0 0.707107 -0.707107,
+                          0.612372 0.353553 -0.707107,
+                          0.612372 -0.353553 -0.707107,
+                          0.612372 -0.353553 -0.707107,
+                          8.65927e-17 -0.707107 -0.707107,
+                          0.612372 -0.353553 -0.707107,
+                          0.612372 0.353553 -0.707107,
+                          0.612372 -0.353553 -0.707107,
+                          8.65927e-17 -0.707107 -0.707107,
+                          0.612372 -0.353553 -0.707107,
+                          8.65927e-17 -0.707107 -0.707107,
+                          -0.612372 -0.353553 -0.707107,
+                          8.65927e-17 -0.707107 -0.707107,
+                          8.65927e-17 -0.707107 -0.707107,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -2.44921e-16 1 -6.12303e-17,
+                          -2.44921e-16 1 -6.12303e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -2.44921e-16 1 -6.12303e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0 1 -6.12303e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          -0.612372 -0.353553 -0.707107,
+                          8.65927e-17 -0.707107 -0.707107,
+                          -0.612372 -0.353553 -0.707107,
+                          0 0.707107 0.707107,
+                          0 0.707107 0.707107,
+                          0.612372 0.353553 0.707107,
+                          -0.612372 0.353553 0.707107,
+                          -1.73185e-16 0.707107 0.707107,
+                          -1.73185e-16 0.707107 0.707107,
+                          -0.612372 0.353553 0.707107,
+                          -0.612372 0.353553 0.707107,
+                          -1.73185e-16 0.707107 0.707107,
+                          0.612372 0.353553 0.707107,
+                          0.612372 0.353553 0.707107,
+                          0.612372 -0.353553 0.707107,
+                          0.612372 0.353553 0.707107,
+                          0 0.707107 0.707107,
+                          0.612372 0.353553 0.707107,
+                          0.612372 -0.353553 0.707107,
+                          0.612372 -0.353553 0.707107,
+                          8.65927e-17 -0.707107 0.707107,
+                          0.612372 -0.353553 0.707107,
+                          0.612372 0.353553 0.707107,
+                          0.612372 -0.353553 0.707107,
+                          8.65927e-17 -0.707107 0.707107,
+                          0.612372 -0.353553 0.707107,
+                          8.65927e-17 -0.707107 0.707107,
+                          -0.612372 -0.353553 0.707107,
+                          8.65927e-17 -0.707107 0.707107,
+                          8.65927e-17 -0.707107 0.707107,
+                          -0.866025 -0.5 3.06152e-17,
+                          1.22461e-16 -1 6.12303e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          -0.612372 -0.353553 0.707107,
+                          8.65927e-17 -0.707107 0.707107,
+                          -0.612372 -0.353553 0.707107,
+                          -0.866025 0.5 -3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          -2.44921e-16 1 -6.12303e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          -0.612372 -0.353553 -0.707107,
+                          -0.612372 -0.353553 -0.707107,
+                          -0.612372 0.353553 -0.707107,
+                          -0.612372 0.353553 -0.707107,
+                          -0.612372 -0.353553 -0.707107,
+                          -0.612372 0.353553 -0.707107,
+                          -0.866025 -0.5 3.06152e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -0.612372 -0.353553 0.707107,
+                          -0.612372 -0.353553 0.707107,
+                          -0.612372 0.353553 0.707107,
+                          -0.612372 0.353553 0.707107,
+                          -0.612372 -0.353553 0.707107,
+                          -0.612372 0.353553 0.707107 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -2.59765 1.50036 -39,
+                          -2.59765 -1.50036 -39,
+                          -1e-20 -3 -39,
+                          -1e-20 -6 -39,
+                          -1e-20 -3 -39,
+                          -2.59765 -1.50036 -39,
+                          -1e-20 3 -39,
+                          -2.59765 1.50036 -39,
+                          -1e-20 -3 -39,
+                          2.59765 -1.50036 -39,
+                          -1e-20 3 -39,
+                          -1e-20 -3 -39,
+                          5.19573 -3.0004 -39,
+                          2.59765 -1.50036 -39,
+                          -1e-20 -3 -39,
+                          5.19573 -3.0004 -39,
+                          -1e-20 -3 -39,
+                          -1e-20 -6 -39,
+                          -5.19573 3.0004 -39,
+                          -2.59765 -1.50036 -39,
+                          -2.59765 1.50036 -39,
+                          -5.19573 -3.0004 -39,
+                          -1e-20 -6 -39,
+                          -2.59765 -1.50036 -39,
+                          -5.19573 3.0004 -39,
+                          -5.19573 -3.0004 -39,
+                          -2.59765 -1.50036 -39,
+                          -5.19573 3.0004 -39,
+                          -2.59765 1.50036 -39,
+                          -1e-20 3 -39,
+                          2.59765 -1.50036 -39,
+                          2.59765 1.50036 -39,
+                          -1e-20 3 -39,
+                          -1e-20 6 -39,
+                          -1e-20 3 -39,
+                          2.59765 1.50036 -39,
+                          -1e-20 6 -39,
+                          -5.19573 3.0004 -39,
+                          -1e-20 3 -39,
+                          5.19573 -3.0004 -39,
+                          2.59765 1.50036 -39,
+                          2.59765 -1.50036 -39,
+                          5.19573 3.0004 -39,
+                          -1e-20 6 -39,
+                          2.59765 1.50036 -39,
+                          5.19573 -3.0004 -39,
+                          5.19573 3.0004 -39,
+                          2.59765 1.50036 -39,
+                          4.76314 -2.75 -42.45,
+                          5.19573 -3.0004 -42.45,
+                          -1e-20 -6 -42.45,
+                          7.34754e-16 -6 -40.5,
+                          -1e-20 -6 -42.45,
+                          5.19573 -3.0004 -42.45,
+                          -1e-20 -5.5 -42.45,
+                          -1e-20 -6 -42.45,
+                          -5.19573 -3.0004 -42.45,
+                          -5.19615 -3 -40.5,
+                          -5.19573 -3.0004 -42.45,
+                          -1e-20 -6 -42.45,
+                          4.76314 -2.75 -42.45,
+                          -1e-20 -6 -42.45,
+                          -1e-20 -5.5 -42.45,
+                          -5.19615 -3 -40.5,
+                          -1e-20 -6 -42.45,
+                          7.34754e-16 -6 -40.5,
+                          4.76314 -2.75 -42.45,
+                          5.19573 3.0004 -42.45,
+                          5.19573 -3.0004 -42.45,
+                          5.19615 -3 -40.5,
+                          5.19573 -3.0004 -42.45,
+                          5.19573 3.0004 -42.45,
+                          5.19615 -3 -40.5,
+                          7.34754e-16 -6 -40.5,
+                          5.19573 -3.0004 -42.45,
+                          -1e-20 5.5 -42.45,
+                          -1e-20 6 -42.45,
+                          5.19573 3.0004 -42.45,
+                          5.19615 3 -40.5,
+                          5.19573 3.0004 -42.45,
+                          -1e-20 6 -42.45,
+                          4.76314 2.75 -42.45,
+                          -1e-20 5.5 -42.45,
+                          5.19573 3.0004 -42.45,
+                          4.76314 -2.75 -42.45,
+                          4.76314 2.75 -42.45,
+                          5.19573 3.0004 -42.45,
+                          5.19615 3 -40.5,
+                          5.19615 -3 -40.5,
+                          5.19573 3.0004 -42.45,
+                          -4.76314 2.75 -42.45,
+                          -5.19573 3.0004 -42.45,
+                          -1e-20 6 -42.45,
+                          -1e-20 6 -40.5,
+                          -1e-20 6 -42.45,
+                          -5.19573 3.0004 -42.45,
+                          -1e-20 5.5 -42.45,
+                          -4.76314 2.75 -42.45,
+                          -1e-20 6 -42.45,
+                          -1e-20 6 -40.5,
+                          5.19615 3 -40.5,
+                          -1e-20 6 -42.45,
+                          -4.76314 2.75 -42.45,
+                          -5.19573 -3.0004 -42.45,
+                          -5.19573 3.0004 -42.45,
+                          -5.19615 3 -40.5,
+                          -5.19573 3.0004 -42.45,
+                          -5.19573 -3.0004 -42.45,
+                          -5.19615 3 -40.5,
+                          -1e-20 6 -40.5,
+                          -5.19573 3.0004 -42.45,
+                          -4.76314 -2.75 -42.45,
+                          -1e-20 -5.5 -42.45,
+                          -5.19573 -3.0004 -42.45,
+                          -4.76314 2.75 -42.45,
+                          -4.76314 -2.75 -42.45,
+                          -5.19573 -3.0004 -42.45,
+                          -5.19615 -3 -40.5,
+                          -5.19615 3 -40.5,
+                          -5.19573 -3.0004 -42.45,
+                          -1e-20 -5.5 -42.95,
+                          -1e-20 -5.5 -42.45,
+                          -4.76314 -2.75 -42.45,
+                          4.76314 -2.75 -42.95,
+                          4.76314 -2.75 -42.45,
+                          -1e-20 -5.5 -42.45,
+                          4.76314 -2.75 -42.95,
+                          -1e-20 -5.5 -42.45,
+                          -1e-20 -5.5 -42.95,
+                          -4.76314 -2.75 -42.95,
+                          -4.76314 -2.75 -42.45,
+                          -4.76314 2.75 -42.45,
+                          -4.76314 -2.75 -42.95,
+                          -1e-20 -5.5 -42.95,
+                          -4.76314 -2.75 -42.45,
+                          -4.76314 2.75 -42.95,
+                          -4.76314 2.75 -42.45,
+                          -1e-20 5.5 -42.45,
+                          -4.76314 -2.75 -42.95,
+                          -4.76314 2.75 -42.45,
+                          -4.76314 2.75 -42.95,
+                          -1e-20 5.5 -42.95,
+                          -1e-20 5.5 -42.45,
+                          4.76314 2.75 -42.45,
+                          -4.76314 2.75 -42.95,
+                          -1e-20 5.5 -42.45,
+                          -1e-20 5.5 -42.95,
+                          4.76314 2.75 -42.95,
+                          4.76314 2.75 -42.45,
+                          4.76314 -2.75 -42.45,
+                          -1e-20 5.5 -42.95,
+                          4.76314 2.75 -42.45,
+                          4.76314 2.75 -42.95,
+                          4.76314 2.75 -42.95,
+                          4.76314 -2.75 -42.45,
+                          4.76314 -2.75 -42.95,
+                          3.46422 -1.99942 -42.95,
+                          4.76314 -2.75 -42.95,
+                          -1e-20 -5.5 -42.95,
+                          -1e-20 -4 -42.95,
+                          -1e-20 -5.5 -42.95,
+                          -4.76314 -2.75 -42.95,
+                          3.46422 -1.99942 -42.95,
+                          -1e-20 -5.5 -42.95,
+                          -1e-20 -4 -42.95,
+                          3.46422 -1.99942 -42.95,
+                          4.76314 2.75 -42.95,
+                          4.76314 -2.75 -42.95,
+                          -1e-20 4 -42.95,
+                          -1e-20 5.5 -42.95,
+                          4.76314 2.75 -42.95,
+                          3.46422 1.99942 -42.95,
+                          -1e-20 4 -42.95,
+                          4.76314 2.75 -42.95,
+                          3.46422 -1.99942 -42.95,
+                          3.46422 1.99942 -42.95,
+                          4.76314 2.75 -42.95,
+                          -3.46422 1.99942 -42.95,
+                          -4.76314 2.75 -42.95,
+                          -1e-20 5.5 -42.95,
+                          -1e-20 4 -42.95,
+                          -3.46422 1.99942 -42.95,
+                          -1e-20 5.5 -42.95,
+                          -3.46422 1.99942 -42.95,
+                          -4.76314 -2.75 -42.95,
+                          -4.76314 2.75 -42.95,
+                          -3.46422 -1.99942 -42.95,
+                          -1e-20 -4 -42.95,
+                          -4.76314 -2.75 -42.95,
+                          -3.46422 1.99942 -42.95,
+                          -3.46422 -1.99942 -42.95,
+                          -4.76314 -2.75 -42.95,
+                          4.89833e-16 -4 -48.95,
+                          -1e-20 -4 -42.95,
+                          -3.46422 -1.99942 -42.95,
+                          3.4641 -2 -48.95,
+                          3.46422 -1.99942 -42.95,
+                          -1e-20 -4 -42.95,
+                          4.89833e-16 -4 -48.95,
+                          3.4641 -2 -48.95,
+                          -1e-20 -4 -42.95,
+                          -3.4641 -2 -48.95,
+                          -3.46422 -1.99942 -42.95,
+                          -3.46422 1.99942 -42.95,
+                          -3.4641 -2 -48.95,
+                          4.89833e-16 -4 -48.95,
+                          -3.46422 -1.99942 -42.95,
+                          -3.4641 2 -48.95,
+                          -3.46422 1.99942 -42.95,
+                          -1e-20 4 -42.95,
+                          -3.4641 2 -48.95,
+                          -3.4641 -2 -48.95,
+                          -3.46422 1.99942 -42.95,
+                          -1e-20 4 -48.95,
+                          -1e-20 4 -42.95,
+                          3.46422 1.99942 -42.95,
+                          -3.4641 2 -48.95,
+                          -1e-20 4 -42.95,
+                          -1e-20 4 -48.95,
+                          3.4641 2 -48.95,
+                          3.46422 1.99942 -42.95,
+                          3.46422 -1.99942 -42.95,
+                          3.4641 2 -48.95,
+                          -1e-20 4 -48.95,
+                          3.46422 1.99942 -42.95,
+                          3.4641 -2 -48.95,
+                          3.4641 2 -48.95,
+                          3.46422 -1.99942 -42.95,
+                          2.59765 -1.50036 -69.95,
+                          3.46422 -1.99942 -69.95,
+                          -1e-20 -4 -69.95,
+                          4.89833e-16 -4 -57.95,
+                          -1e-20 -4 -69.95,
+                          3.46422 -1.99942 -69.95,
+                          -1e-20 -3 -69.95,
+                          -1e-20 -4 -69.95,
+                          -3.46422 -1.99942 -69.95,
+                          -3.4641 -2 -57.95,
+                          -3.46422 -1.99942 -69.95,
+                          -1e-20 -4 -69.95,
+                          2.59765 -1.50036 -69.95,
+                          -1e-20 -4 -69.95,
+                          -1e-20 -3 -69.95,
+                          -3.4641 -2 -57.95,
+                          -1e-20 -4 -69.95,
+                          4.89833e-16 -4 -57.95,
+                          2.59765 -1.50036 -69.95,
+                          3.46422 1.99942 -69.95,
+                          3.46422 -1.99942 -69.95,
+                          3.4641 -2 -57.95,
+                          3.46422 -1.99942 -69.95,
+                          3.46422 1.99942 -69.95,
+                          4.89833e-16 -4 -57.95,
+                          3.46422 -1.99942 -69.95,
+                          3.4641 -2 -57.95,
+                          -1e-20 3 -69.95,
+                          -1e-20 4 -69.95,
+                          3.46422 1.99942 -69.95,
+                          3.4641 2 -57.95,
+                          3.46422 1.99942 -69.95,
+                          -1e-20 4 -69.95,
+                          2.59765 1.50036 -69.95,
+                          -1e-20 3 -69.95,
+                          3.46422 1.99942 -69.95,
+                          2.59765 -1.50036 -69.95,
+                          2.59765 1.50036 -69.95,
+                          3.46422 1.99942 -69.95,
+                          3.4641 -2 -57.95,
+                          3.46422 1.99942 -69.95,
+                          3.4641 2 -57.95,
+                          -2.59765 1.50036 -69.95,
+                          -3.46422 1.99942 -69.95,
+                          -1e-20 4 -69.95,
+                          -1e-20 4 -57.95,
+                          -1e-20 4 -69.95,
+                          -3.46422 1.99942 -69.95,
+                          -1e-20 3 -69.95,
+                          -2.59765 1.50036 -69.95,
+                          -1e-20 4 -69.95,
+                          3.4641 2 -57.95,
+                          -1e-20 4 -69.95,
+                          -1e-20 4 -57.95,
+                          -2.59765 1.50036 -69.95,
+                          -3.46422 -1.99942 -69.95,
+                          -3.46422 1.99942 -69.95,
+                          -3.4641 2 -57.95,
+                          -3.46422 1.99942 -69.95,
+                          -3.46422 -1.99942 -69.95,
+                          -3.4641 2 -57.95,
+                          -1e-20 4 -57.95,
+                          -3.46422 1.99942 -69.95,
+                          -2.59765 -1.50036 -69.95,
+                          -1e-20 -3 -69.95,
+                          -3.46422 -1.99942 -69.95,
+                          -2.59765 1.50036 -69.95,
+                          -2.59765 -1.50036 -69.95,
+                          -3.46422 -1.99942 -69.95,
+                          -3.4641 2 -57.95,
+                          -3.46422 -1.99942 -69.95,
+                          -3.4641 -2 -57.95,
+                          -1e-20 -3 -100,
+                          -1e-20 -3 -69.95,
+                          -2.59765 -1.50036 -69.95,
+                          2.59765 -1.50036 -100,
+                          2.59765 -1.50036 -69.95,
+                          -1e-20 -3 -69.95,
+                          2.59765 -1.50036 -100,
+                          -1e-20 -3 -69.95,
+                          -1e-20 -3 -100,
+                          -2.59765 -1.50036 -100,
+                          -2.59765 -1.50036 -69.95,
+                          -2.59765 1.50036 -69.95,
+                          -2.59765 -1.50036 -100,
+                          -1e-20 -3 -100,
+                          -2.59765 -1.50036 -69.95,
+                          -2.59765 1.50036 -100,
+                          -2.59765 1.50036 -69.95,
+                          -1e-20 3 -69.95,
+                          -2.59765 -1.50036 -100,
+                          -2.59765 1.50036 -69.95,
+                          -2.59765 1.50036 -100,
+                          -1e-20 3 -100,
+                          -1e-20 3 -69.95,
+                          2.59765 1.50036 -69.95,
+                          -2.59765 1.50036 -100,
+                          -1e-20 3 -69.95,
+                          -1e-20 3 -100,
+                          2.59765 1.50036 -100,
+                          2.59765 1.50036 -69.95,
+                          2.59765 -1.50036 -69.95,
+                          -1e-20 3 -100,
+                          2.59765 1.50036 -69.95,
+                          2.59765 1.50036 -100,
+                          2.59765 1.50036 -100,
+                          2.59765 -1.50036 -69.95,
+                          2.59765 -1.50036 -100,
+                          2.59765 1.50036 -100,
+                          2.59765 -1.50036 -100,
+                          -1e-20 -3 -100,
+                          -1e-20 3 -100,
+                          2.59765 1.50036 -100,
+                          -1e-20 -3 -100,
+                          -2.59765 -1.50036 -100,
+                          -1e-20 3 -100,
+                          -1e-20 -3 -100,
+                          -2.59765 -1.50036 -100,
+                          -2.59765 1.50036 -100,
+                          -1e-20 3 -100,
+                          -1e-20 -6 -39,
+                          7.34754e-16 -6 -40.5,
+                          5.19615 -3 -40.5,
+                          -5.19573 -3.0004 -39,
+                          -5.19615 -3 -40.5,
+                          7.34754e-16 -6 -40.5,
+                          -5.19573 -3.0004 -39,
+                          7.34754e-16 -6 -40.5,
+                          -1e-20 -6 -39,
+                          5.19573 -3.0004 -39,
+                          5.19615 -3 -40.5,
+                          5.19615 3 -40.5,
+                          5.19573 -3.0004 -39,
+                          -1e-20 -6 -39,
+                          5.19615 -3 -40.5,
+                          5.19573 3.0004 -39,
+                          5.19615 3 -40.5,
+                          -1e-20 6 -40.5,
+                          5.19573 -3.0004 -39,
+                          5.19615 3 -40.5,
+                          5.19573 3.0004 -39,
+                          -1e-20 6 -39,
+                          -1e-20 6 -40.5,
+                          -5.19615 3 -40.5,
+                          5.19573 3.0004 -39,
+                          -1e-20 6 -40.5,
+                          -1e-20 6 -39,
+                          -1e-20 3.5 -49.45,
+                          -1e-20 4 -48.95,
+                          3.4641 2 -48.95,
+                          -3.03109 1.75 -49.45,
+                          -1e-20 4 -48.95,
+                          -1e-20 3.5 -49.45,
+                          -3.03109 1.75 -49.45,
+                          -3.4641 2 -48.95,
+                          -1e-20 4 -48.95,
+                          3.03109 1.75 -49.45,
+                          3.4641 2 -48.95,
+                          3.4641 -2 -48.95,
+                          3.03109 1.75 -49.45,
+                          -1e-20 3.5 -49.45,
+                          3.4641 2 -48.95,
+                          3.03109 -1.75 -49.45,
+                          3.4641 -2 -48.95,
+                          4.89833e-16 -4 -48.95,
+                          3.03109 -1.75 -49.45,
+                          3.03109 1.75 -49.45,
+                          3.4641 -2 -48.95,
+                          4.28602e-16 -3.5 -49.45,
+                          3.03109 -1.75 -49.45,
+                          4.89833e-16 -4 -48.95,
+                          -3.4641 -2 -48.95,
+                          4.28602e-16 -3.5 -49.45,
+                          4.89833e-16 -4 -48.95,
+                          -1e-20 3.5 -57.45,
+                          -1e-20 3.5 -49.45,
+                          3.03109 1.75 -49.45,
+                          -3.03109 1.75 -57.45,
+                          -1e-20 3.5 -49.45,
+                          -1e-20 3.5 -57.45,
+                          -3.03109 1.75 -57.45,
+                          -3.03109 1.75 -49.45,
+                          -1e-20 3.5 -49.45,
+                          3.03109 1.75 -57.45,
+                          3.03109 1.75 -49.45,
+                          3.03109 -1.75 -49.45,
+                          3.03109 1.75 -57.45,
+                          -1e-20 3.5 -57.45,
+                          3.03109 1.75 -49.45,
+                          3.03109 -1.75 -57.45,
+                          3.03109 -1.75 -49.45,
+                          4.28602e-16 -3.5 -49.45,
+                          3.03109 -1.75 -57.45,
+                          3.03109 1.75 -57.45,
+                          3.03109 -1.75 -49.45,
+                          4.28602e-16 -3.5 -57.45,
+                          3.03109 -1.75 -57.45,
+                          4.28602e-16 -3.5 -49.45,
+                          -3.03109 -1.75 -49.45,
+                          4.28602e-16 -3.5 -57.45,
+                          4.28602e-16 -3.5 -49.45,
+                          -3.03109 -1.75 -49.45,
+                          4.28602e-16 -3.5 -49.45,
+                          -3.4641 -2 -48.95,
+                          -1e-20 4 -57.95,
+                          -1e-20 3.5 -57.45,
+                          3.03109 1.75 -57.45,
+                          -3.4641 2 -57.95,
+                          -1e-20 3.5 -57.45,
+                          -1e-20 4 -57.95,
+                          -3.4641 2 -57.95,
+                          -3.03109 1.75 -57.45,
+                          -1e-20 3.5 -57.45,
+                          3.4641 2 -57.95,
+                          3.03109 1.75 -57.45,
+                          3.03109 -1.75 -57.45,
+                          3.4641 2 -57.95,
+                          -1e-20 4 -57.95,
+                          3.03109 1.75 -57.45,
+                          3.4641 -2 -57.95,
+                          3.03109 -1.75 -57.45,
+                          4.28602e-16 -3.5 -57.45,
+                          3.4641 -2 -57.95,
+                          3.4641 2 -57.95,
+                          3.03109 -1.75 -57.45,
+                          4.89833e-16 -4 -57.95,
+                          3.4641 -2 -57.95,
+                          4.28602e-16 -3.5 -57.45,
+                          -3.03109 -1.75 -57.45,
+                          4.89833e-16 -4 -57.95,
+                          4.28602e-16 -3.5 -57.45,
+                          -3.03109 -1.75 -57.45,
+                          4.28602e-16 -3.5 -57.45,
+                          -3.03109 -1.75 -49.45,
+                          -3.4641 -2 -57.95,
+                          4.89833e-16 -4 -57.95,
+                          -3.03109 -1.75 -57.45,
+                          -5.19573 3.0004 -39,
+                          -5.19615 3 -40.5,
+                          -5.19615 -3 -40.5,
+                          -1e-20 6 -39,
+                          -5.19615 3 -40.5,
+                          -5.19573 3.0004 -39,
+                          -5.19573 3.0004 -39,
+                          -5.19615 -3 -40.5,
+                          -5.19573 -3.0004 -39,
+                          -3.03109 -1.75 -49.45,
+                          -3.4641 -2 -48.95,
+                          -3.4641 2 -48.95,
+                          -3.03109 1.75 -49.45,
+                          -3.03109 -1.75 -49.45,
+                          -3.4641 2 -48.95,
+                          -3.03109 -1.75 -57.45,
+                          -3.03109 -1.75 -49.45,
+                          -3.03109 1.75 -49.45,
+                          -3.03109 1.75 -57.45,
+                          -3.03109 -1.75 -57.45,
+                          -3.03109 1.75 -49.45,
+                          -3.4641 -2 -57.95,
+                          -3.03109 -1.75 -57.45,
+                          -3.03109 1.75 -57.45,
+                          -3.4641 2 -57.95,
+                          -3.4641 -2 -57.95,
+                          -3.03109 1.75 -57.45 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.6 0.6 0.6
+    }
+    Separator {
+        Normal {
+            vector      [ -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -16 -57.5 -104,
+                          -16 57.5 -100,
+                          -16 57.5 -104,
+                          16 57.5 -100,
+                          -16 57.5 -104,
+                          -16 57.5 -100,
+                          16 -57.5 -104,
+                          -16 -57.5 -104,
+                          -16 57.5 -104,
+                          16 57.5 -100,
+                          16 57.5 -104,
+                          -16 57.5 -104,
+                          16 -57.5 -104,
+                          -16 57.5 -104,
+                          16 57.5 -104,
+                          -16 -57.5 -104,
+                          -16 -57.5 -100,
+                          -16 57.5 -100,
+                          16 57.5 -100,
+                          -16 57.5 -100,
+                          -16 -57.5 -100,
+                          16 -57.5 -104,
+                          -16 -57.5 -100,
+                          -16 -57.5 -104,
+                          16 -57.5 -100,
+                          16 57.5 -100,
+                          -16 -57.5 -100,
+                          16 -57.5 -104,
+                          16 -57.5 -100,
+                          -16 -57.5 -100,
+                          16 -57.5 -100,
+                          16 57.5 -104,
+                          16 57.5 -100,
+                          16 -57.5 -104,
+                          16 57.5 -104,
+                          16 -57.5 -100 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.818182 0.761721 0.256138
+    }
+    Separator {
+        Normal {
+            vector      [ 0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.707107 -4.32964e-17 -0.707107,
+                          -0.707107 -4.32964e-17 -0.707107,
+                          -0.707107 -4.32964e-17 -0.707107,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          -0.707107 -4.32964e-17 -0.707107,
+                          -0.707107 -4.32964e-17 -0.707107,
+                          -0.707107 -4.32964e-17 -0.707107,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          -0.866025 3.06152e-17 0.5,
+                          0.866025 3.06152e-17 0.5,
+                          0.866025 3.06152e-17 0.5,
+                          0 6.12303e-17 1,
+                          0.866025 3.06152e-17 0.5,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          -0.866025 3.06152e-17 0.5,
+                          -0.866025 3.06152e-17 0.5,
+                          -0.866025 -3.06152e-17 -0.5,
+                          -0.866025 3.06152e-17 0.5,
+                          0 6.12303e-17 1,
+                          -0.866025 3.06152e-17 0.5,
+                          -0.866025 -3.06152e-17 -0.5,
+                          -0.866025 -3.06152e-17 -0.5,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -0.866025 3.06152e-17 0.5,
+                          -0.866025 -3.06152e-17 -0.5,
+                          -0.866025 -3.06152e-17 -0.5,
+                          1.22461e-16 -6.12303e-17 -1,
+                          1.22461e-16 -6.12303e-17 -1,
+                          0.866025 -3.06152e-17 -0.5,
+                          -0.866025 -3.06152e-17 -0.5,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          0.866025 -3.06152e-17 -0.5,
+                          0.866025 -3.06152e-17 -0.5,
+                          0.866025 3.06152e-17 0.5,
+                          1.22461e-16 -6.12303e-17 -1,
+                          0.866025 -3.06152e-17 -0.5,
+                          0.866025 -3.06152e-17 -0.5,
+                          0.866025 -3.06152e-17 -0.5,
+                          0.866025 3.06152e-17 0.5,
+                          0.866025 3.06152e-17 0.5,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0.866025 3.06152e-17 0.5,
+                          -0.866025 3.06152e-17 0.5,
+                          -0.866025 3.06152e-17 0.5,
+                          0 6.12303e-17 1,
+                          -0.866025 3.06152e-17 0.5,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0.866025 3.06152e-17 0.5,
+                          0.866025 3.06152e-17 0.5,
+                          0.866025 -3.06152e-17 -0.5,
+                          0.866025 3.06152e-17 0.5,
+                          0 6.12303e-17 1,
+                          0.866025 3.06152e-17 0.5,
+                          0.866025 -3.06152e-17 -0.5,
+                          0.866025 -3.06152e-17 -0.5,
+                          1.22461e-16 -6.12303e-17 -1,
+                          0.866025 3.06152e-17 0.5,
+                          0.866025 -3.06152e-17 -0.5,
+                          0.866025 -3.06152e-17 -0.5,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -0.866025 -3.06152e-17 -0.5,
+                          0.866025 -3.06152e-17 -0.5,
+                          1.22461e-16 -6.12303e-17 -1,
+                          1.22461e-16 -6.12303e-17 -1,
+                          -0.866025 -3.06152e-17 -0.5,
+                          -0.866025 -3.06152e-17 -0.5,
+                          -0.866025 3.06152e-17 0.5,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -0.866025 -3.06152e-17 -0.5,
+                          -0.866025 -3.06152e-17 -0.5,
+                          -0.866025 -3.06152e-17 -0.5,
+                          -0.866025 3.06152e-17 0.5,
+                          -0.866025 3.06152e-17 0.5,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -5 -57.5 -129,
+                          -9 -57.5 -111,
+                          -9 -57.5 -125,
+                          -9 -51.5 -125,
+                          -9 -57.5 -125,
+                          -9 -57.5 -111,
+                          -9 -51.5 -125,
+                          -5 -57.5 -129,
+                          -9 -57.5 -125,
+                          -16 -57.5 -104,
+                          -16 -57.5 -111,
+                          -9 -57.5 -111,
+                          -9 -51.5 -111,
+                          -9 -57.5 -111,
+                          -16 -57.5 -111,
+                          5.02465e-30 -57.5 -113.5,
+                          -16 -57.5 -104,
+                          -9 -57.5 -111,
+                          -5.62891 -57.5 -123.25,
+                          -9 -57.5 -111,
+                          -5 -57.5 -129,
+                          -5.62891 -57.5 -116.75,
+                          5.02465e-30 -57.5 -113.5,
+                          -9 -57.5 -111,
+                          -5.62891 -57.5 -123.25,
+                          -5.62891 -57.5 -116.75,
+                          -9 -57.5 -111,
+                          -9 -51.5 -111,
+                          -9 -51.5 -125,
+                          -9 -57.5 -111,
+                          -16 -51.5 -111,
+                          -16 -57.5 -111,
+                          -16 -57.5 -104,
+                          -9 -51.5 -111,
+                          -16 -57.5 -111,
+                          -16 -51.5 -111,
+                          16 -57.5 -111,
+                          16 -57.5 -104,
+                          -16 -57.5 -104,
+                          -16 -51.5 -104,
+                          -16 -57.5 -104,
+                          16 -57.5 -104,
+                          9 -57.5 -111,
+                          16 -57.5 -111,
+                          -16 -57.5 -104,
+                          5.62891 -57.5 -116.75,
+                          9 -57.5 -111,
+                          -16 -57.5 -104,
+                          5.02465e-30 -57.5 -113.5,
+                          5.62891 -57.5 -116.75,
+                          -16 -57.5 -104,
+                          -16 -51.5 -111,
+                          -16 -57.5 -104,
+                          -16 -51.5 -104,
+                          16 -51.5 -104,
+                          16 -57.5 -104,
+                          16 -57.5 -111,
+                          -16 -51.5 -104,
+                          16 -57.5 -104,
+                          16 -51.5 -104,
+                          16 -51.5 -111,
+                          16 -57.5 -111,
+                          9 -57.5 -111,
+                          16 -51.5 -104,
+                          16 -57.5 -111,
+                          16 -51.5 -111,
+                          5.62891 -57.5 -116.75,
+                          9 -57.5 -125,
+                          9 -57.5 -111,
+                          9 -51.5 -111,
+                          9 -57.5 -111,
+                          9 -57.5 -125,
+                          16 -51.5 -111,
+                          9 -57.5 -111,
+                          9 -51.5 -111,
+                          5.62891 -57.5 -123.25,
+                          5 -57.5 -129,
+                          9 -57.5 -125,
+                          5 -51.5 -129,
+                          9 -57.5 -125,
+                          5 -57.5 -129,
+                          5.62891 -57.5 -116.75,
+                          5.62891 -57.5 -123.25,
+                          9 -57.5 -125,
+                          9 -51.5 -125,
+                          9 -57.5 -125,
+                          5 -51.5 -129,
+                          9 -51.5 -111,
+                          9 -57.5 -125,
+                          9 -51.5 -125,
+                          5.6656e-30 -57.5 -126.5,
+                          -5 -57.5 -129,
+                          5 -57.5 -129,
+                          5 -51.5 -129,
+                          5 -57.5 -129,
+                          -5 -57.5 -129,
+                          5.62891 -57.5 -123.25,
+                          5.6656e-30 -57.5 -126.5,
+                          5 -57.5 -129,
+                          -5.62891 -57.5 -123.25,
+                          -5 -57.5 -129,
+                          5.6656e-30 -57.5 -126.5,
+                          -5 -51.5 -129,
+                          -5 -57.5 -129,
+                          -9 -51.5 -125,
+                          5 -51.5 -129,
+                          -5 -57.5 -129,
+                          -5 -51.5 -129,
+                          5.71528e-30 -52.5 -126.5,
+                          5.6656e-30 -57.5 -126.5,
+                          5.62891 -57.5 -123.25,
+                          -5.62917 -52.5 -123.25,
+                          -5.62891 -57.5 -123.25,
+                          5.6656e-30 -57.5 -126.5,
+                          -5.62917 -52.5 -123.25,
+                          5.6656e-30 -57.5 -126.5,
+                          5.71528e-30 -52.5 -126.5,
+                          5.62917 -52.5 -123.25,
+                          5.62891 -57.5 -123.25,
+                          5.62891 -57.5 -116.75,
+                          5.62917 -52.5 -123.25,
+                          5.71528e-30 -52.5 -126.5,
+                          5.62891 -57.5 -123.25,
+                          5.62917 -52.5 -116.75,
+                          5.62891 -57.5 -116.75,
+                          5.02465e-30 -57.5 -113.5,
+                          5.62917 -52.5 -123.25,
+                          5.62891 -57.5 -116.75,
+                          5.62917 -52.5 -116.75,
+                          5.07433e-30 -52.5 -113.5,
+                          5.02465e-30 -57.5 -113.5,
+                          -5.62891 -57.5 -116.75,
+                          5.62917 -52.5 -116.75,
+                          5.02465e-30 -57.5 -113.5,
+                          5.07433e-30 -52.5 -113.5,
+                          -5.62917 -52.5 -116.75,
+                          -5.62891 -57.5 -116.75,
+                          -5.62891 -57.5 -123.25,
+                          5.07433e-30 -52.5 -113.5,
+                          -5.62891 -57.5 -116.75,
+                          -5.62917 -52.5 -116.75,
+                          -5.62917 -52.5 -116.75,
+                          -5.62891 -57.5 -123.25,
+                          -5.62917 -52.5 -123.25,
+                          -4.76314 -51.5 -117.25,
+                          -5 -51.5 -129,
+                          -9 -51.5 -125,
+                          -4.76314 -51.5 -117.25,
+                          -9 -51.5 -125,
+                          -9 -51.5 -111,
+                          4.76314 -51.5 -122.75,
+                          5 -51.5 -129,
+                          -5 -51.5 -129,
+                          -4.76314 -51.5 -122.75,
+                          5.67591e-30 -51.5 -125.5,
+                          -5 -51.5 -129,
+                          4.76314 -51.5 -122.75,
+                          -5 -51.5 -129,
+                          5.67591e-30 -51.5 -125.5,
+                          -4.76314 -51.5 -117.25,
+                          -4.76314 -51.5 -122.75,
+                          -5 -51.5 -129,
+                          9 -51.5 -111,
+                          9 -51.5 -125,
+                          5 -51.5 -129,
+                          4.76314 -51.5 -122.75,
+                          9 -51.5 -111,
+                          5 -51.5 -129,
+                          16 -51.5 -104,
+                          16 -51.5 -111,
+                          9 -51.5 -111,
+                          5.13357e-30 -51.5 -114.5,
+                          16 -51.5 -104,
+                          9 -51.5 -111,
+                          4.76314 -51.5 -117.25,
+                          5.13357e-30 -51.5 -114.5,
+                          9 -51.5 -111,
+                          4.76314 -51.5 -122.75,
+                          4.76314 -51.5 -117.25,
+                          9 -51.5 -111,
+                          -16 -51.5 -111,
+                          -16 -51.5 -104,
+                          16 -51.5 -104,
+                          -9 -51.5 -111,
+                          -16 -51.5 -111,
+                          16 -51.5 -104,
+                          -4.76314 -51.5 -117.25,
+                          -9 -51.5 -111,
+                          16 -51.5 -104,
+                          5.13357e-30 -51.5 -114.5,
+                          -4.76314 -51.5 -117.25,
+                          16 -51.5 -104,
+                          5.66597e-30 -52.5 -125.5,
+                          5.67591e-30 -51.5 -125.5,
+                          -4.76314 -51.5 -122.75,
+                          4.76325 -52.5 -122.75,
+                          4.76314 -51.5 -122.75,
+                          5.67591e-30 -51.5 -125.5,
+                          4.76325 -52.5 -122.75,
+                          5.67591e-30 -51.5 -125.5,
+                          5.66597e-30 -52.5 -125.5,
+                          -4.76325 -52.5 -122.75,
+                          -4.76314 -51.5 -122.75,
+                          -4.76314 -51.5 -117.25,
+                          -4.76325 -52.5 -122.75,
+                          5.66597e-30 -52.5 -125.5,
+                          -4.76314 -51.5 -122.75,
+                          -4.76325 -52.5 -117.25,
+                          -4.76314 -51.5 -117.25,
+                          5.13357e-30 -51.5 -114.5,
+                          -4.76325 -52.5 -122.75,
+                          -4.76314 -51.5 -117.25,
+                          -4.76325 -52.5 -117.25,
+                          5.12363e-30 -52.5 -114.5,
+                          5.13357e-30 -51.5 -114.5,
+                          4.76314 -51.5 -117.25,
+                          -4.76325 -52.5 -117.25,
+                          5.13357e-30 -51.5 -114.5,
+                          5.12363e-30 -52.5 -114.5,
+                          4.76325 -52.5 -117.25,
+                          4.76314 -51.5 -117.25,
+                          4.76314 -51.5 -122.75,
+                          5.12363e-30 -52.5 -114.5,
+                          4.76314 -51.5 -117.25,
+                          4.76325 -52.5 -117.25,
+                          4.76325 -52.5 -117.25,
+                          4.76314 -51.5 -122.75,
+                          4.76325 -52.5 -122.75,
+                          -4.76325 -52.5 -122.75,
+                          -5.62917 -52.5 -123.25,
+                          5.71528e-30 -52.5 -126.5,
+                          5.66597e-30 -52.5 -125.5,
+                          5.71528e-30 -52.5 -126.5,
+                          5.62917 -52.5 -123.25,
+                          -4.76325 -52.5 -122.75,
+                          5.71528e-30 -52.5 -126.5,
+                          5.66597e-30 -52.5 -125.5,
+                          -4.76325 -52.5 -122.75,
+                          -5.62917 -52.5 -116.75,
+                          -5.62917 -52.5 -123.25,
+                          5.12363e-30 -52.5 -114.5,
+                          5.07433e-30 -52.5 -113.5,
+                          -5.62917 -52.5 -116.75,
+                          -4.76325 -52.5 -117.25,
+                          5.12363e-30 -52.5 -114.5,
+                          -5.62917 -52.5 -116.75,
+                          -4.76325 -52.5 -122.75,
+                          -4.76325 -52.5 -117.25,
+                          -5.62917 -52.5 -116.75,
+                          4.76325 -52.5 -117.25,
+                          5.62917 -52.5 -116.75,
+                          5.07433e-30 -52.5 -113.5,
+                          5.12363e-30 -52.5 -114.5,
+                          4.76325 -52.5 -117.25,
+                          5.07433e-30 -52.5 -113.5,
+                          4.76325 -52.5 -117.25,
+                          5.62917 -52.5 -123.25,
+                          5.62917 -52.5 -116.75,
+                          4.76325 -52.5 -122.75,
+                          5.66597e-30 -52.5 -125.5,
+                          5.62917 -52.5 -123.25,
+                          4.76325 -52.5 -117.25,
+                          4.76325 -52.5 -122.75,
+                          5.62917 -52.5 -123.25 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/neck/neck_yaw_link.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/neck/neck_yaw_link.iv
new file mode 100644
index 0000000000000000000000000000000000000000..8821ee89265bbdcfdba67bf148049b36e7e061e9
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/neck/neck_yaw_link.iv
@@ -0,0 +1,4536 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.64 0.464 0.301
+    }
+    Separator {
+        Normal {
+            vector      [ 0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.809017 -0.587785 3.59903e-17,
+                          -0.809017 0.587785 -3.59903e-17,
+                          -0.809017 0.587785 -3.59903e-17,
+                          -1 0 0,
+                          -0.809017 0.587785 -3.59903e-17,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.809017 -0.587785 3.59903e-17,
+                          -0.809017 -0.587785 3.59903e-17,
+                          -0.309017 -0.951057 5.82335e-17,
+                          -0.809017 -0.587785 3.59903e-17,
+                          -1 0 0,
+                          -0.809017 -0.587785 3.59903e-17,
+                          -0.309017 -0.951057 5.82335e-17,
+                          -0.309017 -0.951057 5.82335e-17,
+                          0.309017 -0.951057 5.82335e-17,
+                          -0.809017 -0.587785 3.59903e-17,
+                          -0.309017 -0.951057 5.82335e-17,
+                          -0.309017 -0.951057 5.82335e-17,
+                          0.309017 -0.951057 5.82335e-17,
+                          0.309017 -0.951057 5.82335e-17,
+                          0.809017 -0.587785 3.59903e-17,
+                          -0.309017 -0.951057 5.82335e-17,
+                          0.309017 -0.951057 5.82335e-17,
+                          0.309017 -0.951057 5.82335e-17,
+                          0.809017 -0.587785 3.59903e-17,
+                          0.809017 -0.587785 3.59903e-17,
+                          1 -1.22461e-16 0,
+                          0.309017 -0.951057 5.82335e-17,
+                          0.809017 -0.587785 3.59903e-17,
+                          0.809017 -0.587785 3.59903e-17,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          0.809017 0.587785 -3.59903e-17,
+                          0.809017 -0.587785 3.59903e-17,
+                          1 -1.22461e-16 0,
+                          1 -1.22461e-16 0,
+                          0.809017 0.587785 -3.59903e-17,
+                          0.809017 0.587785 -3.59903e-17,
+                          0.309017 0.951057 -5.82335e-17,
+                          1 1.22461e-16 0,
+                          0.809017 0.587785 -3.59903e-17,
+                          0.809017 0.587785 -3.59903e-17,
+                          0.309017 0.951057 -5.82335e-17,
+                          0.309017 0.951057 -5.82335e-17,
+                          -0.309017 0.951057 -5.82335e-17,
+                          0.809017 0.587785 -3.59903e-17,
+                          0.309017 0.951057 -5.82335e-17,
+                          0.309017 0.951057 -5.82335e-17,
+                          -0.309017 0.951057 -5.82335e-17,
+                          -0.309017 0.951057 -5.82335e-17,
+                          -0.809017 0.587785 -3.59903e-17,
+                          0.309017 0.951057 -5.82335e-17,
+                          -0.309017 0.951057 -5.82335e-17,
+                          -0.309017 0.951057 -5.82335e-17,
+                          -0.309017 0.951057 -5.82335e-17,
+                          -0.809017 0.587785 -3.59903e-17,
+                          -0.809017 0.587785 -3.59903e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.707107 0.707107 -4.32964e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -1 0 0,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -1 0 0,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -1 0 0,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -6.12303e-17 1 -6.12303e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -1 0 0,
+                          -0.707107 0.707107 -4.32964e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -6.12303e-17 1 -6.12303e-17,
+                          -6.12303e-17 1 -6.12303e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -6.12303e-17 1 -6.12303e-17,
+                          -6.12303e-17 1 -6.12303e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0.707107 0.707107 -4.32964e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          1 1.22461e-16 0,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -6.12303e-17 1 -6.12303e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          1 -1.22461e-16 0,
+                          1 -1.22461e-16 0,
+                          0.707107 -0.707107 4.32964e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0.707107 0.707107 -4.32964e-17,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0.707107 -0.707107 4.32964e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          -6.12303e-17 -1 6.12303e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0.707107 -0.707107 4.32964e-17,
+                          1 -1.22461e-16 0,
+                          0.707107 -0.707107 4.32964e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -6.12303e-17 -1 6.12303e-17,
+                          -6.12303e-17 -1 6.12303e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -6.12303e-17 -1 6.12303e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          -6.12303e-17 -1 6.12303e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -6.12303e-17 -1 6.12303e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          1 0 0,
+                          1 0 0,
+                          0.92388 0.382683 -2.34318e-17,
+                          0.92388 -0.382683 2.34318e-17,
+                          0.92388 -0.382683 2.34318e-17,
+                          1 0 0,
+                          0.92388 -0.382683 2.34318e-17,
+                          1 0 0,
+                          1 0 0,
+                          0.92388 0.382683 -2.34318e-17,
+                          0.92388 0.382683 -2.34318e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          1 0 0,
+                          0.92388 0.382683 -2.34318e-17,
+                          0.92388 0.382683 -2.34318e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0.707107 0.707107 -4.32964e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          0.382683 0.92388 -5.65694e-17,
+                          0.92388 0.382683 -2.34318e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0.382683 0.92388 -5.65694e-17,
+                          0.382683 0.92388 -5.65694e-17,
+                          6.12303e-17 1 -6.12303e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          0.382683 0.92388 -5.65694e-17,
+                          0.382683 0.92388 -5.65694e-17,
+                          6.12303e-17 1 -6.12303e-17,
+                          6.12303e-17 1 -6.12303e-17,
+                          -0.382683 0.92388 -5.65694e-17,
+                          0.382683 0.92388 -5.65694e-17,
+                          6.12303e-17 1 -6.12303e-17,
+                          6.12303e-17 1 -6.12303e-17,
+                          -0.382683 0.92388 -5.65694e-17,
+                          -0.382683 0.92388 -5.65694e-17,
+                          -0.707107 0.707107 -4.32964e-17,
+                          6.12303e-17 1 -6.12303e-17,
+                          -0.382683 0.92388 -5.65694e-17,
+                          -0.382683 0.92388 -5.65694e-17,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -0.92388 0.382683 -2.34318e-17,
+                          -0.382683 0.92388 -5.65694e-17,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -0.92388 0.382683 -2.34318e-17,
+                          -0.92388 0.382683 -2.34318e-17,
+                          -1 1.22461e-16 0,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -0.92388 0.382683 -2.34318e-17,
+                          -0.92388 0.382683 -2.34318e-17,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -0.92388 -0.382683 2.34318e-17,
+                          -0.92388 0.382683 -2.34318e-17,
+                          -1 1.22461e-16 0,
+                          -1 1.22461e-16 0,
+                          -0.92388 -0.382683 2.34318e-17,
+                          -0.92388 -0.382683 2.34318e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -0.92388 -0.382683 2.34318e-17,
+                          -1 -1.22461e-16 0,
+                          -0.92388 -0.382683 2.34318e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -0.382683 -0.92388 5.65694e-17,
+                          -0.92388 -0.382683 2.34318e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.382683 -0.92388 5.65694e-17,
+                          -0.382683 -0.92388 5.65694e-17,
+                          6.12303e-17 -1 6.12303e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -0.382683 -0.92388 5.65694e-17,
+                          -0.382683 -0.92388 5.65694e-17,
+                          6.12303e-17 -1 6.12303e-17,
+                          6.12303e-17 -1 6.12303e-17,
+                          0.382683 -0.92388 5.65694e-17,
+                          -0.382683 -0.92388 5.65694e-17,
+                          6.12303e-17 -1 6.12303e-17,
+                          6.12303e-17 -1 6.12303e-17,
+                          0.382683 -0.92388 5.65694e-17,
+                          0.382683 -0.92388 5.65694e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          6.12303e-17 -1 6.12303e-17,
+                          0.382683 -0.92388 5.65694e-17,
+                          0.382683 -0.92388 5.65694e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          0.92388 -0.382683 2.34318e-17,
+                          0.382683 -0.92388 5.65694e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          0.92388 -0.382683 2.34318e-17,
+                          0.92388 -0.382683 2.34318e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -1 0 0,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -6.12303e-17 1 -6.12303e-17,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -1 0 0,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -6.12303e-17 1 -6.12303e-17,
+                          -6.12303e-17 1 -6.12303e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -6.12303e-17 1 -6.12303e-17,
+                          -6.12303e-17 1 -6.12303e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          1 1.22461e-16 0,
+                          -6.12303e-17 1 -6.12303e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          1 -1.22461e-16 0,
+                          1 -1.22461e-16 0,
+                          0.707107 -0.707107 4.32964e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          0.707107 -0.707107 4.32964e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          -6.12303e-17 -1 6.12303e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          1 -1.22461e-16 0,
+                          0.707107 -0.707107 4.32964e-17,
+                          -6.12303e-17 -1 6.12303e-17,
+                          -6.12303e-17 -1 6.12303e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -6.12303e-17 -1 6.12303e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          -6.12303e-17 -1 6.12303e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -6.12303e-17 -1 6.12303e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -1 0 0,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -6.12303e-17 1 -6.12303e-17,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -1 0 0,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -6.12303e-17 1 -6.12303e-17,
+                          -6.12303e-17 1 -6.12303e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -6.12303e-17 1 -6.12303e-17,
+                          -6.12303e-17 1 -6.12303e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          1 1.22461e-16 0,
+                          -6.12303e-17 1 -6.12303e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          1 -1.22461e-16 0,
+                          1 -1.22461e-16 0,
+                          0.707107 -0.707107 4.32964e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          0.707107 -0.707107 4.32964e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          -6.12303e-17 -1 6.12303e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          1 -1.22461e-16 0,
+                          0.707107 -0.707107 4.32964e-17,
+                          -6.12303e-17 -1 6.12303e-17,
+                          -6.12303e-17 -1 6.12303e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -6.12303e-17 -1 6.12303e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          -6.12303e-17 -1 6.12303e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -6.12303e-17 -1 6.12303e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.5 -0.5 0.707107,
+                          0.5 0.5 0.707107,
+                          0.707107 1.29889e-16 0.707107,
+                          0.707107 1.29889e-16 0.707107,
+                          0.5 0.5 0.707107,
+                          0.707107 1.29889e-16 0.707107,
+                          0.5 0.5 0.707107,
+                          0.5 -0.5 0.707107,
+                          0.5 -0.5 0.707107,
+                          -4.32964e-17 -0.707107 0.707107,
+                          0.5 -0.5 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.5 -0.5 0.707107,
+                          -4.32964e-17 -0.707107 0.707107,
+                          -4.32964e-17 -0.707107 0.707107,
+                          -0.5 -0.5 0.707107,
+                          -4.32964e-17 -0.707107 0.707107,
+                          0.5 -0.5 0.707107,
+                          -4.32964e-17 -0.707107 0.707107,
+                          -0.5 -0.5 0.707107,
+                          -0.5 -0.5 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.5 -0.5 0.707107,
+                          -4.32964e-17 -0.707107 0.707107,
+                          -0.5 -0.5 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.5 -0.5 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.5 0.5 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          1 -1.22461e-16 0,
+                          1 -1.22461e-16 0,
+                          0.707107 -0.707107 4.32964e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          0.707107 0.707107 -4.32964e-17,
+                          1 1.22461e-16 0,
+                          0.707107 0.707107 -4.32964e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          -6.12303e-17 -1 6.12303e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          1 -1.22461e-16 0,
+                          0.707107 -0.707107 4.32964e-17,
+                          -6.12303e-17 -1 6.12303e-17,
+                          -6.12303e-17 -1 6.12303e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -6.12303e-17 -1 6.12303e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          -6.12303e-17 -1 6.12303e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -1 0 0,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -6.12303e-17 -1 6.12303e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -1 0 0,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -1 0 0,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.5 0.5 0.707107,
+                          -0.5 0.5 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -1 0 0,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0.707107 0.707107 -4.32964e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          -6.12303e-17 1 -6.12303e-17,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          -6.12303e-17 1 -6.12303e-17,
+                          -6.12303e-17 1 -6.12303e-17,
+                          -0.707107 0.707107 -4.32964e-17,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0.707107 0.707107 -4.32964e-17,
+                          -6.12303e-17 1 -6.12303e-17,
+                          -6.12303e-17 1 -6.12303e-17,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          -6.12303e-17 1 -6.12303e-17,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -0.707107 0.707107 -4.32964e-17,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          1 0 0,
+                          1 0 0,
+                          0.809017 -0.587785 3.59903e-17,
+                          0.809017 0.587785 -3.59903e-17,
+                          0.809017 0.587785 -3.59903e-17,
+                          1 0 0,
+                          1 0 0,
+                          0.809017 0.587785 -3.59903e-17,
+                          1 0 0,
+                          0.809017 -0.587785 3.59903e-17,
+                          0.809017 -0.587785 3.59903e-17,
+                          0.309017 -0.951057 5.82335e-17,
+                          0.809017 -0.587785 3.59903e-17,
+                          1 0 0,
+                          0.809017 -0.587785 3.59903e-17,
+                          0.309017 -0.951057 5.82335e-17,
+                          0.309017 -0.951057 5.82335e-17,
+                          -0.309017 -0.951057 5.82335e-17,
+                          0.309017 -0.951057 5.82335e-17,
+                          0.809017 -0.587785 3.59903e-17,
+                          0.309017 -0.951057 5.82335e-17,
+                          -0.309017 -0.951057 5.82335e-17,
+                          -0.309017 -0.951057 5.82335e-17,
+                          -0.809017 -0.587785 3.59903e-17,
+                          -0.309017 -0.951057 5.82335e-17,
+                          0.309017 -0.951057 5.82335e-17,
+                          -0.309017 -0.951057 5.82335e-17,
+                          -0.809017 -0.587785 3.59903e-17,
+                          -0.809017 -0.587785 3.59903e-17,
+                          -1 -1.22461e-16 0,
+                          -0.809017 -0.587785 3.59903e-17,
+                          -0.309017 -0.951057 5.82335e-17,
+                          -0.809017 -0.587785 3.59903e-17,
+                          -1 1.22461e-16 0,
+                          -1 1.22461e-16 0,
+                          -0.809017 0.587785 -3.59903e-17,
+                          -0.809017 -0.587785 3.59903e-17,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -0.809017 0.587785 -3.59903e-17,
+                          -0.809017 0.587785 -3.59903e-17,
+                          -0.309017 0.951057 -5.82335e-17,
+                          -0.809017 0.587785 -3.59903e-17,
+                          -1 1.22461e-16 0,
+                          -0.809017 0.587785 -3.59903e-17,
+                          -0.309017 0.951057 -5.82335e-17,
+                          -0.309017 0.951057 -5.82335e-17,
+                          0.309017 0.951057 -5.82335e-17,
+                          -0.309017 0.951057 -5.82335e-17,
+                          -0.809017 0.587785 -3.59903e-17,
+                          -0.309017 0.951057 -5.82335e-17,
+                          0.309017 0.951057 -5.82335e-17,
+                          0.309017 0.951057 -5.82335e-17,
+                          0.809017 0.587785 -3.59903e-17,
+                          0.309017 0.951057 -5.82335e-17,
+                          -0.309017 0.951057 -5.82335e-17,
+                          0.309017 0.951057 -5.82335e-17,
+                          0.809017 0.587785 -3.59903e-17,
+                          0.309017 0.951057 -5.82335e-17,
+                          0.809017 0.587785 -3.59903e-17,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.572061 0.415627 -0.707107,
+                          -0.653282 -0.270598 -0.707107,
+                          -0.707107 -1.29889e-16 -0.707107,
+                          -0.707107 -1.29889e-16 -0.707107,
+                          -0.653282 -0.270598 -0.707107,
+                          -0.572061 -0.415627 -0.707107,
+                          -0.707107 -1.29889e-16 -0.707107,
+                          -0.5 0.5 -0.707107,
+                          -0.572061 0.415627 -0.707107,
+                          -0.218508 0.672499 -0.707107,
+                          -0.653282 0.270598 -0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.572061 0.415627 -0.707107,
+                          -0.5 0.5 -0.707107,
+                          -0.653282 0.270598 -0.707107,
+                          -0.572061 0.415627 -0.707107,
+                          4.32964e-17 0.707107 -0.707107,
+                          -0.218508 0.672499 -0.707107,
+                          0.218508 0.672499 -0.707107,
+                          -0.270598 0.653282 -0.707107,
+                          -0.5 0.5 -0.707107,
+                          -0.218508 0.672499 -0.707107,
+                          4.32964e-17 0.707107 -0.707107,
+                          -0.270598 0.653282 -0.707107,
+                          -0.218508 0.672499 -0.707107,
+                          0.270598 0.653282 -0.707107,
+                          0.218508 0.672499 -0.707107,
+                          0.572061 0.415627 -0.707107,
+                          0.270598 0.653282 -0.707107,
+                          4.32964e-17 0.707107 -0.707107,
+                          0.218508 0.672499 -0.707107,
+                          0.653282 0.270598 -0.707107,
+                          0.572061 0.415627 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.5 0.5 -0.707107,
+                          0.270598 0.653282 -0.707107,
+                          0.572061 0.415627 -0.707107,
+                          0.653282 0.270598 -0.707107,
+                          0.5 0.5 -0.707107,
+                          0.572061 0.415627 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.653282 0.270598 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.572061 -0.415627 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.653282 -0.270598 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.572061 -0.415627 -0.707107,
+                          -4.32964e-17 0.707107 0.707107,
+                          -4.32964e-17 0.707107 0.707107,
+                          -0.5 0.5 0.707107,
+                          -0.5 0.5 0.707107,
+                          -4.32964e-17 0.707107 0.707107,
+                          -0.5 0.5 0.707107,
+                          0.5 0.5 0.707107,
+                          0.5 0.5 0.707107,
+                          -4.32964e-17 0.707107 0.707107,
+                          -4.32964e-17 0.707107 0.707107,
+                          0.5 0.5 0.707107,
+                          -4.32964e-17 0.707107 0.707107,
+                          0.5 -0.5 -0.707107,
+                          0.572061 -0.415627 -0.707107,
+                          0.218508 -0.672499 -0.707107,
+                          0.5 -0.5 -0.707107,
+                          0.653282 -0.270598 -0.707107,
+                          0.572061 -0.415627 -0.707107,
+                          4.32964e-17 -0.707107 -0.707107,
+                          0.218508 -0.672499 -0.707107,
+                          -0.218508 -0.672499 -0.707107,
+                          0.270598 -0.653282 -0.707107,
+                          0.5 -0.5 -0.707107,
+                          0.218508 -0.672499 -0.707107,
+                          4.32964e-17 -0.707107 -0.707107,
+                          0.270598 -0.653282 -0.707107,
+                          0.218508 -0.672499 -0.707107,
+                          -0.270598 -0.653282 -0.707107,
+                          -0.218508 -0.672499 -0.707107,
+                          -0.572061 -0.415627 -0.707107,
+                          -0.270598 -0.653282 -0.707107,
+                          4.32964e-17 -0.707107 -0.707107,
+                          -0.218508 -0.672499 -0.707107,
+                          -0.5 -0.5 -0.707107,
+                          -0.270598 -0.653282 -0.707107,
+                          -0.572061 -0.415627 -0.707107,
+                          -0.653282 -0.270598 -0.707107,
+                          -0.5 -0.5 -0.707107,
+                          -0.572061 -0.415627 -0.707107 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 16.5 16.5 -23.5,
+                          -16.5 16.5 -30,
+                          -16.5 16.5 -23.5,
+                          -16.5 -16.5 -30,
+                          -16.5 16.5 -23.5,
+                          -16.5 16.5 -30,
+                          -4.63525 14.2658 -23.5,
+                          16.5 16.5 -23.5,
+                          -16.5 16.5 -23.5,
+                          -16.5 -16.5 -30,
+                          -16.5 -16.5 -23.5,
+                          -16.5 16.5 -23.5,
+                          -15 -1.43891e-15 -23.5,
+                          -16.5 16.5 -23.5,
+                          -16.5 -16.5 -23.5,
+                          -12.1353 8.81678 -23.5,
+                          -4.63525 14.2658 -23.5,
+                          -16.5 16.5 -23.5,
+                          -15 -1.43891e-15 -23.5,
+                          -12.1353 8.81678 -23.5,
+                          -16.5 16.5 -23.5,
+                          16.5 16.5 -23.5,
+                          16.5 16.5 -30,
+                          -16.5 16.5 -30,
+                          4.40293 13.5525 -30,
+                          -16.5 16.5 -30,
+                          16.5 16.5 -30,
+                          -14.25 -1.83691e-15 -30,
+                          -16.5 -16.5 -30,
+                          -16.5 16.5 -30,
+                          -11.5278 8.37671 -30,
+                          -14.25 -1.83691e-15 -30,
+                          -16.5 16.5 -30,
+                          -4.40293 13.5525 -30,
+                          -11.5278 8.37671 -30,
+                          -16.5 16.5 -30,
+                          4.40293 13.5525 -30,
+                          -4.40293 13.5525 -30,
+                          -16.5 16.5 -30,
+                          16.5 -16.5 -23.5,
+                          16.5 16.5 -30,
+                          16.5 16.5 -23.5,
+                          16.5 -16.5 -30,
+                          16.5 16.5 -30,
+                          16.5 -16.5 -23.5,
+                          14.25 -1.83691e-15 -30,
+                          16.5 16.5 -30,
+                          16.5 -16.5 -30,
+                          11.5278 8.37671 -30,
+                          16.5 16.5 -30,
+                          14.25 -1.83691e-15 -30,
+                          11.5278 8.37671 -30,
+                          4.40293 13.5525 -30,
+                          16.5 16.5 -30,
+                          15 -1.43891e-15 -23.5,
+                          16.5 -16.5 -23.5,
+                          16.5 16.5 -23.5,
+                          12.1353 8.81678 -23.5,
+                          15 -1.43891e-15 -23.5,
+                          16.5 16.5 -23.5,
+                          4.63525 14.2658 -23.5,
+                          12.1353 8.81678 -23.5,
+                          16.5 16.5 -23.5,
+                          -4.63525 14.2658 -23.5,
+                          4.63525 14.2658 -23.5,
+                          16.5 16.5 -23.5,
+                          16.5 -16.5 -30,
+                          16.5 -16.5 -23.5,
+                          -16.5 -16.5 -23.5,
+                          4.63525 -14.2658 -23.5,
+                          -16.5 -16.5 -23.5,
+                          16.5 -16.5 -23.5,
+                          -16.5 -16.5 -30,
+                          16.5 -16.5 -30,
+                          -16.5 -16.5 -23.5,
+                          -12.1353 -8.81678 -23.5,
+                          -15 -1.43891e-15 -23.5,
+                          -16.5 -16.5 -23.5,
+                          -4.63525 -14.2658 -23.5,
+                          -12.1353 -8.81678 -23.5,
+                          -16.5 -16.5 -23.5,
+                          4.63525 -14.2658 -23.5,
+                          -4.63525 -14.2658 -23.5,
+                          -16.5 -16.5 -23.5,
+                          12.1353 -8.81678 -23.5,
+                          16.5 -16.5 -23.5,
+                          15 -1.43891e-15 -23.5,
+                          12.1353 -8.81678 -23.5,
+                          4.63525 -14.2658 -23.5,
+                          16.5 -16.5 -23.5,
+                          -4.40293 -13.5525 -30,
+                          16.5 -16.5 -30,
+                          -16.5 -16.5 -30,
+                          11.5278 -8.37671 -30,
+                          14.25 -1.83691e-15 -30,
+                          16.5 -16.5 -30,
+                          4.40293 -13.5525 -30,
+                          11.5278 -8.37671 -30,
+                          16.5 -16.5 -30,
+                          -4.40293 -13.5525 -30,
+                          4.40293 -13.5525 -30,
+                          16.5 -16.5 -30,
+                          -11.5278 -8.37671 -30,
+                          -4.40293 -13.5525 -30,
+                          -16.5 -16.5 -30,
+                          -14.25 -1.83691e-15 -30,
+                          -11.5278 -8.37671 -30,
+                          -16.5 -16.5 -30,
+                          15 -1.71445e-15 -28,
+                          15 -1.43891e-15 -23.5,
+                          12.1353 8.81678 -23.5,
+                          12.1345 -8.81759 -28,
+                          12.1353 -8.81678 -23.5,
+                          15 -1.43891e-15 -23.5,
+                          12.1345 -8.81759 -28,
+                          15 -1.43891e-15 -23.5,
+                          15 -1.71445e-15 -28,
+                          12.1345 8.81759 -28,
+                          12.1353 8.81678 -23.5,
+                          4.63525 14.2658 -23.5,
+                          12.1345 8.81759 -28,
+                          15 -1.71445e-15 -28,
+                          12.1353 8.81678 -23.5,
+                          4.63466 14.2658 -28,
+                          4.63525 14.2658 -23.5,
+                          -4.63525 14.2658 -23.5,
+                          12.1345 8.81759 -28,
+                          4.63525 14.2658 -23.5,
+                          4.63466 14.2658 -28,
+                          -4.63466 14.2658 -28,
+                          -4.63525 14.2658 -23.5,
+                          -12.1353 8.81678 -23.5,
+                          4.63466 14.2658 -28,
+                          -4.63525 14.2658 -23.5,
+                          -4.63466 14.2658 -28,
+                          -12.1345 8.81759 -28,
+                          -12.1353 8.81678 -23.5,
+                          -15 -1.43891e-15 -23.5,
+                          -4.63466 14.2658 -28,
+                          -12.1353 8.81678 -23.5,
+                          -12.1345 8.81759 -28,
+                          -15 -1.71445e-15 -28,
+                          -15 -1.43891e-15 -23.5,
+                          -12.1353 -8.81678 -23.5,
+                          -12.1345 8.81759 -28,
+                          -15 -1.43891e-15 -23.5,
+                          -15 -1.71445e-15 -28,
+                          -12.1345 -8.81759 -28,
+                          -12.1353 -8.81678 -23.5,
+                          -4.63525 -14.2658 -23.5,
+                          -15 -1.71445e-15 -28,
+                          -12.1353 -8.81678 -23.5,
+                          -12.1345 -8.81759 -28,
+                          -4.63466 -14.2658 -28,
+                          -4.63525 -14.2658 -23.5,
+                          4.63525 -14.2658 -23.5,
+                          -12.1345 -8.81759 -28,
+                          -4.63525 -14.2658 -23.5,
+                          -4.63466 -14.2658 -28,
+                          4.63466 -14.2658 -28,
+                          4.63525 -14.2658 -23.5,
+                          12.1353 -8.81678 -23.5,
+                          -4.63466 -14.2658 -28,
+                          4.63525 -14.2658 -23.5,
+                          4.63466 -14.2658 -28,
+                          4.63466 -14.2658 -28,
+                          12.1353 -8.81678 -23.5,
+                          12.1345 -8.81759 -28,
+                          11.5485 -4.78296 -65.8,
+                          6.71737 -6.71737 -65.8,
+                          9.5 -4.02895e-15 -65.8,
+                          9.5 -3.55136e-15 -58,
+                          9.5 -4.02895e-15 -65.8,
+                          6.71737 -6.71737 -65.8,
+                          12.5 -4.02895e-15 -65.8,
+                          9.5 -4.02895e-15 -65.8,
+                          6.71737 6.71737 -65.8,
+                          6.71808 6.71675 -58,
+                          6.71737 6.71737 -65.8,
+                          9.5 -4.02895e-15 -65.8,
+                          11.5485 -4.78296 -65.8,
+                          9.5 -4.02895e-15 -65.8,
+                          12.5 -4.02895e-15 -65.8,
+                          9.5 -3.55136e-15 -58,
+                          6.71808 6.71675 -58,
+                          9.5 -4.02895e-15 -65.8,
+                          8.83812 -8.83937 -65.8,
+                          -1e-20 -9.5 -65.8,
+                          6.71737 -6.71737 -65.8,
+                          6.71808 -6.71675 -58,
+                          6.71737 -6.71737 -65.8,
+                          -1e-20 -9.5 -65.8,
+                          11.5485 -4.78296 -65.8,
+                          8.83812 -8.83937 -65.8,
+                          6.71737 -6.71737 -65.8,
+                          6.71808 -6.71675 -58,
+                          9.5 -3.55136e-15 -58,
+                          6.71737 -6.71737 -65.8,
+                          -8.83812 -8.83937 -65.8,
+                          -6.71737 -6.71737 -65.8,
+                          -1e-20 -9.5 -65.8,
+                          6.10613e-16 -9.49974 -58,
+                          -1e-20 -9.5 -65.8,
+                          -6.71737 -6.71737 -65.8,
+                          4.78424 -11.5482 -65.8,
+                          -8.83812 -8.83937 -65.8,
+                          -1e-20 -9.5 -65.8,
+                          8.83812 -8.83937 -65.8,
+                          4.78424 -11.5482 -65.8,
+                          -1e-20 -9.5 -65.8,
+                          6.71808 -6.71675 -58,
+                          -1e-20 -9.5 -65.8,
+                          6.10613e-16 -9.49974 -58,
+                          -12.5 -4.02895e-15 -65.8,
+                          -9.5 -4.02895e-15 -65.8,
+                          -6.71737 -6.71737 -65.8,
+                          -6.71808 -6.71675 -58,
+                          -6.71737 -6.71737 -65.8,
+                          -9.5 -4.02895e-15 -65.8,
+                          -11.5485 -4.78296 -65.8,
+                          -12.5 -4.02895e-15 -65.8,
+                          -6.71737 -6.71737 -65.8,
+                          -8.83812 -8.83937 -65.8,
+                          -11.5485 -4.78296 -65.8,
+                          -6.71737 -6.71737 -65.8,
+                          6.10613e-16 -9.49974 -58,
+                          -6.71737 -6.71737 -65.8,
+                          -6.71808 -6.71675 -58,
+                          -11.5485 4.78296 -65.8,
+                          -6.71737 6.71737 -65.8,
+                          -9.5 -4.02895e-15 -65.8,
+                          -9.5 -3.55136e-15 -58,
+                          -9.5 -4.02895e-15 -65.8,
+                          -6.71737 6.71737 -65.8,
+                          -12.5 -4.02895e-15 -65.8,
+                          -11.5485 4.78296 -65.8,
+                          -9.5 -4.02895e-15 -65.8,
+                          -6.71808 -6.71675 -58,
+                          -9.5 -4.02895e-15 -65.8,
+                          -9.5 -3.55136e-15 -58,
+                          -8.83812 8.83937 -65.8,
+                          -1e-20 9.5 -65.8,
+                          -6.71737 6.71737 -65.8,
+                          -6.71808 6.71675 -58,
+                          -6.71737 6.71737 -65.8,
+                          -1e-20 9.5 -65.8,
+                          -11.5485 4.78296 -65.8,
+                          -8.83812 8.83937 -65.8,
+                          -6.71737 6.71737 -65.8,
+                          -6.71808 6.71675 -58,
+                          -9.5 -3.55136e-15 -58,
+                          -6.71737 6.71737 -65.8,
+                          8.83812 8.83937 -65.8,
+                          6.71737 6.71737 -65.8,
+                          -1e-20 9.5 -65.8,
+                          6.10613e-16 9.49974 -58,
+                          -1e-20 9.5 -65.8,
+                          6.71737 6.71737 -65.8,
+                          -4.78424 11.5482 -65.8,
+                          8.83812 8.83937 -65.8,
+                          -1e-20 9.5 -65.8,
+                          -8.83812 8.83937 -65.8,
+                          -4.78424 11.5482 -65.8,
+                          -1e-20 9.5 -65.8,
+                          6.10613e-16 9.49974 -58,
+                          -6.71808 6.71675 -58,
+                          -1e-20 9.5 -65.8,
+                          11.5485 4.78296 -65.8,
+                          12.5 -4.02895e-15 -65.8,
+                          6.71737 6.71737 -65.8,
+                          8.83812 8.83937 -65.8,
+                          11.5485 4.78296 -65.8,
+                          6.71737 6.71737 -65.8,
+                          6.71808 6.71675 -58,
+                          6.10613e-16 9.49974 -58,
+                          6.71737 6.71737 -65.8,
+                          12.5 -2.60229e-15 -42.5,
+                          12.5 -4.02895e-15 -65.8,
+                          11.5485 4.78296 -65.8,
+                          11.5485 -4.78354 -42.5,
+                          11.5485 -4.78296 -65.8,
+                          12.5 -4.02895e-15 -65.8,
+                          11.5485 -4.78354 -42.5,
+                          12.5 -4.02895e-15 -65.8,
+                          12.5 -2.60229e-15 -42.5,
+                          11.5485 4.78354 -42.5,
+                          11.5485 4.78296 -65.8,
+                          8.83812 8.83937 -65.8,
+                          12.5 -2.60229e-15 -42.5,
+                          11.5485 4.78296 -65.8,
+                          11.5485 4.78354 -42.5,
+                          -4.78424 11.5482 -65.8,
+                          4.78424 11.5482 -65.8,
+                          8.83812 8.83937 -65.8,
+                          8.83883 8.83883 -42.5,
+                          8.83812 8.83937 -65.8,
+                          4.78424 11.5482 -65.8,
+                          11.5485 4.78354 -42.5,
+                          8.83812 8.83937 -65.8,
+                          8.83883 8.83883 -42.5,
+                          -4.78424 11.5482 -65.8,
+                          -1e-20 12.4998 -65.8,
+                          4.78424 11.5482 -65.8,
+                          4.78354 11.5485 -42.5,
+                          4.78424 11.5482 -65.8,
+                          -1e-20 12.4998 -65.8,
+                          8.83883 8.83883 -42.5,
+                          4.78424 11.5482 -65.8,
+                          4.78354 11.5485 -42.5,
+                          7.65369e-16 12.5 -42.5,
+                          -1e-20 12.4998 -65.8,
+                          -4.78424 11.5482 -65.8,
+                          4.78354 11.5485 -42.5,
+                          -1e-20 12.4998 -65.8,
+                          7.65369e-16 12.5 -42.5,
+                          -4.78354 11.5485 -42.5,
+                          -4.78424 11.5482 -65.8,
+                          -8.83812 8.83937 -65.8,
+                          7.65369e-16 12.5 -42.5,
+                          -4.78424 11.5482 -65.8,
+                          -4.78354 11.5485 -42.5,
+                          -8.83883 8.83883 -42.5,
+                          -8.83812 8.83937 -65.8,
+                          -11.5485 4.78296 -65.8,
+                          -4.78354 11.5485 -42.5,
+                          -8.83812 8.83937 -65.8,
+                          -8.83883 8.83883 -42.5,
+                          -11.5485 4.78354 -42.5,
+                          -11.5485 4.78296 -65.8,
+                          -12.5 -4.02895e-15 -65.8,
+                          -8.83883 8.83883 -42.5,
+                          -11.5485 4.78296 -65.8,
+                          -11.5485 4.78354 -42.5,
+                          -12.5 -1.07153e-15 -42.5,
+                          -12.5 -4.02895e-15 -65.8,
+                          -11.5485 -4.78296 -65.8,
+                          -11.5485 4.78354 -42.5,
+                          -12.5 -4.02895e-15 -65.8,
+                          -12.5 -1.07153e-15 -42.5,
+                          -11.5485 -4.78354 -42.5,
+                          -11.5485 -4.78296 -65.8,
+                          -8.83812 -8.83937 -65.8,
+                          -11.5485 -4.78354 -42.5,
+                          -12.5 -1.07153e-15 -42.5,
+                          -11.5485 -4.78296 -65.8,
+                          4.78424 -11.5482 -65.8,
+                          -4.78424 -11.5482 -65.8,
+                          -8.83812 -8.83937 -65.8,
+                          -8.83883 -8.83883 -42.5,
+                          -8.83812 -8.83937 -65.8,
+                          -4.78424 -11.5482 -65.8,
+                          -11.5485 -4.78354 -42.5,
+                          -8.83812 -8.83937 -65.8,
+                          -8.83883 -8.83883 -42.5,
+                          4.78424 -11.5482 -65.8,
+                          -1e-20 -12.4998 -65.8,
+                          -4.78424 -11.5482 -65.8,
+                          -4.78354 -11.5485 -42.5,
+                          -4.78424 -11.5482 -65.8,
+                          -1e-20 -12.4998 -65.8,
+                          -8.83883 -8.83883 -42.5,
+                          -4.78424 -11.5482 -65.8,
+                          -4.78354 -11.5485 -42.5,
+                          7.65369e-16 -12.5 -42.5,
+                          -1e-20 -12.4998 -65.8,
+                          4.78424 -11.5482 -65.8,
+                          -4.78354 -11.5485 -42.5,
+                          -1e-20 -12.4998 -65.8,
+                          7.65369e-16 -12.5 -42.5,
+                          4.78354 -11.5485 -42.5,
+                          4.78424 -11.5482 -65.8,
+                          8.83812 -8.83937 -65.8,
+                          7.65369e-16 -12.5 -42.5,
+                          4.78424 -11.5482 -65.8,
+                          4.78354 -11.5485 -42.5,
+                          8.83883 -8.83883 -42.5,
+                          8.83812 -8.83937 -65.8,
+                          11.5485 -4.78296 -65.8,
+                          4.78354 -11.5485 -42.5,
+                          8.83812 -8.83937 -65.8,
+                          8.83883 -8.83883 -42.5,
+                          8.83883 -8.83883 -42.5,
+                          11.5485 -4.78296 -65.8,
+                          11.5485 -4.78354 -42.5,
+                          -8 -3.55136e-15 -58,
+                          -9.5 -3.55136e-15 -58,
+                          -6.71808 6.71675 -58,
+                          -5.65685 -5.65685 -58,
+                          -6.71808 -6.71675 -58,
+                          -9.5 -3.55136e-15 -58,
+                          -8 -3.55136e-15 -58,
+                          -5.65685 -5.65685 -58,
+                          -9.5 -3.55136e-15 -58,
+                          4.89833e-16 8 -58,
+                          -6.71808 6.71675 -58,
+                          6.10613e-16 9.49974 -58,
+                          -5.65685 5.65685 -58,
+                          -8 -3.55136e-15 -58,
+                          -6.71808 6.71675 -58,
+                          4.89833e-16 8 -58,
+                          -5.65685 5.65685 -58,
+                          -6.71808 6.71675 -58,
+                          4.89833e-16 8 -58,
+                          6.10613e-16 9.49974 -58,
+                          6.71808 6.71675 -58,
+                          5.65685 5.65685 -58,
+                          6.71808 6.71675 -58,
+                          9.5 -3.55136e-15 -58,
+                          5.65685 5.65685 -58,
+                          4.89833e-16 8 -58,
+                          6.71808 6.71675 -58,
+                          8 -3.55136e-15 -58,
+                          9.5 -3.55136e-15 -58,
+                          6.71808 -6.71675 -58,
+                          5.65685 5.65685 -58,
+                          9.5 -3.55136e-15 -58,
+                          8 -3.55136e-15 -58,
+                          4.89833e-16 -8 -58,
+                          6.10613e-16 -9.49974 -58,
+                          -6.71808 -6.71675 -58,
+                          -5.65685 -5.65685 -58,
+                          4.89833e-16 -8 -58,
+                          -6.71808 -6.71675 -58,
+                          4.89833e-16 -8 -58,
+                          6.71808 -6.71675 -58,
+                          6.10613e-16 -9.49974 -58,
+                          5.65685 -5.65685 -58,
+                          8 -3.55136e-15 -58,
+                          6.71808 -6.71675 -58,
+                          4.89833e-16 -8 -58,
+                          5.65685 -5.65685 -58,
+                          6.71808 -6.71675 -58,
+                          8 -3.00029e-15 -49,
+                          8 -3.55136e-15 -58,
+                          5.65685 -5.65685 -58,
+                          5.65685 5.65685 -49,
+                          5.65685 5.65685 -58,
+                          8 -3.55136e-15 -58,
+                          8 -3.00029e-15 -49,
+                          5.65685 5.65685 -49,
+                          8 -3.55136e-15 -58,
+                          5.65685 -5.65685 -49,
+                          5.65685 -5.65685 -58,
+                          4.89833e-16 -8 -58,
+                          5.65685 -5.65685 -49,
+                          8 -3.00029e-15 -49,
+                          5.65685 -5.65685 -58,
+                          4.89833e-16 -8 -49,
+                          4.89833e-16 -8 -58,
+                          -5.65685 -5.65685 -58,
+                          5.65685 -5.65685 -49,
+                          4.89833e-16 -8 -58,
+                          4.89833e-16 -8 -49,
+                          -5.65685 -5.65685 -49,
+                          -5.65685 -5.65685 -58,
+                          -8 -3.55136e-15 -58,
+                          4.89833e-16 -8 -49,
+                          -5.65685 -5.65685 -58,
+                          -5.65685 -5.65685 -49,
+                          -8 -3.00029e-15 -49,
+                          -8 -3.55136e-15 -58,
+                          -5.65685 5.65685 -58,
+                          -5.65685 -5.65685 -49,
+                          -8 -3.55136e-15 -58,
+                          -8 -3.00029e-15 -49,
+                          -5.65685 5.65685 -49,
+                          -5.65685 5.65685 -58,
+                          4.89833e-16 8 -58,
+                          -5.65685 5.65685 -49,
+                          -8 -3.00029e-15 -49,
+                          -5.65685 5.65685 -58,
+                          4.89833e-16 8 -49,
+                          4.89833e-16 8 -58,
+                          5.65685 5.65685 -58,
+                          4.89833e-16 8 -49,
+                          -5.65685 5.65685 -49,
+                          4.89833e-16 8 -58,
+                          5.65685 5.65685 -49,
+                          4.89833e-16 8 -49,
+                          5.65685 5.65685 -58,
+                          -9.5 -3.00029e-15 -49,
+                          -8 -3.00029e-15 -49,
+                          -5.65685 5.65685 -49,
+                          -6.71808 -6.71675 -49,
+                          -5.65685 -5.65685 -49,
+                          -8 -3.00029e-15 -49,
+                          -9.5 -3.00029e-15 -49,
+                          -6.71808 -6.71675 -49,
+                          -8 -3.00029e-15 -49,
+                          -6.71808 6.71675 -49,
+                          -5.65685 5.65685 -49,
+                          4.89833e-16 8 -49,
+                          -6.71808 6.71675 -49,
+                          -9.5 -3.00029e-15 -49,
+                          -5.65685 5.65685 -49,
+                          6.71808 6.71675 -49,
+                          4.89833e-16 8 -49,
+                          5.65685 5.65685 -49,
+                          6.10613e-16 9.49974 -49,
+                          -6.71808 6.71675 -49,
+                          4.89833e-16 8 -49,
+                          6.71808 6.71675 -49,
+                          6.10613e-16 9.49974 -49,
+                          4.89833e-16 8 -49,
+                          6.71808 6.71675 -49,
+                          5.65685 5.65685 -49,
+                          8 -3.00029e-15 -49,
+                          9.5 -3.00029e-15 -49,
+                          8 -3.00029e-15 -49,
+                          5.65685 -5.65685 -49,
+                          6.71808 6.71675 -49,
+                          8 -3.00029e-15 -49,
+                          9.5 -3.00029e-15 -49,
+                          -6.71808 -6.71675 -49,
+                          4.89833e-16 -8 -49,
+                          -5.65685 -5.65685 -49,
+                          6.71808 -6.71675 -49,
+                          5.65685 -5.65685 -49,
+                          4.89833e-16 -8 -49,
+                          6.10613e-16 -9.49974 -49,
+                          6.71808 -6.71675 -49,
+                          4.89833e-16 -8 -49,
+                          -6.71808 -6.71675 -49,
+                          6.10613e-16 -9.49974 -49,
+                          4.89833e-16 -8 -49,
+                          6.71808 -6.71675 -49,
+                          9.5 -3.00029e-15 -49,
+                          5.65685 -5.65685 -49,
+                          9.5 -2.50065e-15 -40.84,
+                          9.5 -3.00029e-15 -49,
+                          6.71808 -6.71675 -49,
+                          6.71751 6.71751 -40.84,
+                          6.71808 6.71675 -49,
+                          9.5 -3.00029e-15 -49,
+                          9.5 -2.50065e-15 -40.84,
+                          6.71751 6.71751 -40.84,
+                          9.5 -3.00029e-15 -49,
+                          6.71751 -6.71751 -40.84,
+                          6.71808 -6.71675 -49,
+                          6.10613e-16 -9.49974 -49,
+                          6.71751 -6.71751 -40.84,
+                          9.5 -2.50065e-15 -40.84,
+                          6.71808 -6.71675 -49,
+                          5.81678e-16 -9.5 -40.84,
+                          6.10613e-16 -9.49974 -49,
+                          -6.71808 -6.71675 -49,
+                          6.71751 -6.71751 -40.84,
+                          6.10613e-16 -9.49974 -49,
+                          5.81678e-16 -9.5 -40.84,
+                          -6.71751 -6.71751 -40.84,
+                          -6.71808 -6.71675 -49,
+                          -9.5 -3.00029e-15 -49,
+                          5.81678e-16 -9.5 -40.84,
+                          -6.71808 -6.71675 -49,
+                          -6.71751 -6.71751 -40.84,
+                          -9.5 -1.33727e-15 -40.84,
+                          -9.5 -3.00029e-15 -49,
+                          -6.71808 6.71675 -49,
+                          -6.71751 -6.71751 -40.84,
+                          -9.5 -3.00029e-15 -49,
+                          -9.5 -1.33727e-15 -40.84,
+                          -6.71751 6.71751 -40.84,
+                          -6.71808 6.71675 -49,
+                          6.10613e-16 9.49974 -49,
+                          -6.71751 6.71751 -40.84,
+                          -9.5 -1.33727e-15 -40.84,
+                          -6.71808 6.71675 -49,
+                          5.81678e-16 9.5 -40.84,
+                          6.10613e-16 9.49974 -49,
+                          6.71808 6.71675 -49,
+                          5.81678e-16 9.5 -40.84,
+                          -6.71751 6.71751 -40.84,
+                          6.10613e-16 9.49974 -49,
+                          6.71751 6.71751 -40.84,
+                          5.81678e-16 9.5 -40.84,
+                          6.71808 6.71675 -49,
+                          -11 -1.06173e-15 -39.34,
+                          -9.5 -1.33727e-15 -40.84,
+                          -6.71751 6.71751 -40.84,
+                          -7.77817 -7.77817 -39.34,
+                          -9.5 -1.33727e-15 -40.84,
+                          -11 -1.06173e-15 -39.34,
+                          -6.71751 -6.71751 -40.84,
+                          -9.5 -1.33727e-15 -40.84,
+                          -7.77817 -7.77817 -39.34,
+                          -7.77817 7.77817 -39.34,
+                          -6.71751 6.71751 -40.84,
+                          5.81678e-16 9.5 -40.84,
+                          -7.77817 7.77817 -39.34,
+                          -11 -1.06173e-15 -39.34,
+                          -6.71751 6.71751 -40.84,
+                          6.73523e-16 11 -39.34,
+                          5.81678e-16 9.5 -40.84,
+                          6.71751 6.71751 -40.84,
+                          6.73523e-16 11 -39.34,
+                          -7.77817 7.77817 -39.34,
+                          5.81678e-16 9.5 -40.84,
+                          7.77817 7.77817 -39.34,
+                          6.71751 6.71751 -40.84,
+                          9.5 -2.50065e-15 -40.84,
+                          7.77817 7.77817 -39.34,
+                          6.73523e-16 11 -39.34,
+                          6.71751 6.71751 -40.84,
+                          11 -2.4088e-15 -39.34,
+                          7.77817 7.77817 -39.34,
+                          9.5 -2.50065e-15 -40.84,
+                          6.71751 -6.71751 -40.84,
+                          11 -2.4088e-15 -39.34,
+                          9.5 -2.50065e-15 -40.84,
+                          -11 -1.71445e-15 -28,
+                          -11 -1.06173e-15 -39.34,
+                          -7.77817 7.77817 -39.34,
+                          -7.77801 -7.77801 -28,
+                          -11 -1.06173e-15 -39.34,
+                          -11 -1.71445e-15 -28,
+                          -7.77817 -7.77817 -39.34,
+                          -11 -1.06173e-15 -39.34,
+                          -7.77801 -7.77801 -28,
+                          -7.77801 7.77801 -28,
+                          -7.77817 7.77817 -39.34,
+                          6.73523e-16 11 -39.34,
+                          -7.77801 7.77801 -28,
+                          -11 -1.71445e-15 -28,
+                          -7.77817 7.77817 -39.34,
+                          6.73523e-16 11 -28,
+                          6.73523e-16 11 -39.34,
+                          7.77817 7.77817 -39.34,
+                          6.73523e-16 11 -28,
+                          -7.77801 7.77801 -28,
+                          6.73523e-16 11 -39.34,
+                          7.77801 7.77801 -28,
+                          7.77817 7.77817 -39.34,
+                          11 -2.4088e-15 -39.34,
+                          7.77801 7.77801 -28,
+                          6.73523e-16 11 -28,
+                          7.77817 7.77817 -39.34,
+                          11 -1.71445e-15 -28,
+                          7.77801 7.77801 -28,
+                          11 -2.4088e-15 -39.34,
+                          7.77817 -7.77817 -39.34,
+                          11 -1.71445e-15 -28,
+                          11 -2.4088e-15 -39.34,
+                          6.71751 -6.71751 -40.84,
+                          7.77817 -7.77817 -39.34,
+                          11 -2.4088e-15 -39.34,
+                          -15 -1.71445e-15 -28,
+                          -11 -1.71445e-15 -28,
+                          -7.77801 7.77801 -28,
+                          -12.1345 -8.81759 -28,
+                          -7.77801 -7.77801 -28,
+                          -11 -1.71445e-15 -28,
+                          -15 -1.71445e-15 -28,
+                          -12.1345 -8.81759 -28,
+                          -11 -1.71445e-15 -28,
+                          -12.1345 8.81759 -28,
+                          -7.77801 7.77801 -28,
+                          6.73523e-16 11 -28,
+                          -12.1345 8.81759 -28,
+                          -15 -1.71445e-15 -28,
+                          -7.77801 7.77801 -28,
+                          12.1345 8.81759 -28,
+                          6.73523e-16 11 -28,
+                          7.77801 7.77801 -28,
+                          4.63466 14.2658 -28,
+                          -12.1345 8.81759 -28,
+                          6.73523e-16 11 -28,
+                          12.1345 8.81759 -28,
+                          4.63466 14.2658 -28,
+                          6.73523e-16 11 -28,
+                          12.1345 8.81759 -28,
+                          7.77801 7.77801 -28,
+                          11 -1.71445e-15 -28,
+                          15 -1.71445e-15 -28,
+                          11 -1.71445e-15 -28,
+                          7.77801 -7.77801 -28,
+                          7.77817 -7.77817 -39.34,
+                          7.77801 -7.77801 -28,
+                          11 -1.71445e-15 -28,
+                          12.1345 8.81759 -28,
+                          11 -1.71445e-15 -28,
+                          15 -1.71445e-15 -28,
+                          -12.1345 -8.81759 -28,
+                          6.73523e-16 -11 -28,
+                          -7.77801 -7.77801 -28,
+                          -7.77817 -7.77817 -39.34,
+                          -7.77801 -7.77801 -28,
+                          6.73523e-16 -11 -28,
+                          12.1345 -8.81759 -28,
+                          7.77801 -7.77801 -28,
+                          6.73523e-16 -11 -28,
+                          6.73523e-16 -11 -39.34,
+                          6.73523e-16 -11 -28,
+                          7.77801 -7.77801 -28,
+                          -4.63466 -14.2658 -28,
+                          12.1345 -8.81759 -28,
+                          6.73523e-16 -11 -28,
+                          -12.1345 -8.81759 -28,
+                          -4.63466 -14.2658 -28,
+                          6.73523e-16 -11 -28,
+                          -7.77817 -7.77817 -39.34,
+                          6.73523e-16 -11 -28,
+                          6.73523e-16 -11 -39.34,
+                          12.1345 -8.81759 -28,
+                          15 -1.71445e-15 -28,
+                          7.77801 -7.77801 -28,
+                          6.73523e-16 -11 -39.34,
+                          7.77801 -7.77801 -28,
+                          7.77817 -7.77817 -39.34,
+                          -4.63466 -14.2658 -28,
+                          4.63466 -14.2658 -28,
+                          12.1345 -8.81759 -28,
+                          4.63466 14.2658 -28,
+                          -4.63466 14.2658 -28,
+                          -12.1345 8.81759 -28,
+                          14.25 -2.49514e-15 -40.75,
+                          14.25 -1.83691e-15 -30,
+                          11.5278 -8.37671 -30,
+                          11.5285 8.37594 -40.75,
+                          11.5278 8.37671 -30,
+                          14.25 -1.83691e-15 -30,
+                          14.25 -2.49514e-15 -40.75,
+                          11.5285 8.37594 -40.75,
+                          14.25 -1.83691e-15 -30,
+                          11.5285 -8.37594 -40.75,
+                          11.5278 -8.37671 -30,
+                          4.40293 -13.5525 -30,
+                          11.5285 -8.37594 -40.75,
+                          14.25 -2.49514e-15 -40.75,
+                          11.5278 -8.37671 -30,
+                          4.40349 -13.5526 -40.75,
+                          4.40293 -13.5525 -30,
+                          -4.40293 -13.5525 -30,
+                          4.40349 -13.5526 -40.75,
+                          11.5285 -8.37594 -40.75,
+                          4.40293 -13.5525 -30,
+                          -4.40349 -13.5526 -40.75,
+                          -4.40293 -13.5525 -30,
+                          -11.5278 -8.37671 -30,
+                          -4.40349 -13.5526 -40.75,
+                          4.40349 -13.5526 -40.75,
+                          -4.40293 -13.5525 -30,
+                          -11.5285 -8.37594 -40.75,
+                          -11.5278 -8.37671 -30,
+                          -14.25 -1.83691e-15 -30,
+                          -11.5285 -8.37594 -40.75,
+                          -4.40349 -13.5526 -40.75,
+                          -11.5278 -8.37671 -30,
+                          -14.25 -7.50071e-16 -40.75,
+                          -14.25 -1.83691e-15 -30,
+                          -11.5278 8.37671 -30,
+                          -11.5285 -8.37594 -40.75,
+                          -14.25 -1.83691e-15 -30,
+                          -14.25 -7.50071e-16 -40.75,
+                          -11.5285 8.37594 -40.75,
+                          -11.5278 8.37671 -30,
+                          -4.40293 13.5525 -30,
+                          -11.5285 8.37594 -40.75,
+                          -14.25 -7.50071e-16 -40.75,
+                          -11.5278 8.37671 -30,
+                          -4.40349 13.5526 -40.75,
+                          -4.40293 13.5525 -30,
+                          4.40293 13.5525 -30,
+                          -4.40349 13.5526 -40.75,
+                          -11.5285 8.37594 -40.75,
+                          -4.40293 13.5525 -30,
+                          4.40349 13.5526 -40.75,
+                          4.40293 13.5525 -30,
+                          11.5278 8.37671 -30,
+                          4.40349 13.5526 -40.75,
+                          -4.40349 13.5526 -40.75,
+                          4.40293 13.5525 -30,
+                          11.5285 8.37594 -40.75,
+                          4.40349 13.5526 -40.75,
+                          11.5278 8.37671 -30,
+                          -12.5 -1.07153e-15 -42.5,
+                          -14.25 -7.50071e-16 -40.75,
+                          -11.5285 8.37594 -40.75,
+                          -11.5485 -4.78354 -42.5,
+                          -14.25 -7.50071e-16 -40.75,
+                          -12.5 -1.07153e-15 -42.5,
+                          -11.5485 -4.78354 -42.5,
+                          -11.5285 -8.37594 -40.75,
+                          -14.25 -7.50071e-16 -40.75,
+                          -8.83883 8.83883 -42.5,
+                          -11.5285 8.37594 -40.75,
+                          -4.40349 13.5526 -40.75,
+                          -11.5485 4.78354 -42.5,
+                          -12.5 -1.07153e-15 -42.5,
+                          -11.5285 8.37594 -40.75,
+                          -8.83883 8.83883 -42.5,
+                          -11.5485 4.78354 -42.5,
+                          -11.5285 8.37594 -40.75,
+                          7.65369e-16 12.5 -42.5,
+                          -4.40349 13.5526 -40.75,
+                          4.40349 13.5526 -40.75,
+                          -4.78354 11.5485 -42.5,
+                          -8.83883 8.83883 -42.5,
+                          -4.40349 13.5526 -40.75,
+                          7.65369e-16 12.5 -42.5,
+                          -4.78354 11.5485 -42.5,
+                          -4.40349 13.5526 -40.75,
+                          4.78354 11.5485 -42.5,
+                          4.40349 13.5526 -40.75,
+                          11.5285 8.37594 -40.75,
+                          4.78354 11.5485 -42.5,
+                          7.65369e-16 12.5 -42.5,
+                          4.40349 13.5526 -40.75,
+                          11.5485 4.78354 -42.5,
+                          11.5285 8.37594 -40.75,
+                          14.25 -2.49514e-15 -40.75,
+                          8.83883 8.83883 -42.5,
+                          4.78354 11.5485 -42.5,
+                          11.5285 8.37594 -40.75,
+                          11.5485 4.78354 -42.5,
+                          8.83883 8.83883 -42.5,
+                          11.5285 8.37594 -40.75,
+                          12.5 -2.60229e-15 -42.5,
+                          11.5485 4.78354 -42.5,
+                          14.25 -2.49514e-15 -40.75,
+                          11.5285 -8.37594 -40.75,
+                          12.5 -2.60229e-15 -42.5,
+                          14.25 -2.49514e-15 -40.75,
+                          11.5485 -4.78354 -42.5,
+                          12.5 -2.60229e-15 -42.5,
+                          11.5285 -8.37594 -40.75,
+                          5.81678e-16 -9.5 -40.84,
+                          6.73523e-16 -11 -39.34,
+                          7.77817 -7.77817 -39.34,
+                          6.71751 -6.71751 -40.84,
+                          5.81678e-16 -9.5 -40.84,
+                          7.77817 -7.77817 -39.34,
+                          -6.71751 -6.71751 -40.84,
+                          -7.77817 -7.77817 -39.34,
+                          6.73523e-16 -11 -39.34,
+                          5.81678e-16 -9.5 -40.84,
+                          -6.71751 -6.71751 -40.84,
+                          6.73523e-16 -11 -39.34,
+                          8.83883 -8.83883 -42.5,
+                          11.5285 -8.37594 -40.75,
+                          4.40349 -13.5526 -40.75,
+                          8.83883 -8.83883 -42.5,
+                          11.5485 -4.78354 -42.5,
+                          11.5285 -8.37594 -40.75,
+                          7.65369e-16 -12.5 -42.5,
+                          4.40349 -13.5526 -40.75,
+                          -4.40349 -13.5526 -40.75,
+                          4.78354 -11.5485 -42.5,
+                          8.83883 -8.83883 -42.5,
+                          4.40349 -13.5526 -40.75,
+                          7.65369e-16 -12.5 -42.5,
+                          4.78354 -11.5485 -42.5,
+                          4.40349 -13.5526 -40.75,
+                          -4.78354 -11.5485 -42.5,
+                          -4.40349 -13.5526 -40.75,
+                          -11.5285 -8.37594 -40.75,
+                          -4.78354 -11.5485 -42.5,
+                          7.65369e-16 -12.5 -42.5,
+                          -4.40349 -13.5526 -40.75,
+                          -8.83883 -8.83883 -42.5,
+                          -4.78354 -11.5485 -42.5,
+                          -11.5285 -8.37594 -40.75,
+                          -11.5485 -4.78354 -42.5,
+                          -8.83883 -8.83883 -42.5,
+                          -11.5285 -8.37594 -40.75 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.82 0.6 0.24
+    }
+    Separator {
+        Normal {
+            vector      [ 0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.809017 0.587785 -3.59903e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.809017 -0.587785 3.59903e-17,
+                          -0.809017 -0.587785 3.59903e-17,
+                          -1 -2.44921e-16 0,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.809017 -0.587785 3.59903e-17,
+                          -1 -2.44921e-16 0,
+                          -1 -2.44921e-16 0,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.809017 0.587785 -3.59903e-17,
+                          -0.809017 0.587785 -3.59903e-17,
+                          -0.309017 0.951057 -5.82335e-17,
+                          -0.809017 0.587785 -3.59903e-17,
+                          -1 0 0,
+                          -0.809017 0.587785 -3.59903e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.309017 0.951057 -5.82335e-17,
+                          -0.309017 0.951057 -5.82335e-17,
+                          0.309017 0.951057 -5.82335e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.809017 0.587785 -3.59903e-17,
+                          -0.309017 0.951057 -5.82335e-17,
+                          -0.309017 0.951057 -5.82335e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0.309017 0.951057 -5.82335e-17,
+                          0.309017 0.951057 -5.82335e-17,
+                          0.809017 0.587785 -3.59903e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.309017 0.951057 -5.82335e-17,
+                          0.309017 0.951057 -5.82335e-17,
+                          0.309017 0.951057 -5.82335e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0.809017 0.587785 -3.59903e-17,
+                          0.809017 0.587785 -3.59903e-17,
+                          1 1.22461e-16 0,
+                          0.309017 0.951057 -5.82335e-17,
+                          0.809017 0.587785 -3.59903e-17,
+                          0.809017 0.587785 -3.59903e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          0.809017 -0.587785 3.59903e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0.809017 0.587785 -3.59903e-17,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0.809017 -0.587785 3.59903e-17,
+                          0.809017 -0.587785 3.59903e-17,
+                          0.309017 -0.951057 5.82335e-17,
+                          1 1.22461e-16 0,
+                          0.809017 -0.587785 3.59903e-17,
+                          0.809017 -0.587785 3.59903e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0.309017 -0.951057 5.82335e-17,
+                          0.309017 -0.951057 5.82335e-17,
+                          -0.309017 -0.951057 5.82335e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0.809017 -0.587785 3.59903e-17,
+                          0.309017 -0.951057 5.82335e-17,
+                          0.309017 -0.951057 5.82335e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.309017 -0.951057 5.82335e-17,
+                          -0.309017 -0.951057 5.82335e-17,
+                          -0.809017 -0.587785 3.59903e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0.309017 -0.951057 5.82335e-17,
+                          -0.309017 -0.951057 5.82335e-17,
+                          -0.309017 -0.951057 5.82335e-17,
+                          -0.309017 -0.951057 5.82335e-17,
+                          -0.809017 -0.587785 3.59903e-17,
+                          -0.809017 -0.587785 3.59903e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          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.707107 0.707107 -4.32964e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0.707107 0.707107 -4.32964e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -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.707107 -0.707107 4.32964e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          -0.822897 3.47905e-17 0.568191,
+                          -0.822897 3.47905e-17 0.568191,
+                          -0.822897 3.47905e-17 0.568191,
+                          -0.822897 3.47905e-17 0.568191,
+                          -0.822897 3.47905e-17 0.568191,
+                          -0.822897 3.47905e-17 0.568191,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          -0.822897 3.47905e-17 0.568191,
+                          -0.822897 3.47905e-17 0.568191,
+                          -0.822897 3.47905e-17 0.568191,
+                          -0.822897 3.47905e-17 0.568191,
+                          -0.822897 3.47905e-17 0.568191,
+                          -0.822897 3.47905e-17 0.568191,
+                          0.707107 -0.707107 4.32964e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -1 -1.65135e-16 0,
+                          -1 0 0,
+                          -0.866025 0.5 -3.06152e-17,
+                          -0.760951 -0.648809 3.97268e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          -1 -2.44921e-16 0,
+                          -0.760951 -0.648809 3.97268e-17,
+                          -1 -2.44921e-16 0,
+                          -1 -2.44921e-16 0,
+                          -0.760955 0.648805 -3.97265e-17,
+                          -0.866025 0.5 -3.06152e-17,
+                          -0.5 0.866025 -5.3027e-17,
+                          -0.760955 0.648805 -3.97265e-17,
+                          -1 -1.65135e-16 0,
+                          -0.866025 0.5 -3.06152e-17,
+                          -0.44736 0.894354 -5.47616e-17,
+                          -0.5 0.866025 -5.3027e-17,
+                          -6.12303e-17 1 -6.12303e-17,
+                          -0.44736 0.894354 -5.47616e-17,
+                          -0.760955 0.648805 -3.97265e-17,
+                          -0.5 0.866025 -5.3027e-17,
+                          -6.12303e-17 1 -6.12303e-17,
+                          -6.12303e-17 1 -6.12303e-17,
+                          0.5 0.866025 -5.3027e-17,
+                          -6.12303e-17 1 -6.12303e-17,
+                          -0.44736 0.894354 -5.47616e-17,
+                          -6.12303e-17 1 -6.12303e-17,
+                          0.707096 0.707117 -4.3297e-17,
+                          0.5 0.866025 -5.3027e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          0.707096 0.707117 -4.3297e-17,
+                          -6.12303e-17 1 -6.12303e-17,
+                          0.5 0.866025 -5.3027e-17,
+                          0.707096 0.707117 -4.3297e-17,
+                          0.866025 0.5 -3.06152e-17,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          0.866025 -0.5 3.06152e-17,
+                          1 1.22461e-16 0,
+                          0.707096 0.707117 -4.3297e-17,
+                          1 1.22461e-16 0,
+                          0.707096 -0.707117 4.3297e-17,
+                          0.866025 -0.5 3.06152e-17,
+                          0.5 -0.866025 5.3027e-17,
+                          0.707096 -0.707117 4.3297e-17,
+                          1 1.22461e-16 0,
+                          0.866025 -0.5 3.06152e-17,
+                          0.707096 -0.707117 4.3297e-17,
+                          0.5 -0.866025 5.3027e-17,
+                          1.83691e-16 -1 6.12303e-17,
+                          1.83691e-16 -1 6.12303e-17,
+                          1.83691e-16 -1 6.12303e-17,
+                          -0.5 -0.866025 5.3027e-17,
+                          0.707096 -0.707117 4.3297e-17,
+                          1.83691e-16 -1 6.12303e-17,
+                          1.83691e-16 -1 6.12303e-17,
+                          -0.760951 -0.648809 3.97268e-17,
+                          -0.5 -0.866025 5.3027e-17,
+                          -0.866025 -0.5 3.06152e-17,
+                          -0.44738 -0.894344 5.4761e-17,
+                          -0.5 -0.866025 5.3027e-17,
+                          -0.760951 -0.648809 3.97268e-17,
+                          1.83691e-16 -1 6.12303e-17,
+                          -0.5 -0.866025 5.3027e-17,
+                          -0.44738 -0.894344 5.4761e-17,
+                          -0.822897 3.47905e-17 0.568191,
+                          -0.822897 3.47905e-17 0.568191,
+                          -0.822897 3.47905e-17 0.568191,
+                          -0.822897 3.47905e-17 0.568191,
+                          -0.822897 3.47905e-17 0.568191,
+                          -0.822897 3.47905e-17 0.568191,
+                          -0.822897 3.47905e-17 0.568191,
+                          -0.822897 3.47905e-17 0.568191,
+                          -0.822897 3.47905e-17 0.568191,
+                          -0.822897 3.47905e-17 0.568191,
+                          -0.822897 3.47905e-17 0.568191,
+                          -0.822897 3.47905e-17 0.568191,
+                          -0.822897 3.47905e-17 0.568191,
+                          -0.822897 3.47905e-17 0.568191,
+                          -0.822897 3.47905e-17 0.568191,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 -1,
+                          0 6.12303e-17 -1,
+                          0 0.5 -0.866025,
+                          0 -0.5 -0.866025,
+                          0 -0.5 -0.866025,
+                          0 6.12303e-17 -1,
+                          0 -0.5 -0.866025,
+                          0 6.12303e-17 -1,
+                          0 6.12303e-17 -1,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 0.866025 -0.5,
+                          0 0.5 -0.866025,
+                          0 6.12303e-17 -1,
+                          0 0.5 -0.866025,
+                          0 0.866025 -0.5,
+                          0 0.866025 -0.5,
+                          0 1 0,
+                          0 0.5 -0.866025,
+                          0 0.866025 -0.5,
+                          0 0.866025 -0.5,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 1 0,
+                          0 1 0,
+                          0 0.866025 0.5,
+                          0 0.866025 -0.5,
+                          0 1 0,
+                          0 1 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.866025 0.5,
+                          0 0.866025 0.5,
+                          0 0.5 0.866025,
+                          0 1 0,
+                          0 0.866025 0.5,
+                          0 0.866025 0.5,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.5 0.866025,
+                          0 0.5 0.866025,
+                          0 6.12303e-17 1,
+                          0 0.866025 0.5,
+                          0 0.5 0.866025,
+                          0 0.5 0.866025,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -1.83691e-16 1,
+                          0 -1.83691e-16 1,
+                          0 -0.5 0.866025,
+                          0 0.5 0.866025,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.5 0.866025,
+                          0 -0.5 0.866025,
+                          0 -0.866025 0.5,
+                          0 -1.83691e-16 1,
+                          0 -0.5 0.866025,
+                          0 -0.5 0.866025,
+                          0 -0.866025 0.5,
+                          0 -0.866025 0.5,
+                          0 -1 -1.22461e-16,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.5 0.866025,
+                          0 -0.866025 0.5,
+                          0 -0.866025 0.5,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -0.866025 -0.5,
+                          0 -0.866025 0.5,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -0.866025 -0.5,
+                          0 -0.866025 -0.5,
+                          0 -0.5 -0.866025,
+                          0 -1 -1.22461e-16,
+                          0 -0.866025 -0.5,
+                          0 -0.866025 -0.5,
+                          0 -0.866025 -0.5,
+                          0 -0.5 -0.866025,
+                          0 -0.5 -0.866025,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 6.12303e-17 -1,
+                          0 6.12303e-17 -1,
+                          0 -0.866025 -0.5,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.866025 -0.5,
+                          0 0.866025 -0.5,
+                          0 6.12303e-17 -1,
+                          0 6.12303e-17 -1,
+                          0 0.866025 -0.5,
+                          0 6.12303e-17 -1,
+                          0 -0.866025 -0.5,
+                          0 -0.866025 -0.5,
+                          0 -0.866025 0.5,
+                          0 -0.866025 -0.5,
+                          0 6.12303e-17 -1,
+                          0 -0.866025 -0.5,
+                          0 -0.866025 0.5,
+                          0 -0.866025 0.5,
+                          0 -1.83691e-16 1,
+                          0 -0.866025 -0.5,
+                          0 -0.866025 0.5,
+                          0 -0.866025 0.5,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 0.866025 0.5,
+                          0 -0.866025 0.5,
+                          0 -1.83691e-16 1,
+                          0 -1.83691e-16 1,
+                          0 0.866025 0.5,
+                          0 0.866025 0.5,
+                          0 0.866025 -0.5,
+                          0 0.866025 0.5,
+                          0 6.12303e-17 1,
+                          0 0.866025 0.5,
+                          0 0.866025 -0.5,
+                          0 0.866025 0.5,
+                          0 0.866025 -0.5,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          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.822897 3.47905e-17 0.568191,
+                          -0.822897 3.47905e-17 0.568191,
+                          -0.822897 3.47905e-17 0.568191,
+                          -0.822897 3.47905e-17 0.568191,
+                          -0.822897 3.47905e-17 0.568191,
+                          -0.822897 3.47905e-17 0.568191,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -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 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 0.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          0 -1.83691e-16 1,
+                          0 -0.707107 0.707107,
+                          0 -1.83691e-16 1,
+                          0 -1.83691e-16 1,
+                          0 0.707107 0.707107,
+                          0 0.707107 0.707107,
+                          0 1 -4.44089e-16,
+                          0 0.707107 0.707107,
+                          0 6.12303e-17 1,
+                          0 0.707107 0.707107,
+                          0 1 0,
+                          0 1 -4.44089e-16,
+                          0 0.707107 -0.707107,
+                          0 1 0,
+                          0 0.707107 0.707107,
+                          0 1 -4.44089e-16,
+                          0 0.707107 -0.707107,
+                          0 0.707107 -0.707107,
+                          0 6.12303e-17 -1,
+                          0 0.707107 -0.707107,
+                          0 1 0,
+                          0 0.707107 -0.707107,
+                          0 6.12303e-17 -1,
+                          0 6.12303e-17 -1,
+                          0 -0.707107 -0.707107,
+                          0 6.12303e-17 -1,
+                          0 0.707107 -0.707107,
+                          0 6.12303e-17 -1,
+                          0 -0.707107 -0.707107,
+                          0 -0.707107 -0.707107,
+                          0 -1 -1.22461e-16,
+                          0 -0.707107 -0.707107,
+                          0 6.12303e-17 -1,
+                          0 -0.707107 -0.707107,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -0.707107 0.707107,
+                          0 -0.707107 -0.707107,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -0.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -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 6.12303e-17 -1,
+                          0 6.12303e-17 -1,
+                          0 -0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 6.12303e-17 -1,
+                          0 6.12303e-17 -1,
+                          0 0.5 -0.866025,
+                          0 6.12303e-17 -1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.5 -0.866025,
+                          0 -0.5 -0.866025,
+                          0 -0.866025 -0.5,
+                          0 -0.5 -0.866025,
+                          0 6.12303e-17 -1,
+                          0 -0.5 -0.866025,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.866025 -0.5,
+                          0 -0.866025 -0.5,
+                          0 -1 -1.22461e-16,
+                          0 -0.866025 -0.5,
+                          0 -0.5 -0.866025,
+                          0 -0.866025 -0.5,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -0.866025 0.5,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -1 -1.22461e-16,
+                          0 -0.866025 -0.5,
+                          0 -1 -1.22461e-16,
+                          0 -0.866025 0.5,
+                          0 -0.866025 0.5,
+                          0 -0.5 0.866025,
+                          0 -0.866025 0.5,
+                          0 -1 -1.22461e-16,
+                          0 -0.866025 0.5,
+                          0 -0.5 0.866025,
+                          0 -0.5 0.866025,
+                          0 -1.83691e-16 1,
+                          0 -0.5 0.866025,
+                          0 -0.866025 0.5,
+                          0 -0.5 0.866025,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 0.5 0.866025,
+                          0 -0.5 0.866025,
+                          0 -1.83691e-16 1,
+                          0 -1.83691e-16 1,
+                          0 0.5 0.866025,
+                          0 0.5 0.866025,
+                          0 0.866025 0.5,
+                          0 0.5 0.866025,
+                          0 6.12303e-17 1,
+                          0 0.5 0.866025,
+                          0 0.866025 0.5,
+                          0 0.866025 0.5,
+                          0 1 0,
+                          0 0.866025 0.5,
+                          0 0.5 0.866025,
+                          0 0.866025 0.5,
+                          0 1 0,
+                          0 1 0,
+                          0 0.866025 -0.5,
+                          0 1 0,
+                          0 0.866025 0.5,
+                          0 1 0,
+                          0 0.866025 -0.5,
+                          0 0.866025 -0.5,
+                          0 0.5 -0.866025,
+                          0 0.866025 -0.5,
+                          0 1 0,
+                          0 0.866025 -0.5,
+                          0 0.5 -0.866025,
+                          0 0.866025 -0.5,
+                          0 0.5 -0.866025,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -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 6.12303e-17 -1,
+                          0 6.12303e-17 -1,
+                          0 -0.866025 -0.5,
+                          0 0.866025 -0.5,
+                          0 0.866025 -0.5,
+                          0 6.12303e-17 -1,
+                          0 6.12303e-17 -1,
+                          0 0.866025 -0.5,
+                          0 6.12303e-17 -1,
+                          0 -0.866025 -0.5,
+                          0 -0.866025 -0.5,
+                          0 -0.866025 0.5,
+                          0 -0.866025 -0.5,
+                          0 6.12303e-17 -1,
+                          0 -0.866025 -0.5,
+                          0 -0.866025 0.5,
+                          0 -0.866025 0.5,
+                          0 -1.83691e-16 1,
+                          0 -0.866025 -0.5,
+                          0 -0.866025 0.5,
+                          0 -0.866025 0.5,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 0.866025 0.5,
+                          0 -0.866025 0.5,
+                          0 -1.83691e-16 1,
+                          0 -1.83691e-16 1,
+                          0 0.866025 0.5,
+                          0 0.866025 0.5,
+                          0 0.866025 -0.5,
+                          0 0.866025 0.5,
+                          0 6.12303e-17 1,
+                          0 0.866025 0.5,
+                          0 0.866025 -0.5,
+                          0 0.866025 0.5,
+                          0 0.866025 -0.5,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 16.5 -12.5 -23.5,
+                          12.5402 -9.10995 -23.5,
+                          15.5 4.59227e-16 -23.5,
+                          15.5 8.32732e-16 -17.4,
+                          15.5 4.59227e-16 -23.5,
+                          12.5402 -9.10995 -23.5,
+                          16.5 12.5 -23.5,
+                          15.5 4.59227e-16 -23.5,
+                          12.5402 9.10995 -23.5,
+                          12.5398 9.11067 -17.4,
+                          12.5402 9.10995 -23.5,
+                          15.5 4.59227e-16 -23.5,
+                          16.5 12.5 -23.5,
+                          16.5 -12.5 -23.5,
+                          15.5 4.59227e-16 -23.5,
+                          12.5398 9.11067 -17.4,
+                          15.5 4.59227e-16 -23.5,
+                          15.5 8.32732e-16 -17.4,
+                          16.5 -12.5 -23.5,
+                          4.79011 -14.7411 -23.5,
+                          12.5402 -9.10995 -23.5,
+                          12.5398 -9.11067 -17.4,
+                          12.5402 -9.10995 -23.5,
+                          4.79011 -14.7411 -23.5,
+                          12.5398 -9.11067 -17.4,
+                          15.5 8.32732e-16 -17.4,
+                          12.5402 -9.10995 -23.5,
+                          12.5 -16.5 -23.5,
+                          -4.79011 -14.7411 -23.5,
+                          4.79011 -14.7411 -23.5,
+                          4.78976 -14.7414 -17.4,
+                          4.79011 -14.7411 -23.5,
+                          -4.79011 -14.7411 -23.5,
+                          16.5 -12.5 -23.5,
+                          12.5 -16.5 -23.5,
+                          4.79011 -14.7411 -23.5,
+                          12.5398 -9.11067 -17.4,
+                          4.79011 -14.7411 -23.5,
+                          4.78976 -14.7414 -17.4,
+                          -16.5 -12.5 -23.5,
+                          -12.5402 -9.10995 -23.5,
+                          -4.79011 -14.7411 -23.5,
+                          -4.78976 -14.7414 -17.4,
+                          -4.79011 -14.7411 -23.5,
+                          -12.5402 -9.10995 -23.5,
+                          -12.5 -16.5 -23.5,
+                          -4.79011 -14.7411 -23.5,
+                          12.5 -16.5 -23.5,
+                          -12.5 -16.5 -23.5,
+                          -16.5 -12.5 -23.5,
+                          -4.79011 -14.7411 -23.5,
+                          4.78976 -14.7414 -17.4,
+                          -4.79011 -14.7411 -23.5,
+                          -4.78976 -14.7414 -17.4,
+                          -16.5 -12.5 -23.5,
+                          -15.5 -3.33705e-15 -23.5,
+                          -12.5402 -9.10995 -23.5,
+                          -12.5398 -9.11067 -17.4,
+                          -12.5402 -9.10995 -23.5,
+                          -15.5 -3.33705e-15 -23.5,
+                          -4.78976 -14.7414 -17.4,
+                          -12.5402 -9.10995 -23.5,
+                          -12.5398 -9.11067 -17.4,
+                          -16.5 12.5 -23.5,
+                          -12.5402 9.10995 -23.5,
+                          -15.5 -3.33705e-15 -23.5,
+                          -15.5 -2.96355e-15 -17.4,
+                          -15.5 -3.33705e-15 -23.5,
+                          -12.5402 9.10995 -23.5,
+                          -16.5 -12.5 -23.5,
+                          -16.5 12.5 -23.5,
+                          -15.5 -3.33705e-15 -23.5,
+                          -12.5398 -9.11067 -17.4,
+                          -15.5 -3.33705e-15 -23.5,
+                          -15.5 -2.96355e-15 -17.4,
+                          -16.5 12.5 -23.5,
+                          -4.79011 14.7411 -23.5,
+                          -12.5402 9.10995 -23.5,
+                          -12.5398 9.11067 -17.4,
+                          -12.5402 9.10995 -23.5,
+                          -4.79011 14.7411 -23.5,
+                          -15.5 -2.96355e-15 -17.4,
+                          -12.5402 9.10995 -23.5,
+                          -12.5398 9.11067 -17.4,
+                          -12.5 16.5 -23.5,
+                          4.79011 14.7411 -23.5,
+                          -4.79011 14.7411 -23.5,
+                          -4.78976 14.7414 -17.4,
+                          -4.79011 14.7411 -23.5,
+                          4.79011 14.7411 -23.5,
+                          -16.5 12.5 -23.5,
+                          -12.5 16.5 -23.5,
+                          -4.79011 14.7411 -23.5,
+                          -12.5398 9.11067 -17.4,
+                          -4.79011 14.7411 -23.5,
+                          -4.78976 14.7414 -17.4,
+                          16.5 12.5 -23.5,
+                          12.5402 9.10995 -23.5,
+                          4.79011 14.7411 -23.5,
+                          4.78976 14.7414 -17.4,
+                          4.79011 14.7411 -23.5,
+                          12.5402 9.10995 -23.5,
+                          12.5 16.5 -23.5,
+                          16.5 12.5 -23.5,
+                          4.79011 14.7411 -23.5,
+                          -12.5 16.5 -23.5,
+                          12.5 16.5 -23.5,
+                          4.79011 14.7411 -23.5,
+                          -4.78976 14.7414 -17.4,
+                          4.79011 14.7411 -23.5,
+                          4.78976 14.7414 -17.4,
+                          4.78976 14.7414 -17.4,
+                          12.5402 9.10995 -23.5,
+                          12.5398 9.11067 -17.4,
+                          16.5 -12.5 28,
+                          12.5 -16.5 -23.5,
+                          16.5 -12.5 -23.5,
+                          12.5 -16.5 25.1034,
+                          -12.5 -16.5 -23.5,
+                          12.5 -16.5 -23.5,
+                          16.5 -12.5 28,
+                          12.5 -16.5 25.1034,
+                          12.5 -16.5 -23.5,
+                          16.5 4.32977 -2.50034,
+                          16.5 -12.5 -23.5,
+                          16.5 12.5 -23.5,
+                          16.5 2.50034 -4.32977,
+                          16.5 -3.06152e-16 -5,
+                          16.5 -12.5 -23.5,
+                          16.5 -2.50034 -4.32977,
+                          16.5 -12.5 -23.5,
+                          16.5 -3.06152e-16 -5,
+                          16.5 4.32977 -2.50034,
+                          16.5 2.50034 -4.32977,
+                          16.5 -12.5 -23.5,
+                          16.5 -5 3.06152e-16,
+                          16.5 -4.32977 2.50034,
+                          16.5 -12.5 -23.5,
+                          16.5 -12.5 28,
+                          16.5 -12.5 -23.5,
+                          16.5 -4.32977 2.50034,
+                          16.5 -4.32977 -2.50034,
+                          16.5 -5 3.06152e-16,
+                          16.5 -12.5 -23.5,
+                          16.5 -2.50034 -4.32977,
+                          16.5 -4.32977 -2.50034,
+                          16.5 -12.5 -23.5,
+                          12.5 16.5 25.1034,
+                          16.5 12.5 -23.5,
+                          12.5 16.5 -23.5,
+                          14.5 14.5 28,
+                          16.5 12.5 -23.5,
+                          12.5 16.5 25.1034,
+                          16.5 5 -3.06152e-16,
+                          16.5 4.32977 -2.50034,
+                          16.5 12.5 -23.5,
+                          16.5 12.5 28,
+                          16.5 5 -3.06152e-16,
+                          16.5 12.5 -23.5,
+                          14.5 14.5 28,
+                          16.5 12.5 28,
+                          16.5 12.5 -23.5,
+                          -12.5 16.5 7,
+                          12.5 16.5 -23.5,
+                          -12.5 16.5 -23.5,
+                          -1e-20 16.5 7,
+                          12.5 16.5 -23.5,
+                          -12.5 16.5 7,
+                          -1e-20 16.5 7,
+                          12.5 16.5 25.1034,
+                          12.5 16.5 -23.5,
+                          -16.5 12.5 7,
+                          -12.5 16.5 -23.5,
+                          -16.5 12.5 -23.5,
+                          -16.5 12.5 7,
+                          -12.5 16.5 7,
+                          -12.5 16.5 -23.5,
+                          -16.5 -4.94918 -4.95016,
+                          -16.5 12.5 -23.5,
+                          -16.5 -12.5 -23.5,
+                          -16.5 6.99981 -4.28601e-16,
+                          -16.5 12.5 7,
+                          -16.5 12.5 -23.5,
+                          -16.5 4.94918 -4.95016,
+                          -16.5 6.99981 -4.28601e-16,
+                          -16.5 12.5 -23.5,
+                          -16.5 -4.28612e-16 -7,
+                          -16.5 4.94918 -4.95016,
+                          -16.5 12.5 -23.5,
+                          -16.5 -4.94918 -4.95016,
+                          -16.5 -4.28612e-16 -7,
+                          -16.5 12.5 -23.5,
+                          -12.5 -16.5 7,
+                          -16.5 -12.5 -23.5,
+                          -12.5 -16.5 -23.5,
+                          -16.5 -12.5 7,
+                          -16.5 -12.5 -23.5,
+                          -12.5 -16.5 7,
+                          -16.5 -4.94918 -4.95016,
+                          -16.5 -12.5 -23.5,
+                          -16.5 -12.5 7,
+                          -1e-20 -16.5 7,
+                          -12.5 -16.5 7,
+                          -12.5 -16.5 -23.5,
+                          12.5 -16.5 25.1034,
+                          -1e-20 -16.5 7,
+                          -12.5 -16.5 -23.5,
+                          -16.5 12.5 7,
+                          -1e-20 16.5 7,
+                          -12.5 16.5 7,
+                          -1e-20 5 7,
+                          12.5 16.5 25.1034,
+                          -1e-20 16.5 7,
+                          -1e-20 5 7,
+                          14.5 14.5 28,
+                          12.5 16.5 25.1034,
+                          -16.5 12.5 7,
+                          -1e-20 5 7,
+                          -1e-20 16.5 7,
+                          -1e-20 -5 7,
+                          -12.5 -16.5 7,
+                          -1e-20 -16.5 7,
+                          -16.5 -12.5 7,
+                          -12.5 -16.5 7,
+                          -1e-20 -5 7,
+                          14.5 -14.5 28,
+                          -1e-20 -16.5 7,
+                          12.5 -16.5 25.1034,
+                          14.5 -14.5 28,
+                          -1e-20 -5 7,
+                          -1e-20 -16.5 7,
+                          14.5 -14.5 28,
+                          12.5 -16.5 25.1034,
+                          16.5 -12.5 28,
+                          2.50034 4.32977 -17.4,
+                          12.5398 9.11067 -17.4,
+                          15.5 8.32732e-16 -17.4,
+                          5 -4.53104e-16 -17.4,
+                          15.5 8.32732e-16 -17.4,
+                          12.5398 -9.11067 -17.4,
+                          4.32977 2.50034 -17.4,
+                          15.5 8.32732e-16 -17.4,
+                          5 -4.53104e-16 -17.4,
+                          4.32977 2.50034 -17.4,
+                          2.50034 4.32977 -17.4,
+                          15.5 8.32732e-16 -17.4,
+                          -4.78976 14.7414 -17.4,
+                          4.78976 14.7414 -17.4,
+                          12.5398 9.11067 -17.4,
+                          -12.5398 9.11067 -17.4,
+                          -4.78976 14.7414 -17.4,
+                          12.5398 9.11067 -17.4,
+                          2.50034 4.32977 -17.4,
+                          -12.5398 9.11067 -17.4,
+                          12.5398 9.11067 -17.4,
+                          -5 -1.67771e-15 -17.4,
+                          -15.5 -2.96355e-15 -17.4,
+                          -12.5398 9.11067 -17.4,
+                          -4.32977 2.50034 -17.4,
+                          -5 -1.67771e-15 -17.4,
+                          -12.5398 9.11067 -17.4,
+                          -2.50034 4.32977 -17.4,
+                          -4.32977 2.50034 -17.4,
+                          -12.5398 9.11067 -17.4,
+                          -9.18465e-16 5 -17.4,
+                          -2.50034 4.32977 -17.4,
+                          -12.5398 9.11067 -17.4,
+                          2.50034 4.32977 -17.4,
+                          -9.18465e-16 5 -17.4,
+                          -12.5398 9.11067 -17.4,
+                          -2.50034 -4.32977 -17.4,
+                          -12.5398 -9.11067 -17.4,
+                          -15.5 -2.96355e-15 -17.4,
+                          -4.32977 -2.50034 -17.4,
+                          -2.50034 -4.32977 -17.4,
+                          -15.5 -2.96355e-15 -17.4,
+                          -5 -1.67771e-15 -17.4,
+                          -4.32977 -2.50034 -17.4,
+                          -15.5 -2.96355e-15 -17.4,
+                          4.78976 -14.7414 -17.4,
+                          -4.78976 -14.7414 -17.4,
+                          -12.5398 -9.11067 -17.4,
+                          12.5398 -9.11067 -17.4,
+                          4.78976 -14.7414 -17.4,
+                          -12.5398 -9.11067 -17.4,
+                          -2.50034 -4.32977 -17.4,
+                          12.5398 -9.11067 -17.4,
+                          -12.5398 -9.11067 -17.4,
+                          4.32977 -2.50034 -17.4,
+                          5 -4.53104e-16 -17.4,
+                          12.5398 -9.11067 -17.4,
+                          2.50034 -4.32977 -17.4,
+                          4.32977 -2.50034 -17.4,
+                          12.5398 -9.11067 -17.4,
+                          3.06142e-16 -5 -17.4,
+                          2.50034 -4.32977 -17.4,
+                          12.5398 -9.11067 -17.4,
+                          -2.50034 -4.32977 -17.4,
+                          3.06142e-16 -5 -17.4,
+                          12.5398 -9.11067 -17.4,
+                          5 -1.68916e-14 14.2414,
+                          5 -4.53104e-16 -17.4,
+                          4.32977 -2.50034 -17.4,
+                          3.80476 3.24405 12.5103,
+                          4.32977 2.50034 -17.4,
+                          5 -4.53104e-16 -17.4,
+                          3.80476 3.24405 12.5103,
+                          5 -4.53104e-16 -17.4,
+                          5 -1.68916e-14 14.2414,
+                          3.80477 -3.24402 12.5104,
+                          4.32977 -2.50034 -17.4,
+                          2.50034 -4.32977 -17.4,
+                          3.80477 -3.24402 12.5104,
+                          5 -1.68916e-14 14.2414,
+                          4.32977 -2.50034 -17.4,
+                          2.23671 -4.47204 10.2394,
+                          2.50034 -4.32977 -17.4,
+                          3.06142e-16 -5 -17.4,
+                          2.23671 -4.47204 10.2394,
+                          3.80477 -3.24402 12.5104,
+                          2.50034 -4.32977 -17.4,
+                          -1e-20 -5 7,
+                          3.06142e-16 -5 -17.4,
+                          -2.50034 -4.32977 -17.4,
+                          -1e-20 -5 7,
+                          2.23671 -4.47204 10.2394,
+                          3.06142e-16 -5 -17.4,
+                          -3.53548 -3.53559 7,
+                          -2.50034 -4.32977 -17.4,
+                          -4.32977 -2.50034 -17.4,
+                          -3.53548 -3.53559 7,
+                          -1e-20 -5 7,
+                          -2.50034 -4.32977 -17.4,
+                          -3.53548 -3.53559 7,
+                          -4.32977 -2.50034 -17.4,
+                          -5 -1.67771e-15 -17.4,
+                          -5 4.28612e-16 7,
+                          -5 -1.67771e-15 -17.4,
+                          -4.32977 2.50034 -17.4,
+                          -5 4.28612e-16 7,
+                          -3.53548 -3.53559 7,
+                          -5 -1.67771e-15 -17.4,
+                          -3.53548 3.53559 7,
+                          -4.32977 2.50034 -17.4,
+                          -2.50034 4.32977 -17.4,
+                          -3.53548 3.53559 7,
+                          -5 4.28612e-16 7,
+                          -4.32977 2.50034 -17.4,
+                          -3.53548 3.53559 7,
+                          -2.50034 4.32977 -17.4,
+                          -9.18465e-16 5 -17.4,
+                          -1e-20 5 7,
+                          -9.18465e-16 5 -17.4,
+                          2.50034 4.32977 -17.4,
+                          -3.53548 3.53559 7,
+                          -9.18465e-16 5 -17.4,
+                          -1e-20 5 7,
+                          3.80476 3.24405 12.5103,
+                          2.50034 4.32977 -17.4,
+                          4.32977 2.50034 -17.4,
+                          2.23681 4.47199 10.2395,
+                          2.50034 4.32977 -17.4,
+                          3.80476 3.24405 12.5103,
+                          -1e-20 5 7,
+                          2.50034 4.32977 -17.4,
+                          2.23681 4.47199 10.2395,
+                          14.5 14.5 28,
+                          5 -1.68916e-14 14.2414,
+                          3.80477 -3.24402 12.5104,
+                          3.80476 3.24405 12.5103,
+                          5 -1.68916e-14 14.2414,
+                          14.5 14.5 28,
+                          14.5 -14.5 28,
+                          3.80477 -3.24402 12.5104,
+                          2.23671 -4.47204 10.2394,
+                          14.5 14.5 28,
+                          3.80477 -3.24402 12.5104,
+                          14.5 -14.5 28,
+                          14.5 -14.5 28,
+                          2.23671 -4.47204 10.2394,
+                          -1e-20 -5 7,
+                          -16.5 -12.5 7,
+                          -1e-20 -5 7,
+                          -3.53548 -3.53559 7,
+                          -16.5 -12.5 7,
+                          -3.53548 -3.53559 7,
+                          -5 4.28612e-16 7,
+                          -16.5 4.28612e-16 7,
+                          -16.5 -12.5 7,
+                          -5 4.28612e-16 7,
+                          -3.53548 3.53559 7,
+                          -16.5 4.28612e-16 7,
+                          -5 4.28612e-16 7,
+                          17.5 -3.06152e-16 -5,
+                          16.5 -3.06152e-16 -5,
+                          16.5 2.50034 -4.32977,
+                          17.5 -2.49989 -4.32993,
+                          16.5 -2.50034 -4.32977,
+                          16.5 -3.06152e-16 -5,
+                          17.5 -2.49989 -4.32993,
+                          16.5 -3.06152e-16 -5,
+                          17.5 -3.06152e-16 -5,
+                          17.5 2.49989 -4.32993,
+                          16.5 2.50034 -4.32977,
+                          16.5 4.32977 -2.50034,
+                          17.5 2.49989 -4.32993,
+                          17.5 -3.06152e-16 -5,
+                          16.5 2.50034 -4.32977,
+                          17.5 4.33013 -2.5,
+                          16.5 4.32977 -2.50034,
+                          16.5 5 -3.06152e-16,
+                          17.5 2.49989 -4.32993,
+                          16.5 4.32977 -2.50034,
+                          17.5 4.33013 -2.5,
+                          16.5 12.5 28,
+                          16.5 4.32977 2.50034,
+                          16.5 5 -3.06152e-16,
+                          17.5 4.99978 -6.94716e-16,
+                          16.5 5 -3.06152e-16,
+                          16.5 4.32977 2.50034,
+                          17.5 4.33013 -2.5,
+                          16.5 5 -3.06152e-16,
+                          17.5 4.99978 -6.94716e-16,
+                          16.5 12.5 28,
+                          16.5 2.50034 4.32977,
+                          16.5 4.32977 2.50034,
+                          17.5 4.33013 2.5,
+                          16.5 4.32977 2.50034,
+                          16.5 2.50034 4.32977,
+                          17.5 4.99978 -6.94716e-16,
+                          16.5 4.32977 2.50034,
+                          17.5 4.33013 2.5,
+                          16.5 12.5 28,
+                          16.5 3.06152e-16 5,
+                          16.5 2.50034 4.32977,
+                          17.5 2.49989 4.32993,
+                          16.5 2.50034 4.32977,
+                          16.5 3.06152e-16 5,
+                          17.5 4.33013 2.5,
+                          16.5 2.50034 4.32977,
+                          17.5 2.49989 4.32993,
+                          16.5 12.5 28,
+                          16.5 -2.50034 4.32977,
+                          16.5 3.06152e-16 5,
+                          17.5 3.06152e-16 5,
+                          16.5 3.06152e-16 5,
+                          16.5 -2.50034 4.32977,
+                          17.5 2.49989 4.32993,
+                          16.5 3.06152e-16 5,
+                          17.5 3.06152e-16 5,
+                          16.5 12.5 28,
+                          16.5 -4.32977 2.50034,
+                          16.5 -2.50034 4.32977,
+                          17.5 -2.49989 4.32993,
+                          16.5 -2.50034 4.32977,
+                          16.5 -4.32977 2.50034,
+                          17.5 3.06152e-16 5,
+                          16.5 -2.50034 4.32977,
+                          17.5 -2.49989 4.32993,
+                          17.5 -4.33013 2.5,
+                          16.5 -4.32977 2.50034,
+                          16.5 -5 3.06152e-16,
+                          16.5 12.5 28,
+                          16.5 -12.5 28,
+                          16.5 -4.32977 2.50034,
+                          17.5 -2.49989 4.32993,
+                          16.5 -4.32977 2.50034,
+                          17.5 -4.33013 2.5,
+                          17.5 -4.99978 -8.24402e-17,
+                          16.5 -5 3.06152e-16,
+                          16.5 -4.32977 -2.50034,
+                          17.5 -4.33013 2.5,
+                          16.5 -5 3.06152e-16,
+                          17.5 -4.99978 -8.24402e-17,
+                          17.5 -4.33013 -2.5,
+                          16.5 -4.32977 -2.50034,
+                          16.5 -2.50034 -4.32977,
+                          17.5 -4.99978 -8.24402e-17,
+                          16.5 -4.32977 -2.50034,
+                          17.5 -4.33013 -2.5,
+                          17.5 -4.33013 -2.5,
+                          16.5 -2.50034 -4.32977,
+                          17.5 -2.49989 -4.32993,
+                          14.5 -14.5 28,
+                          16.5 -12.5 28,
+                          16.5 12.5 28,
+                          14.5 14.5 28,
+                          14.5 -14.5 28,
+                          16.5 12.5 28,
+                          23.5 -2.59765 1.50036,
+                          23.5 -2.59765 -1.50036,
+                          23.5 -1.83691e-16 -3,
+                          17.5 -1.83691e-16 -3,
+                          23.5 -1.83691e-16 -3,
+                          23.5 -2.59765 -1.50036,
+                          23.5 1.83691e-16 3,
+                          23.5 -2.59765 1.50036,
+                          23.5 -1.83691e-16 -3,
+                          23.5 2.59765 -1.50036,
+                          23.5 1.83691e-16 3,
+                          23.5 -1.83691e-16 -3,
+                          17.5 2.59765 -1.50036,
+                          23.5 2.59765 -1.50036,
+                          23.5 -1.83691e-16 -3,
+                          17.5 -1.83691e-16 -3,
+                          17.5 2.59765 -1.50036,
+                          23.5 -1.83691e-16 -3,
+                          17.5 -2.59765 -1.50036,
+                          23.5 -2.59765 -1.50036,
+                          23.5 -2.59765 1.50036,
+                          17.5 -2.59765 -1.50036,
+                          17.5 -1.83691e-16 -3,
+                          23.5 -2.59765 -1.50036,
+                          17.5 -2.59765 1.50036,
+                          23.5 -2.59765 1.50036,
+                          23.5 1.83691e-16 3,
+                          17.5 -2.59765 -1.50036,
+                          23.5 -2.59765 1.50036,
+                          17.5 -2.59765 1.50036,
+                          23.5 2.59765 -1.50036,
+                          23.5 2.59765 1.50036,
+                          23.5 1.83691e-16 3,
+                          17.5 1.83691e-16 3,
+                          23.5 1.83691e-16 3,
+                          23.5 2.59765 1.50036,
+                          17.5 -2.59765 1.50036,
+                          23.5 1.83691e-16 3,
+                          17.5 1.83691e-16 3,
+                          17.5 2.59765 1.50036,
+                          23.5 2.59765 1.50036,
+                          23.5 2.59765 -1.50036,
+                          17.5 2.59765 1.50036,
+                          17.5 1.83691e-16 3,
+                          23.5 2.59765 1.50036,
+                          17.5 2.59765 -1.50036,
+                          17.5 2.59765 1.50036,
+                          23.5 2.59765 -1.50036,
+                          17.5 3.06152e-16 5,
+                          17.5 1.83691e-16 3,
+                          17.5 2.59765 1.50036,
+                          17.5 -2.49989 4.32993,
+                          17.5 -2.59765 1.50036,
+                          17.5 1.83691e-16 3,
+                          17.5 3.06152e-16 5,
+                          17.5 -2.49989 4.32993,
+                          17.5 1.83691e-16 3,
+                          17.5 4.33013 -2.5,
+                          17.5 2.59765 1.50036,
+                          17.5 2.59765 -1.50036,
+                          17.5 2.49989 4.32993,
+                          17.5 3.06152e-16 5,
+                          17.5 2.59765 1.50036,
+                          17.5 4.33013 -2.5,
+                          17.5 2.49989 4.32993,
+                          17.5 2.59765 1.50036,
+                          17.5 2.49989 -4.32993,
+                          17.5 2.59765 -1.50036,
+                          17.5 -1.83691e-16 -3,
+                          17.5 2.49989 -4.32993,
+                          17.5 4.33013 -2.5,
+                          17.5 2.59765 -1.50036,
+                          17.5 -3.06152e-16 -5,
+                          17.5 -1.83691e-16 -3,
+                          17.5 -2.59765 -1.50036,
+                          17.5 2.49989 -4.32993,
+                          17.5 -1.83691e-16 -3,
+                          17.5 -3.06152e-16 -5,
+                          17.5 -4.33013 2.5,
+                          17.5 -2.59765 -1.50036,
+                          17.5 -2.59765 1.50036,
+                          17.5 -2.49989 4.32993,
+                          17.5 -4.33013 2.5,
+                          17.5 -2.59765 1.50036,
+                          17.5 -2.49989 -4.32993,
+                          17.5 -3.06152e-16 -5,
+                          17.5 -2.59765 -1.50036,
+                          17.5 -4.33013 2.5,
+                          17.5 -2.49989 -4.32993,
+                          17.5 -2.59765 -1.50036,
+                          17.5 -4.33013 2.5,
+                          17.5 -4.33013 -2.5,
+                          17.5 -2.49989 -4.32993,
+                          17.5 -4.33013 2.5,
+                          17.5 -4.99978 -8.24402e-17,
+                          17.5 -4.33013 -2.5,
+                          17.5 4.33013 -2.5,
+                          17.5 4.33013 2.5,
+                          17.5 2.49989 4.32993,
+                          17.5 4.33013 -2.5,
+                          17.5 4.99978 -6.94716e-16,
+                          17.5 4.33013 2.5,
+                          2.23681 4.47199 10.2395,
+                          3.80476 3.24405 12.5103,
+                          14.5 14.5 28,
+                          -1e-20 5 7,
+                          2.23681 4.47199 10.2395,
+                          14.5 14.5 28,
+                          -16.5 4.28612e-16 7,
+                          -1e-20 5 7,
+                          -16.5 12.5 7,
+                          -3.53548 3.53559 7,
+                          -1e-20 5 7,
+                          -16.5 4.28612e-16 7,
+                          -16.5 -4.94918 4.95016,
+                          -16.5 -12.5 7,
+                          -16.5 4.28612e-16 7,
+                          -16.5 -6.99981 4.28601e-16,
+                          -16.5 -4.94918 -4.95016,
+                          -16.5 -12.5 7,
+                          -16.5 -4.94918 4.95016,
+                          -16.5 -6.99981 4.28601e-16,
+                          -16.5 -12.5 7,
+                          -16.5 4.94918 4.95016,
+                          -16.5 4.28612e-16 7,
+                          -16.5 12.5 7,
+                          -16.5 6.99981 -4.28601e-16,
+                          -16.5 4.94918 4.95016,
+                          -16.5 12.5 7,
+                          -18.5 4.28612e-16 7,
+                          -16.5 4.28612e-16 7,
+                          -16.5 4.94918 4.95016,
+                          -18.5 -4.94975 4.94975,
+                          -16.5 -4.94918 4.95016,
+                          -16.5 4.28612e-16 7,
+                          -18.5 -4.94975 4.94975,
+                          -16.5 4.28612e-16 7,
+                          -18.5 4.28612e-16 7,
+                          -18.5 4.94975 4.94975,
+                          -16.5 4.94918 4.95016,
+                          -16.5 6.99981 -4.28601e-16,
+                          -18.5 4.94975 4.94975,
+                          -18.5 4.28612e-16 7,
+                          -16.5 4.94918 4.95016,
+                          -18.5 7 -8.57224e-16,
+                          -16.5 6.99981 -4.28601e-16,
+                          -16.5 4.94918 -4.95016,
+                          -18.5 7 -8.57224e-16,
+                          -18.5 4.94975 4.94975,
+                          -16.5 6.99981 -4.28601e-16,
+                          -18.5 4.94975 -4.94975,
+                          -16.5 4.94918 -4.95016,
+                          -16.5 -4.28612e-16 -7,
+                          -18.5 4.94975 -4.94975,
+                          -18.5 7 -8.57224e-16,
+                          -16.5 4.94918 -4.95016,
+                          -18.5 -4.28612e-16 -7,
+                          -16.5 -4.28612e-16 -7,
+                          -16.5 -4.94918 -4.95016,
+                          -18.5 -4.28612e-16 -7,
+                          -18.5 4.94975 -4.94975,
+                          -16.5 -4.28612e-16 -7,
+                          -18.5 -4.94975 -4.94975,
+                          -16.5 -4.94918 -4.95016,
+                          -16.5 -6.99981 4.28601e-16,
+                          -18.5 -4.94975 -4.94975,
+                          -18.5 -4.28612e-16 -7,
+                          -16.5 -4.94918 -4.95016,
+                          -18.5 -7 0,
+                          -16.5 -6.99981 4.28601e-16,
+                          -16.5 -4.94918 4.95016,
+                          -18.5 -4.94975 -4.94975,
+                          -16.5 -6.99981 4.28601e-16,
+                          -18.5 -7 0,
+                          -18.5 -7 0,
+                          -16.5 -4.94918 4.95016,
+                          -18.5 -4.94975 4.94975,
+                          -18.5 3.06152e-16 5,
+                          -18.5 4.28612e-16 7,
+                          -18.5 4.94975 4.94975,
+                          -18.5 -2.49989 4.32993,
+                          -18.5 -4.33013 2.5,
+                          -18.5 4.28612e-16 7,
+                          -18.5 -4.94975 4.94975,
+                          -18.5 4.28612e-16 7,
+                          -18.5 -4.33013 2.5,
+                          -18.5 3.06152e-16 5,
+                          -18.5 -2.49989 4.32993,
+                          -18.5 4.28612e-16 7,
+                          -18.5 4.99978 -6.94716e-16,
+                          -18.5 4.94975 4.94975,
+                          -18.5 7 -8.57224e-16,
+                          -18.5 2.49989 4.32993,
+                          -18.5 3.06152e-16 5,
+                          -18.5 4.94975 4.94975,
+                          -18.5 4.33013 2.5,
+                          -18.5 2.49989 4.32993,
+                          -18.5 4.94975 4.94975,
+                          -18.5 4.99978 -6.94716e-16,
+                          -18.5 4.33013 2.5,
+                          -18.5 4.94975 4.94975,
+                          -18.5 4.99978 -6.94716e-16,
+                          -18.5 7 -8.57224e-16,
+                          -18.5 4.94975 -4.94975,
+                          -18.5 4.33013 -2.5,
+                          -18.5 4.94975 -4.94975,
+                          -18.5 -4.28612e-16 -7,
+                          -18.5 4.33013 -2.5,
+                          -18.5 4.99978 -6.94716e-16,
+                          -18.5 4.94975 -4.94975,
+                          -18.5 2.49989 -4.32993,
+                          -18.5 -4.28612e-16 -7,
+                          -18.5 -3.06152e-16 -5,
+                          -18.5 -4.94975 -4.94975,
+                          -18.5 -3.06152e-16 -5,
+                          -18.5 -4.28612e-16 -7,
+                          -18.5 2.49989 -4.32993,
+                          -18.5 4.33013 -2.5,
+                          -18.5 -4.28612e-16 -7,
+                          -18.5 -4.94975 -4.94975,
+                          -18.5 -2.49989 -4.32993,
+                          -18.5 -3.06152e-16 -5,
+                          -24 -3.06152e-16 -5,
+                          -18.5 -3.06152e-16 -5,
+                          -18.5 -2.49989 -4.32993,
+                          -24 2.49989 -4.32993,
+                          -18.5 2.49989 -4.32993,
+                          -18.5 -3.06152e-16 -5,
+                          -24 -3.06152e-16 -5,
+                          -24 2.49989 -4.32993,
+                          -18.5 -3.06152e-16 -5,
+                          -18.5 -4.94975 -4.94975,
+                          -18.5 -4.33013 -2.5,
+                          -18.5 -2.49989 -4.32993,
+                          -24 -2.49989 -4.32993,
+                          -18.5 -2.49989 -4.32993,
+                          -18.5 -4.33013 -2.5,
+                          -24 -2.49989 -4.32993,
+                          -24 -3.06152e-16 -5,
+                          -18.5 -2.49989 -4.32993,
+                          -18.5 -4.94975 -4.94975,
+                          -18.5 -4.99978 -8.24402e-17,
+                          -18.5 -4.33013 -2.5,
+                          -24 -4.33013 -2.5,
+                          -18.5 -4.33013 -2.5,
+                          -18.5 -4.99978 -8.24402e-17,
+                          -24 -4.33013 -2.5,
+                          -24 -2.49989 -4.32993,
+                          -18.5 -4.33013 -2.5,
+                          -18.5 -4.94975 4.94975,
+                          -18.5 -4.33013 2.5,
+                          -18.5 -4.99978 -8.24402e-17,
+                          -24 -4.99978 -8.24402e-17,
+                          -18.5 -4.99978 -8.24402e-17,
+                          -18.5 -4.33013 2.5,
+                          -18.5 -7 0,
+                          -18.5 -4.94975 4.94975,
+                          -18.5 -4.99978 -8.24402e-17,
+                          -18.5 -4.94975 -4.94975,
+                          -18.5 -7 0,
+                          -18.5 -4.99978 -8.24402e-17,
+                          -24 -4.99978 -8.24402e-17,
+                          -24 -4.33013 -2.5,
+                          -18.5 -4.99978 -8.24402e-17,
+                          -24 -4.33013 2.5,
+                          -18.5 -4.33013 2.5,
+                          -18.5 -2.49989 4.32993,
+                          -24 -4.33013 2.5,
+                          -24 -4.99978 -8.24402e-17,
+                          -18.5 -4.33013 2.5,
+                          -24 -2.49989 4.32993,
+                          -18.5 -2.49989 4.32993,
+                          -18.5 3.06152e-16 5,
+                          -24 -2.49989 4.32993,
+                          -24 -4.33013 2.5,
+                          -18.5 -2.49989 4.32993,
+                          -24 3.06152e-16 5,
+                          -18.5 3.06152e-16 5,
+                          -18.5 2.49989 4.32993,
+                          -24 -2.49989 4.32993,
+                          -18.5 3.06152e-16 5,
+                          -24 3.06152e-16 5,
+                          -24 2.49989 4.32993,
+                          -18.5 2.49989 4.32993,
+                          -18.5 4.33013 2.5,
+                          -24 2.49989 4.32993,
+                          -24 3.06152e-16 5,
+                          -18.5 2.49989 4.32993,
+                          -24 4.33013 2.5,
+                          -18.5 4.33013 2.5,
+                          -18.5 4.99978 -6.94716e-16,
+                          -24 4.33013 2.5,
+                          -24 2.49989 4.32993,
+                          -18.5 4.33013 2.5,
+                          -24 4.99978 -6.94716e-16,
+                          -18.5 4.99978 -6.94716e-16,
+                          -18.5 4.33013 -2.5,
+                          -24 4.99978 -6.94716e-16,
+                          -24 4.33013 2.5,
+                          -18.5 4.99978 -6.94716e-16,
+                          -24 4.33013 -2.5,
+                          -18.5 4.33013 -2.5,
+                          -18.5 2.49989 -4.32993,
+                          -24 4.33013 -2.5,
+                          -24 4.99978 -6.94716e-16,
+                          -18.5 4.33013 -2.5,
+                          -24 2.49989 -4.32993,
+                          -24 4.33013 -2.5,
+                          -18.5 2.49989 -4.32993,
+                          -24 2.44921e-16 4,
+                          -24 3.06152e-16 5,
+                          -24 2.49989 4.32993,
+                          -24 -3.46422 1.99942,
+                          -24 -2.49989 4.32993,
+                          -24 3.06152e-16 5,
+                          -24 2.44921e-16 4,
+                          -24 -3.46422 1.99942,
+                          -24 3.06152e-16 5,
+                          -24 3.46422 1.99942,
+                          -24 2.49989 4.32993,
+                          -24 4.33013 2.5,
+                          -24 3.46422 1.99942,
+                          -24 2.44921e-16 4,
+                          -24 2.49989 4.32993,
+                          -24 4.33013 -2.5,
+                          -24 4.33013 2.5,
+                          -24 4.99978 -6.94716e-16,
+                          -24 3.46422 -1.99942,
+                          -24 4.33013 2.5,
+                          -24 4.33013 -2.5,
+                          -24 3.46422 -1.99942,
+                          -24 3.46422 1.99942,
+                          -24 4.33013 2.5,
+                          -24 3.46422 -1.99942,
+                          -24 4.33013 -2.5,
+                          -24 2.49989 -4.32993,
+                          -24 3.46422 -1.99942,
+                          -24 2.49989 -4.32993,
+                          -24 -3.06152e-16 -5,
+                          -24 -2.44921e-16 -4,
+                          -24 -3.06152e-16 -5,
+                          -24 -2.49989 -4.32993,
+                          -24 3.46422 -1.99942,
+                          -24 -3.06152e-16 -5,
+                          -24 -2.44921e-16 -4,
+                          -24 -3.46422 -1.99942,
+                          -24 -2.49989 -4.32993,
+                          -24 -4.33013 -2.5,
+                          -24 -3.46422 -1.99942,
+                          -24 -2.44921e-16 -4,
+                          -24 -2.49989 -4.32993,
+                          -24 -4.33013 2.5,
+                          -24 -4.33013 -2.5,
+                          -24 -4.99978 -8.24402e-17,
+                          -24 -3.46422 1.99942,
+                          -24 -4.33013 -2.5,
+                          -24 -4.33013 2.5,
+                          -24 -3.46422 1.99942,
+                          -24 -3.46422 -1.99942,
+                          -24 -4.33013 -2.5,
+                          -24 -3.46422 1.99942,
+                          -24 -4.33013 2.5,
+                          -24 -2.49989 4.32993,
+                          -47 -2.44921e-16 -4,
+                          -24 -2.44921e-16 -4,
+                          -24 -3.46422 -1.99942,
+                          -47 3.46422 -1.99942,
+                          -24 3.46422 -1.99942,
+                          -24 -2.44921e-16 -4,
+                          -47 -2.44921e-16 -4,
+                          -47 3.46422 -1.99942,
+                          -24 -2.44921e-16 -4,
+                          -47 -3.46422 -1.99942,
+                          -24 -3.46422 -1.99942,
+                          -24 -3.46422 1.99942,
+                          -47 -3.46422 -1.99942,
+                          -47 -2.44921e-16 -4,
+                          -24 -3.46422 -1.99942,
+                          -47 -3.46422 1.99942,
+                          -24 -3.46422 1.99942,
+                          -24 2.44921e-16 4,
+                          -47 -3.46422 -1.99942,
+                          -24 -3.46422 1.99942,
+                          -47 -3.46422 1.99942,
+                          -47 2.44921e-16 4,
+                          -24 2.44921e-16 4,
+                          -24 3.46422 1.99942,
+                          -47 -3.46422 1.99942,
+                          -24 2.44921e-16 4,
+                          -47 2.44921e-16 4,
+                          -47 3.46422 1.99942,
+                          -24 3.46422 1.99942,
+                          -24 3.46422 -1.99942,
+                          -47 3.46422 1.99942,
+                          -47 2.44921e-16 4,
+                          -24 3.46422 1.99942,
+                          -47 3.46422 -1.99942,
+                          -47 3.46422 1.99942,
+                          -24 3.46422 -1.99942,
+                          -47 -2.44921e-16 -4,
+                          -47 2.44921e-16 4,
+                          -47 3.46422 1.99942,
+                          -47 -3.46422 -1.99942,
+                          -47 2.44921e-16 4,
+                          -47 -2.44921e-16 -4,
+                          -47 -3.46422 -1.99942,
+                          -47 -3.46422 1.99942,
+                          -47 2.44921e-16 4,
+                          -47 -2.44921e-16 -4,
+                          -47 3.46422 1.99942,
+                          -47 3.46422 -1.99942 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.028 0.028 0.7
+    }
+    Separator {
+        Normal {
+            vector      [ 0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          -1.22461e-16 -1 6.12303e-17,
+                          -1.22461e-16 -1 6.12303e-17,
+                          -0.433884 -0.900969 5.51666e-17,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0.433884 -0.900969 5.51666e-17,
+                          0.433884 -0.900969 5.51666e-17,
+                          -1.22461e-16 -1 6.12303e-17,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0.433884 -0.900969 5.51666e-17,
+                          -1.22461e-16 -1 6.12303e-17,
+                          -1.22461e-16 -1 6.12303e-17,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          -0.433884 -0.900969 5.51666e-17,
+                          -0.433884 -0.900969 5.51666e-17,
+                          -0.781832 -0.62349 3.81765e-17,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          -0.433884 -0.900969 5.51666e-17,
+                          -1.22461e-16 -1 6.12303e-17,
+                          -0.433884 -0.900969 5.51666e-17,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          -0.781832 -0.62349 3.81765e-17,
+                          -0.781832 -0.62349 3.81765e-17,
+                          -0.974928 -0.222521 1.3625e-17,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          -0.433884 -0.900969 5.51666e-17,
+                          -0.781832 -0.62349 3.81765e-17,
+                          -0.781832 -0.62349 3.81765e-17,
+                          -0.974928 -0.222521 1.3625e-17,
+                          -0.974928 -0.222521 1.3625e-17,
+                          -0.974928 0.222521 -1.3625e-17,
+                          -0.781832 -0.62349 3.81765e-17,
+                          -0.974928 -0.222521 1.3625e-17,
+                          -0.974928 -0.222521 1.3625e-17,
+                          -0.974928 0.222521 -1.3625e-17,
+                          -0.974928 0.222521 -1.3625e-17,
+                          -0.781832 0.62349 -3.81765e-17,
+                          -0.974928 -0.222521 1.3625e-17,
+                          -0.974928 0.222521 -1.3625e-17,
+                          -0.974928 0.222521 -1.3625e-17,
+                          -0.781832 0.62349 -3.81765e-17,
+                          -0.781832 0.62349 -3.81765e-17,
+                          -0.433884 0.900969 -5.51666e-17,
+                          -0.974928 0.222521 -1.3625e-17,
+                          -0.781832 0.62349 -3.81765e-17,
+                          -0.781832 0.62349 -3.81765e-17,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          -0.433884 0.900969 -5.51666e-17,
+                          -0.433884 0.900969 -5.51666e-17,
+                          0 1 -6.12303e-17,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          -0.781832 0.62349 -3.81765e-17,
+                          -0.433884 0.900969 -5.51666e-17,
+                          -0.433884 0.900969 -5.51666e-17,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          2.44921e-16 1 -6.12303e-17,
+                          2.44921e-16 1 -6.12303e-17,
+                          0.433884 0.900969 -5.51666e-17,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          -0.433884 0.900969 -5.51666e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0.433884 0.900969 -5.51666e-17,
+                          0.433884 0.900969 -5.51666e-17,
+                          0.781832 0.62349 -3.81765e-17,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          2.44921e-16 1 -6.12303e-17,
+                          0.433884 0.900969 -5.51666e-17,
+                          0.433884 0.900969 -5.51666e-17,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0.781832 0.62349 -3.81765e-17,
+                          0.781832 0.62349 -3.81765e-17,
+                          0.974928 0.222521 -1.3625e-17,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0.433884 0.900969 -5.51666e-17,
+                          0.781832 0.62349 -3.81765e-17,
+                          0.781832 0.62349 -3.81765e-17,
+                          0.974928 0.222521 -1.3625e-17,
+                          0.974928 0.222521 -1.3625e-17,
+                          0.974928 -0.222521 1.3625e-17,
+                          0.781832 0.62349 -3.81765e-17,
+                          0.974928 0.222521 -1.3625e-17,
+                          0.974928 0.222521 -1.3625e-17,
+                          0.974928 -0.222521 1.3625e-17,
+                          0.974928 -0.222521 1.3625e-17,
+                          0.781832 -0.62349 3.81765e-17,
+                          0.974928 0.222521 -1.3625e-17,
+                          0.974928 -0.222521 1.3625e-17,
+                          0.974928 -0.222521 1.3625e-17,
+                          0.781832 -0.62349 3.81765e-17,
+                          0.781832 -0.62349 3.81765e-17,
+                          0.433884 -0.900969 5.51666e-17,
+                          0.974928 -0.222521 1.3625e-17,
+                          0.781832 -0.62349 3.81765e-17,
+                          0.781832 -0.62349 3.81765e-17,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0.781832 -0.62349 3.81765e-17,
+                          0.433884 -0.900969 5.51666e-17,
+                          0.433884 -0.900969 5.51666e-17,
+                          2.44921e-16 -1 6.12303e-17,
+                          2.44921e-16 -1 6.12303e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          0 -1 6.12303e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          1 1.83691e-16 0,
+                          0.707107 -0.707107 4.32964e-17,
+                          2.44921e-16 -1 6.12303e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          1 1.83691e-16 0,
+                          1 1.83691e-16 0,
+                          0.707107 0.707107 -4.32964e-17,
+                          0.707107 -0.707107 4.32964e-17,
+                          1 1.83691e-16 0,
+                          1 1.83691e-16 0,
+                          0.707107 0.707107 -4.32964e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          -1.22461e-16 1 -6.12303e-17,
+                          1 1.83691e-16 0,
+                          0.707107 0.707107 -4.32964e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          -1.22461e-16 1 -6.12303e-17,
+                          -1.22461e-16 1 -6.12303e-17,
+                          -0.707107 0.707107 -4.32964e-17,
+                          0.707107 0.707107 -4.32964e-17,
+                          -1.22461e-16 1 -6.12303e-17,
+                          -1.22461e-16 1 -6.12303e-17,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -1 -6.12303e-17 0,
+                          -1.22461e-16 1 -6.12303e-17,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -1 -6.12303e-17 0,
+                          -1 -6.12303e-17 0,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -0.707107 0.707107 -4.32964e-17,
+                          -1 -6.12303e-17 0,
+                          -1 -6.12303e-17 0,
+                          -1 -6.12303e-17 0,
+                          -0.707107 -0.707107 4.32964e-17,
+                          -0.707107 -0.707107 4.32964e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          1.22461e-16 1 -6.12303e-17,
+                          1.22461e-16 1 -6.12303e-17,
+                          -0.433884 0.900969 -5.51666e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0.433884 0.900969 -5.51666e-17,
+                          0.433884 0.900969 -5.51666e-17,
+                          1.22461e-16 1 -6.12303e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0.433884 0.900969 -5.51666e-17,
+                          1.22461e-16 1 -6.12303e-17,
+                          1.22461e-16 1 -6.12303e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.433884 0.900969 -5.51666e-17,
+                          -0.433884 0.900969 -5.51666e-17,
+                          -0.781832 0.62349 -3.81765e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.433884 0.900969 -5.51666e-17,
+                          1.22461e-16 1 -6.12303e-17,
+                          -0.433884 0.900969 -5.51666e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.781832 0.62349 -3.81765e-17,
+                          -0.781832 0.62349 -3.81765e-17,
+                          -0.974928 0.222521 -1.3625e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.433884 0.900969 -5.51666e-17,
+                          -0.781832 0.62349 -3.81765e-17,
+                          -0.781832 0.62349 -3.81765e-17,
+                          -0.974928 0.222521 -1.3625e-17,
+                          -0.974928 0.222521 -1.3625e-17,
+                          -0.974928 -0.222521 1.3625e-17,
+                          -0.781832 0.62349 -3.81765e-17,
+                          -0.974928 0.222521 -1.3625e-17,
+                          -0.974928 0.222521 -1.3625e-17,
+                          -0.974928 -0.222521 1.3625e-17,
+                          -0.974928 -0.222521 1.3625e-17,
+                          -0.781832 -0.62349 3.81765e-17,
+                          -0.974928 0.222521 -1.3625e-17,
+                          -0.974928 -0.222521 1.3625e-17,
+                          -0.974928 -0.222521 1.3625e-17,
+                          -0.781832 -0.62349 3.81765e-17,
+                          -0.781832 -0.62349 3.81765e-17,
+                          -0.433884 -0.900969 5.51666e-17,
+                          -0.974928 -0.222521 1.3625e-17,
+                          -0.781832 -0.62349 3.81765e-17,
+                          -0.781832 -0.62349 3.81765e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.433884 -0.900969 5.51666e-17,
+                          -0.433884 -0.900969 5.51666e-17,
+                          -2.44921e-16 -1 6.12303e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.781832 -0.62349 3.81765e-17,
+                          -0.433884 -0.900969 5.51666e-17,
+                          -0.433884 -0.900969 5.51666e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0.433884 -0.900969 5.51666e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.433884 -0.900969 5.51666e-17,
+                          -2.44921e-16 -1 6.12303e-17,
+                          -2.44921e-16 -1 6.12303e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0.433884 -0.900969 5.51666e-17,
+                          0.433884 -0.900969 5.51666e-17,
+                          0.781832 -0.62349 3.81765e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -1 6.12303e-17,
+                          0.433884 -0.900969 5.51666e-17,
+                          0.433884 -0.900969 5.51666e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0.781832 -0.62349 3.81765e-17,
+                          0.781832 -0.62349 3.81765e-17,
+                          0.974928 -0.222521 1.3625e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0.433884 -0.900969 5.51666e-17,
+                          0.781832 -0.62349 3.81765e-17,
+                          0.781832 -0.62349 3.81765e-17,
+                          0.974928 -0.222521 1.3625e-17,
+                          0.974928 -0.222521 1.3625e-17,
+                          0.974928 0.222521 -1.3625e-17,
+                          0.781832 -0.62349 3.81765e-17,
+                          0.974928 -0.222521 1.3625e-17,
+                          0.974928 -0.222521 1.3625e-17,
+                          0.974928 0.222521 -1.3625e-17,
+                          0.974928 0.222521 -1.3625e-17,
+                          0.781832 0.62349 -3.81765e-17,
+                          0.974928 -0.222521 1.3625e-17,
+                          0.974928 0.222521 -1.3625e-17,
+                          0.974928 0.222521 -1.3625e-17,
+                          0.781832 0.62349 -3.81765e-17,
+                          0.781832 0.62349 -3.81765e-17,
+                          0.433884 0.900969 -5.51666e-17,
+                          0.974928 0.222521 -1.3625e-17,
+                          0.781832 0.62349 -3.81765e-17,
+                          0.781832 0.62349 -3.81765e-17,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0.781832 0.62349 -3.81765e-17,
+                          0.433884 0.900969 -5.51666e-17,
+                          0.433884 0.900969 -5.51666e-17,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 13.6677 -28.3804 -76.3,
+                          13.6677 28.3804 -76.3,
+                          -1e-20 31.5 -76.3,
+                          -1e-20 31.5 -65.8,
+                          -1e-20 31.5 -76.3,
+                          13.6677 28.3804 -76.3,
+                          7 -4.67187e-15 -76.3,
+                          13.6677 -28.3804 -76.3,
+                          -1e-20 31.5 -76.3,
+                          -1e-20 7 -76.3,
+                          -1e-20 31.5 -76.3,
+                          -13.6677 28.3804 -76.3,
+                          -13.6677 28.3804 -65.8,
+                          -13.6677 28.3804 -76.3,
+                          -1e-20 31.5 -76.3,
+                          4.94975 4.94975 -76.3,
+                          -1e-20 31.5 -76.3,
+                          -1e-20 7 -76.3,
+                          4.94975 4.94975 -76.3,
+                          7 -4.67187e-15 -76.3,
+                          -1e-20 31.5 -76.3,
+                          -13.6677 28.3804 -65.8,
+                          -1e-20 31.5 -76.3,
+                          -1e-20 31.5 -65.8,
+                          24.6279 -19.6396 -76.3,
+                          24.6279 19.6396 -76.3,
+                          13.6677 28.3804 -76.3,
+                          13.6677 28.3804 -65.8,
+                          13.6677 28.3804 -76.3,
+                          24.6279 19.6396 -76.3,
+                          13.6677 -28.3804 -76.3,
+                          24.6279 -19.6396 -76.3,
+                          13.6677 28.3804 -76.3,
+                          13.6677 28.3804 -65.8,
+                          -1e-20 31.5 -65.8,
+                          13.6677 28.3804 -76.3,
+                          30.7102 -7.00926 -76.3,
+                          30.7102 7.00926 -76.3,
+                          24.6279 19.6396 -76.3,
+                          24.6279 19.6396 -65.8,
+                          24.6279 19.6396 -76.3,
+                          30.7102 7.00926 -76.3,
+                          24.6279 -19.6396 -76.3,
+                          30.7102 -7.00926 -76.3,
+                          24.6279 19.6396 -76.3,
+                          13.6677 28.3804 -65.8,
+                          24.6279 19.6396 -76.3,
+                          24.6279 19.6396 -65.8,
+                          30.7102 7.00926 -65.8,
+                          30.7102 7.00926 -76.3,
+                          30.7102 -7.00926 -76.3,
+                          24.6279 19.6396 -65.8,
+                          30.7102 7.00926 -76.3,
+                          30.7102 7.00926 -65.8,
+                          30.7102 -7.00926 -65.8,
+                          30.7102 -7.00926 -76.3,
+                          24.6279 -19.6396 -76.3,
+                          30.7102 7.00926 -65.8,
+                          30.7102 -7.00926 -76.3,
+                          30.7102 -7.00926 -65.8,
+                          24.6279 -19.6396 -65.8,
+                          24.6279 -19.6396 -76.3,
+                          13.6677 -28.3804 -76.3,
+                          30.7102 -7.00926 -65.8,
+                          24.6279 -19.6396 -76.3,
+                          24.6279 -19.6396 -65.8,
+                          -1e-20 -7 -76.3,
+                          -1e-20 -31.5 -76.3,
+                          13.6677 -28.3804 -76.3,
+                          13.6677 -28.3804 -65.8,
+                          13.6677 -28.3804 -76.3,
+                          -1e-20 -31.5 -76.3,
+                          4.94975 -4.94975 -76.3,
+                          -1e-20 -7 -76.3,
+                          13.6677 -28.3804 -76.3,
+                          7 -4.67187e-15 -76.3,
+                          4.94975 -4.94975 -76.3,
+                          13.6677 -28.3804 -76.3,
+                          24.6279 -19.6396 -65.8,
+                          13.6677 -28.3804 -76.3,
+                          13.6677 -28.3804 -65.8,
+                          -13.6677 28.3804 -76.3,
+                          -13.6677 -28.3804 -76.3,
+                          -1e-20 -31.5 -76.3,
+                          -1e-20 -31.5 -65.8,
+                          -1e-20 -31.5 -76.3,
+                          -13.6677 -28.3804 -76.3,
+                          -7 -5.95771e-15 -76.3,
+                          -13.6677 28.3804 -76.3,
+                          -1e-20 -31.5 -76.3,
+                          -4.94975 -4.94975 -76.3,
+                          -7 -5.95771e-15 -76.3,
+                          -1e-20 -31.5 -76.3,
+                          -1e-20 -7 -76.3,
+                          -4.94975 -4.94975 -76.3,
+                          -1e-20 -31.5 -76.3,
+                          13.6677 -28.3804 -65.8,
+                          -1e-20 -31.5 -76.3,
+                          -1e-20 -31.5 -65.8,
+                          -24.6279 19.6396 -76.3,
+                          -24.6279 -19.6396 -76.3,
+                          -13.6677 -28.3804 -76.3,
+                          -13.6677 -28.3804 -65.8,
+                          -13.6677 -28.3804 -76.3,
+                          -24.6279 -19.6396 -76.3,
+                          -13.6677 28.3804 -76.3,
+                          -24.6279 19.6396 -76.3,
+                          -13.6677 -28.3804 -76.3,
+                          -1e-20 -31.5 -65.8,
+                          -13.6677 -28.3804 -76.3,
+                          -13.6677 -28.3804 -65.8,
+                          -30.7102 7.00926 -76.3,
+                          -30.7102 -7.00926 -76.3,
+                          -24.6279 -19.6396 -76.3,
+                          -24.6279 -19.6396 -65.8,
+                          -24.6279 -19.6396 -76.3,
+                          -30.7102 -7.00926 -76.3,
+                          -24.6279 19.6396 -76.3,
+                          -30.7102 7.00926 -76.3,
+                          -24.6279 -19.6396 -76.3,
+                          -13.6677 -28.3804 -65.8,
+                          -24.6279 -19.6396 -76.3,
+                          -24.6279 -19.6396 -65.8,
+                          -30.7102 -7.00926 -65.8,
+                          -30.7102 -7.00926 -76.3,
+                          -30.7102 7.00926 -76.3,
+                          -24.6279 -19.6396 -65.8,
+                          -30.7102 -7.00926 -76.3,
+                          -30.7102 -7.00926 -65.8,
+                          -30.7102 7.00926 -65.8,
+                          -30.7102 7.00926 -76.3,
+                          -24.6279 19.6396 -76.3,
+                          -30.7102 -7.00926 -65.8,
+                          -30.7102 7.00926 -76.3,
+                          -30.7102 7.00926 -65.8,
+                          -24.6279 19.6396 -65.8,
+                          -24.6279 19.6396 -76.3,
+                          -13.6677 28.3804 -76.3,
+                          -30.7102 7.00926 -65.8,
+                          -24.6279 19.6396 -76.3,
+                          -24.6279 19.6396 -65.8,
+                          -4.94975 4.94975 -76.3,
+                          -1e-20 7 -76.3,
+                          -13.6677 28.3804 -76.3,
+                          -7 -5.95771e-15 -76.3,
+                          -4.94975 4.94975 -76.3,
+                          -13.6677 28.3804 -76.3,
+                          -24.6279 19.6396 -65.8,
+                          -13.6677 28.3804 -76.3,
+                          -13.6677 28.3804 -65.8,
+                          -1e-20 7 -77.8,
+                          -1e-20 7 -76.3,
+                          -4.94975 4.94975 -76.3,
+                          4.94975 4.94975 -77.8,
+                          4.94975 4.94975 -76.3,
+                          -1e-20 7 -76.3,
+                          4.94975 4.94975 -77.8,
+                          -1e-20 7 -76.3,
+                          -1e-20 7 -77.8,
+                          -4.94975 4.94975 -77.8,
+                          -4.94975 4.94975 -76.3,
+                          -7 -5.95771e-15 -76.3,
+                          -4.94975 4.94975 -77.8,
+                          -1e-20 7 -77.8,
+                          -4.94975 4.94975 -76.3,
+                          -7 -6.04956e-15 -77.8,
+                          -7 -5.95771e-15 -76.3,
+                          -4.94975 -4.94975 -76.3,
+                          -4.94975 4.94975 -77.8,
+                          -7 -5.95771e-15 -76.3,
+                          -7 -6.04956e-15 -77.8,
+                          -4.94975 -4.94975 -77.8,
+                          -4.94975 -4.94975 -76.3,
+                          -1e-20 -7 -76.3,
+                          -7 -6.04956e-15 -77.8,
+                          -4.94975 -4.94975 -76.3,
+                          -4.94975 -4.94975 -77.8,
+                          -1e-20 -7 -77.8,
+                          -1e-20 -7 -76.3,
+                          4.94975 -4.94975 -76.3,
+                          -4.94975 -4.94975 -77.8,
+                          -1e-20 -7 -76.3,
+                          -1e-20 -7 -77.8,
+                          4.94975 -4.94975 -77.8,
+                          4.94975 -4.94975 -76.3,
+                          7 -4.67187e-15 -76.3,
+                          -1e-20 -7 -77.8,
+                          4.94975 -4.94975 -76.3,
+                          4.94975 -4.94975 -77.8,
+                          7 -4.76372e-15 -77.8,
+                          7 -4.67187e-15 -76.3,
+                          4.94975 4.94975 -76.3,
+                          4.94975 -4.94975 -77.8,
+                          7 -4.67187e-15 -76.3,
+                          7 -4.76372e-15 -77.8,
+                          7 -4.76372e-15 -77.8,
+                          4.94975 4.94975 -76.3,
+                          4.94975 4.94975 -77.8,
+                          -14.3185 -29.7318 -77.8,
+                          -14.3185 29.7318 -77.8,
+                          -1e-20 33 -77.8,
+                          -1e-20 33 -65.8,
+                          -1e-20 33 -77.8,
+                          -14.3185 29.7318 -77.8,
+                          -7 -6.04956e-15 -77.8,
+                          -14.3185 -29.7318 -77.8,
+                          -1e-20 33 -77.8,
+                          -1e-20 7 -77.8,
+                          -1e-20 33 -77.8,
+                          14.3185 29.7318 -77.8,
+                          14.3185 29.7318 -65.8,
+                          14.3185 29.7318 -77.8,
+                          -1e-20 33 -77.8,
+                          -4.94975 4.94975 -77.8,
+                          -1e-20 33 -77.8,
+                          -1e-20 7 -77.8,
+                          -4.94975 4.94975 -77.8,
+                          -7 -6.04956e-15 -77.8,
+                          -1e-20 33 -77.8,
+                          14.3185 29.7318 -65.8,
+                          -1e-20 33 -77.8,
+                          -1e-20 33 -65.8,
+                          -25.8006 -20.5748 -77.8,
+                          -25.8006 20.5748 -77.8,
+                          -14.3185 29.7318 -77.8,
+                          -14.3185 29.7318 -65.8,
+                          -14.3185 29.7318 -77.8,
+                          -25.8006 20.5748 -77.8,
+                          -14.3185 -29.7318 -77.8,
+                          -25.8006 -20.5748 -77.8,
+                          -14.3185 29.7318 -77.8,
+                          -14.3185 29.7318 -65.8,
+                          -1e-20 33 -65.8,
+                          -14.3185 29.7318 -77.8,
+                          -32.1726 -7.34303 -77.8,
+                          -32.1726 7.34303 -77.8,
+                          -25.8006 20.5748 -77.8,
+                          -25.8006 20.5748 -65.8,
+                          -25.8006 20.5748 -77.8,
+                          -32.1726 7.34303 -77.8,
+                          -25.8006 -20.5748 -77.8,
+                          -32.1726 -7.34303 -77.8,
+                          -25.8006 20.5748 -77.8,
+                          -14.3185 29.7318 -65.8,
+                          -25.8006 20.5748 -77.8,
+                          -25.8006 20.5748 -65.8,
+                          -32.1726 7.34303 -65.8,
+                          -32.1726 7.34303 -77.8,
+                          -32.1726 -7.34303 -77.8,
+                          -25.8006 20.5748 -65.8,
+                          -32.1726 7.34303 -77.8,
+                          -32.1726 7.34303 -65.8,
+                          -32.1726 -7.34303 -65.8,
+                          -32.1726 -7.34303 -77.8,
+                          -25.8006 -20.5748 -77.8,
+                          -32.1726 7.34303 -65.8,
+                          -32.1726 -7.34303 -77.8,
+                          -32.1726 -7.34303 -65.8,
+                          -25.8006 -20.5748 -65.8,
+                          -25.8006 -20.5748 -77.8,
+                          -14.3185 -29.7318 -77.8,
+                          -32.1726 -7.34303 -65.8,
+                          -25.8006 -20.5748 -77.8,
+                          -25.8006 -20.5748 -65.8,
+                          -1e-20 -7 -77.8,
+                          -1e-20 -33 -77.8,
+                          -14.3185 -29.7318 -77.8,
+                          -14.3185 -29.7318 -65.8,
+                          -14.3185 -29.7318 -77.8,
+                          -1e-20 -33 -77.8,
+                          -4.94975 -4.94975 -77.8,
+                          -1e-20 -7 -77.8,
+                          -14.3185 -29.7318 -77.8,
+                          -7 -6.04956e-15 -77.8,
+                          -4.94975 -4.94975 -77.8,
+                          -14.3185 -29.7318 -77.8,
+                          -25.8006 -20.5748 -65.8,
+                          -14.3185 -29.7318 -77.8,
+                          -14.3185 -29.7318 -65.8,
+                          14.3185 29.7318 -77.8,
+                          14.3185 -29.7318 -77.8,
+                          -1e-20 -33 -77.8,
+                          -1e-20 -33 -65.8,
+                          -1e-20 -33 -77.8,
+                          14.3185 -29.7318 -77.8,
+                          7 -4.76372e-15 -77.8,
+                          14.3185 29.7318 -77.8,
+                          -1e-20 -33 -77.8,
+                          4.94975 -4.94975 -77.8,
+                          7 -4.76372e-15 -77.8,
+                          -1e-20 -33 -77.8,
+                          -1e-20 -7 -77.8,
+                          4.94975 -4.94975 -77.8,
+                          -1e-20 -33 -77.8,
+                          -14.3185 -29.7318 -65.8,
+                          -1e-20 -33 -77.8,
+                          -1e-20 -33 -65.8,
+                          25.8006 20.5748 -77.8,
+                          25.8006 -20.5748 -77.8,
+                          14.3185 -29.7318 -77.8,
+                          14.3185 -29.7318 -65.8,
+                          14.3185 -29.7318 -77.8,
+                          25.8006 -20.5748 -77.8,
+                          14.3185 29.7318 -77.8,
+                          25.8006 20.5748 -77.8,
+                          14.3185 -29.7318 -77.8,
+                          -1e-20 -33 -65.8,
+                          14.3185 -29.7318 -77.8,
+                          14.3185 -29.7318 -65.8,
+                          32.1726 7.34303 -77.8,
+                          32.1726 -7.34303 -77.8,
+                          25.8006 -20.5748 -77.8,
+                          25.8006 -20.5748 -65.8,
+                          25.8006 -20.5748 -77.8,
+                          32.1726 -7.34303 -77.8,
+                          25.8006 20.5748 -77.8,
+                          32.1726 7.34303 -77.8,
+                          25.8006 -20.5748 -77.8,
+                          14.3185 -29.7318 -65.8,
+                          25.8006 -20.5748 -77.8,
+                          25.8006 -20.5748 -65.8,
+                          32.1726 -7.34303 -65.8,
+                          32.1726 -7.34303 -77.8,
+                          32.1726 7.34303 -77.8,
+                          25.8006 -20.5748 -65.8,
+                          32.1726 -7.34303 -77.8,
+                          32.1726 -7.34303 -65.8,
+                          32.1726 7.34303 -65.8,
+                          32.1726 7.34303 -77.8,
+                          25.8006 20.5748 -77.8,
+                          32.1726 -7.34303 -65.8,
+                          32.1726 7.34303 -77.8,
+                          32.1726 7.34303 -65.8,
+                          25.8006 20.5748 -65.8,
+                          25.8006 20.5748 -77.8,
+                          14.3185 29.7318 -77.8,
+                          32.1726 7.34303 -65.8,
+                          25.8006 20.5748 -77.8,
+                          25.8006 20.5748 -65.8,
+                          4.94975 4.94975 -77.8,
+                          -1e-20 7 -77.8,
+                          14.3185 29.7318 -77.8,
+                          7 -4.76372e-15 -77.8,
+                          4.94975 4.94975 -77.8,
+                          14.3185 29.7318 -77.8,
+                          25.8006 20.5748 -65.8,
+                          14.3185 29.7318 -77.8,
+                          14.3185 29.7318 -65.8,
+                          13.6677 28.3804 -65.8,
+                          14.3185 29.7318 -65.8,
+                          -1e-20 33 -65.8,
+                          -1e-20 31.5 -65.8,
+                          -1e-20 33 -65.8,
+                          -14.3185 29.7318 -65.8,
+                          13.6677 28.3804 -65.8,
+                          -1e-20 33 -65.8,
+                          -1e-20 31.5 -65.8,
+                          24.6279 19.6396 -65.8,
+                          25.8006 20.5748 -65.8,
+                          14.3185 29.7318 -65.8,
+                          13.6677 28.3804 -65.8,
+                          24.6279 19.6396 -65.8,
+                          14.3185 29.7318 -65.8,
+                          30.7102 7.00926 -65.8,
+                          32.1726 7.34303 -65.8,
+                          25.8006 20.5748 -65.8,
+                          24.6279 19.6396 -65.8,
+                          30.7102 7.00926 -65.8,
+                          25.8006 20.5748 -65.8,
+                          30.7102 7.00926 -65.8,
+                          32.1726 -7.34303 -65.8,
+                          32.1726 7.34303 -65.8,
+                          30.7102 -7.00926 -65.8,
+                          25.8006 -20.5748 -65.8,
+                          32.1726 -7.34303 -65.8,
+                          30.7102 7.00926 -65.8,
+                          30.7102 -7.00926 -65.8,
+                          32.1726 -7.34303 -65.8,
+                          24.6279 -19.6396 -65.8,
+                          14.3185 -29.7318 -65.8,
+                          25.8006 -20.5748 -65.8,
+                          30.7102 -7.00926 -65.8,
+                          24.6279 -19.6396 -65.8,
+                          25.8006 -20.5748 -65.8,
+                          -1e-20 -31.5 -65.8,
+                          -1e-20 -33 -65.8,
+                          14.3185 -29.7318 -65.8,
+                          13.6677 -28.3804 -65.8,
+                          -1e-20 -31.5 -65.8,
+                          14.3185 -29.7318 -65.8,
+                          24.6279 -19.6396 -65.8,
+                          13.6677 -28.3804 -65.8,
+                          14.3185 -29.7318 -65.8,
+                          -13.6677 -28.3804 -65.8,
+                          -14.3185 -29.7318 -65.8,
+                          -1e-20 -33 -65.8,
+                          -1e-20 -31.5 -65.8,
+                          -13.6677 -28.3804 -65.8,
+                          -1e-20 -33 -65.8,
+                          -24.6279 -19.6396 -65.8,
+                          -25.8006 -20.5748 -65.8,
+                          -14.3185 -29.7318 -65.8,
+                          -13.6677 -28.3804 -65.8,
+                          -24.6279 -19.6396 -65.8,
+                          -14.3185 -29.7318 -65.8,
+                          -30.7102 -7.00926 -65.8,
+                          -32.1726 -7.34303 -65.8,
+                          -25.8006 -20.5748 -65.8,
+                          -24.6279 -19.6396 -65.8,
+                          -30.7102 -7.00926 -65.8,
+                          -25.8006 -20.5748 -65.8,
+                          -30.7102 -7.00926 -65.8,
+                          -32.1726 7.34303 -65.8,
+                          -32.1726 -7.34303 -65.8,
+                          -30.7102 7.00926 -65.8,
+                          -25.8006 20.5748 -65.8,
+                          -32.1726 7.34303 -65.8,
+                          -30.7102 -7.00926 -65.8,
+                          -30.7102 7.00926 -65.8,
+                          -32.1726 7.34303 -65.8,
+                          -24.6279 19.6396 -65.8,
+                          -14.3185 29.7318 -65.8,
+                          -25.8006 20.5748 -65.8,
+                          -30.7102 7.00926 -65.8,
+                          -24.6279 19.6396 -65.8,
+                          -25.8006 20.5748 -65.8,
+                          -13.6677 28.3804 -65.8,
+                          -1e-20 31.5 -65.8,
+                          -14.3185 29.7318 -65.8,
+                          -24.6279 19.6396 -65.8,
+                          -13.6677 28.3804 -65.8,
+                          -14.3185 29.7318 -65.8 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/platform/hd_platform_pitch_link.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/platform/hd_platform_pitch_link.iv
new file mode 100644
index 0000000000000000000000000000000000000000..c03e7e6793de935c857060dcb584eb5563cb9d6e
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/platform/hd_platform_pitch_link.iv
@@ -0,0 +1,20344 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+
+    Material {
+        diffuseColor    0.95 0.77 0.53
+    }
+    Separator {
+        Normal {
+            vector      [ 0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          1 0 -2.44921e-16,
+                          1 0 -2.44921e-16,
+                          0.974928 0 -0.222521,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.977931 0 0.208927,
+                          0.974928 0 0.222521,
+                          1 0 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.977931 0 0.208927,
+                          1 0 0,
+                          1 0 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.912701 0 -0.408627,
+                          0.974928 0 -0.222521,
+                          0.900969 0 -0.433884,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.977931 0 -0.208927,
+                          1 0 -2.44921e-16,
+                          0.974928 0 -0.222521,
+                          0.912701 0 -0.408627,
+                          0.977931 0 -0.208927,
+                          0.974928 0 -0.222521,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.807192 0 -0.590289,
+                          0.900969 0 -0.433884,
+                          0.781832 0 -0.62349,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.807192 0 -0.590289,
+                          0.912701 0 -0.408627,
+                          0.900969 0 -0.433884,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.666062 0 -0.745896,
+                          0.781832 0 -0.62349,
+                          0.62349 0 -0.781832,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.666062 0 -0.745896,
+                          0.807192 0 -0.590289,
+                          0.781832 0 -0.62349,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.495541 0 -0.868584,
+                          0.62349 0 -0.781832,
+                          0.433884 0 -0.900969,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.495541 0 -0.868584,
+                          0.666062 0 -0.745896,
+                          0.62349 0 -0.781832,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.303155 0 -0.952941,
+                          0.433884 0 -0.900969,
+                          0.222521 0 -0.974928,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.303155 0 -0.952941,
+                          0.495541 0 -0.868584,
+                          0.433884 0 -0.900969,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.102476 0 -0.994736,
+                          0.222521 0 -0.974928,
+                          -1.83691e-16 0 -1,
+                          0.102476 0 -0.994736,
+                          0.303155 0 -0.952941,
+                          0.222521 0 -0.974928,
+                          -0.102476 0 -0.994736,
+                          -1.83691e-16 0 -1,
+                          -0.222521 0 -0.974928,
+                          -0.102476 0 -0.994736,
+                          0.102476 0 -0.994736,
+                          -1.83691e-16 0 -1,
+                          -0.303155 0 -0.952941,
+                          -0.222521 0 -0.974928,
+                          -0.433884 0 -0.900969,
+                          -0.303155 0 -0.952941,
+                          -0.102476 0 -0.994736,
+                          -0.222521 0 -0.974928,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.495541 0 -0.868584,
+                          -0.433884 0 -0.900969,
+                          -0.62349 0 -0.781832,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.495541 0 -0.868584,
+                          -0.303155 0 -0.952941,
+                          -0.433884 0 -0.900969,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.666062 0 -0.745896,
+                          -0.62349 0 -0.781832,
+                          -0.781832 0 -0.62349,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.666062 0 -0.745896,
+                          -0.495541 0 -0.868584,
+                          -0.62349 0 -0.781832,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.807192 0 -0.590289,
+                          -0.781832 0 -0.62349,
+                          -0.900969 0 -0.433884,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.807192 0 -0.590289,
+                          -0.666062 0 -0.745896,
+                          -0.781832 0 -0.62349,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.912701 0 -0.408627,
+                          -0.900969 0 -0.433884,
+                          -0.974928 0 -0.222521,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.912701 0 -0.408627,
+                          -0.807192 0 -0.590289,
+                          -0.900969 0 -0.433884,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.977931 0 -0.208927,
+                          -0.974928 0 -0.222521,
+                          -1 0 1.22461e-16,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.977931 0 -0.208927,
+                          -0.912701 0 -0.408627,
+                          -0.974928 0 -0.222521,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -1 0 1.22461e-16,
+                          -1 0 1.22461e-16,
+                          -0.974928 0 0.222521,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.977931 0 -0.208927,
+                          -1 0 1.22461e-16,
+                          -1 0 1.22461e-16,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.912701 0 0.408627,
+                          -0.974928 0 0.222521,
+                          -0.900969 0 0.433884,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.977931 0 0.208927,
+                          -1 0 1.22461e-16,
+                          -0.974928 0 0.222521,
+                          -0.912701 0 0.408627,
+                          -0.977931 0 0.208927,
+                          -0.974928 0 0.222521,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.807192 0 0.590289,
+                          -0.900969 0 0.433884,
+                          -0.781832 0 0.62349,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.807192 0 0.590289,
+                          -0.912701 0 0.408627,
+                          -0.900969 0 0.433884,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.666062 0 0.745896,
+                          -0.781832 0 0.62349,
+                          -0.62349 0 0.781832,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.666062 0 0.745896,
+                          -0.807192 0 0.590289,
+                          -0.781832 0 0.62349,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.495541 0 0.868584,
+                          -0.62349 0 0.781832,
+                          -0.433884 0 0.900969,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.495541 0 0.868584,
+                          -0.666062 0 0.745896,
+                          -0.62349 0 0.781832,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.303155 0 0.952941,
+                          -0.433884 0 0.900969,
+                          -0.222521 0 0.974928,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.303155 0 0.952941,
+                          -0.495541 0 0.868584,
+                          -0.433884 0 0.900969,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.102476 0 0.994736,
+                          -0.222521 0 0.974928,
+                          6.12303e-17 0 1,
+                          -0.102476 0 0.994736,
+                          -0.303155 0 0.952941,
+                          -0.222521 0 0.974928,
+                          0.102476 0 0.994736,
+                          6.12303e-17 0 1,
+                          0.222521 0 0.974928,
+                          0.102476 0 0.994736,
+                          -0.102476 0 0.994736,
+                          6.12303e-17 0 1,
+                          0.303155 0 0.952941,
+                          0.222521 0 0.974928,
+                          0.433884 0 0.900969,
+                          0.303155 0 0.952941,
+                          0.102476 0 0.994736,
+                          0.222521 0 0.974928,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.495541 0 0.868584,
+                          0.433884 0 0.900969,
+                          0.62349 0 0.781832,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.495541 0 0.868584,
+                          0.303155 0 0.952941,
+                          0.433884 0 0.900969,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.666062 0 0.745896,
+                          0.62349 0 0.781832,
+                          0.781832 0 0.62349,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.666062 0 0.745896,
+                          0.495541 0 0.868584,
+                          0.62349 0 0.781832,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.807192 0 0.590289,
+                          0.781832 0 0.62349,
+                          0.900969 0 0.433884,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.807192 0 0.590289,
+                          0.666062 0 0.745896,
+                          0.781832 0 0.62349,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.912701 0 0.408627,
+                          0.900969 0 0.433884,
+                          0.974928 0 0.222521,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.912701 0 0.408627,
+                          0.807192 0 0.590289,
+                          0.900969 0 0.433884,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.977931 0 0.208927,
+                          0.912701 0 0.408627,
+                          0.974928 0 0.222521,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.970942 0 -0.239316,
+                          -0.970942 0 0.239316,
+                          -0.970942 0 0.239316,
+                          -1 0 2.44921e-16,
+                          -1 0 2.44921e-16,
+                          -0.970942 0 0.239316,
+                          -1 0 2.44921e-16,
+                          -0.970942 0 -0.239316,
+                          -0.970942 0 -0.239316,
+                          -0.885456 0 -0.464723,
+                          -0.970942 0 -0.239316,
+                          -1 0 0,
+                          -0.970942 0 -0.239316,
+                          -0.885456 0 -0.464723,
+                          -0.885456 0 -0.464723,
+                          -0.748511 0 -0.663123,
+                          -0.885456 0 -0.464723,
+                          -0.970942 0 -0.239316,
+                          -0.885456 0 -0.464723,
+                          -0.748511 0 -0.663123,
+                          -0.748511 0 -0.663123,
+                          -0.568065 0 -0.822984,
+                          -0.748511 0 -0.663123,
+                          -0.885456 0 -0.464723,
+                          -0.748511 0 -0.663123,
+                          -0.568065 0 -0.822984,
+                          -0.568065 0 -0.822984,
+                          -0.354605 0 -0.935016,
+                          -0.568065 0 -0.822984,
+                          -0.748511 0 -0.663123,
+                          -0.568065 0 -0.822984,
+                          -0.354605 0 -0.935016,
+                          -0.354605 0 -0.935016,
+                          -0.120537 0 -0.992709,
+                          -0.354605 0 -0.935016,
+                          -0.568065 0 -0.822984,
+                          -0.354605 0 -0.935016,
+                          -0.120537 0 -0.992709,
+                          -0.120537 0 -0.992709,
+                          0.120537 0 -0.992709,
+                          -0.120537 0 -0.992709,
+                          -0.354605 0 -0.935016,
+                          -0.120537 0 -0.992709,
+                          0.120537 0 -0.992709,
+                          0.120537 0 -0.992709,
+                          0.354605 0 -0.935016,
+                          0.120537 0 -0.992709,
+                          -0.120537 0 -0.992709,
+                          0.120537 0 -0.992709,
+                          0.354605 0 -0.935016,
+                          0.354605 0 -0.935016,
+                          0.568065 0 -0.822984,
+                          0.354605 0 -0.935016,
+                          0.120537 0 -0.992709,
+                          0.354605 0 -0.935016,
+                          0.568065 0 -0.822984,
+                          0.568065 0 -0.822984,
+                          0.748511 0 -0.663123,
+                          0.568065 0 -0.822984,
+                          0.354605 0 -0.935016,
+                          0.568065 0 -0.822984,
+                          0.748511 0 -0.663123,
+                          0.748511 0 -0.663123,
+                          0.885456 0 -0.464723,
+                          0.748511 0 -0.663123,
+                          0.568065 0 -0.822984,
+                          0.748511 0 -0.663123,
+                          0.885456 0 -0.464723,
+                          0.885456 0 -0.464723,
+                          0.970942 0 -0.239316,
+                          0.885456 0 -0.464723,
+                          0.748511 0 -0.663123,
+                          0.885456 0 -0.464723,
+                          0.970942 0 -0.239316,
+                          0.970942 0 -0.239316,
+                          1 0 -1.22461e-16,
+                          0.970942 0 -0.239316,
+                          0.885456 0 -0.464723,
+                          0.970942 0 -0.239316,
+                          1 0 -1.22461e-16,
+                          1 0 -1.22461e-16,
+                          0.970942 0 0.239316,
+                          0.970942 0 -0.239316,
+                          1 0 -1.22461e-16,
+                          1 0 -1.22461e-16,
+                          0.970942 0 0.239316,
+                          0.970942 0 0.239316,
+                          0.885456 0 0.464723,
+                          0.970942 0 0.239316,
+                          1 0 -1.22461e-16,
+                          0.970942 0 0.239316,
+                          0.885456 0 0.464723,
+                          0.885456 0 0.464723,
+                          0.748511 0 0.663123,
+                          0.885456 0 0.464723,
+                          0.970942 0 0.239316,
+                          0.885456 0 0.464723,
+                          0.748511 0 0.663123,
+                          0.748511 0 0.663123,
+                          0.568065 0 0.822984,
+                          0.748511 0 0.663123,
+                          0.885456 0 0.464723,
+                          0.748511 0 0.663123,
+                          0.568065 0 0.822984,
+                          0.568065 0 0.822984,
+                          0.354605 0 0.935016,
+                          0.568065 0 0.822984,
+                          0.748511 0 0.663123,
+                          0.568065 0 0.822984,
+                          0.354605 0 0.935016,
+                          0.354605 0 0.935016,
+                          0.120537 0 0.992709,
+                          0.354605 0 0.935016,
+                          0.568065 0 0.822984,
+                          0.354605 0 0.935016,
+                          0.120537 0 0.992709,
+                          0.120537 0 0.992709,
+                          -0.120537 0 0.992709,
+                          0.120537 0 0.992709,
+                          0.354605 0 0.935016,
+                          0.120537 0 0.992709,
+                          -0.120537 0 0.992709,
+                          -0.120537 0 0.992709,
+                          -0.354605 0 0.935016,
+                          -0.120537 0 0.992709,
+                          0.120537 0 0.992709,
+                          -0.120537 0 0.992709,
+                          -0.354605 0 0.935016,
+                          -0.354605 0 0.935016,
+                          -0.568065 0 0.822984,
+                          -0.354605 0 0.935016,
+                          -0.120537 0 0.992709,
+                          -0.354605 0 0.935016,
+                          -0.568065 0 0.822984,
+                          -0.568065 0 0.822984,
+                          -0.748511 0 0.663123,
+                          -0.568065 0 0.822984,
+                          -0.354605 0 0.935016,
+                          -0.568065 0 0.822984,
+                          -0.748511 0 0.663123,
+                          -0.748511 0 0.663123,
+                          -0.885456 0 0.464723,
+                          -0.748511 0 0.663123,
+                          -0.568065 0 0.822984,
+                          -0.748511 0 0.663123,
+                          -0.885456 0 0.464723,
+                          -0.885456 0 0.464723,
+                          -0.970942 0 0.239316,
+                          -0.885456 0 0.464723,
+                          -0.748511 0 0.663123,
+                          -0.885456 0 0.464723,
+                          -0.970942 0 0.239316,
+                          -0.885456 0 0.464723,
+                          -0.970942 0 0.239316,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -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 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 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -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 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 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          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,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          1 0 2.44921e-16,
+                          1 0 2.44921e-16,
+                          0.939693 0 0.34202,
+                          0.939693 0 -0.34202,
+                          0.939693 0 -0.34202,
+                          1 0 1.22461e-16,
+                          0.939693 0 -0.34202,
+                          1 0 1.22461e-16,
+                          1 0 1.22461e-16,
+                          0.939693 0 0.34202,
+                          0.939693 0 0.34202,
+                          0.766044 0 0.642788,
+                          0.939693 0 0.34202,
+                          1 0 2.44921e-16,
+                          0.939693 0 0.34202,
+                          0.766044 0 0.642788,
+                          0.766044 0 0.642788,
+                          0.5 0 0.866025,
+                          0.939693 0 0.34202,
+                          0.766044 0 0.642788,
+                          0.766044 0 0.642788,
+                          0.5 0 0.866025,
+                          0.5 0 0.866025,
+                          0.173648 0 0.984808,
+                          0.766044 0 0.642788,
+                          0.5 0 0.866025,
+                          0.5 0 0.866025,
+                          0.173648 0 0.984808,
+                          0.173648 0 0.984808,
+                          -0.173648 0 0.984808,
+                          0.5 0 0.866025,
+                          0.173648 0 0.984808,
+                          0.173648 0 0.984808,
+                          -0.173648 0 0.984808,
+                          -0.173648 0 0.984808,
+                          -0.5 0 0.866025,
+                          0.173648 0 0.984808,
+                          -0.173648 0 0.984808,
+                          -0.173648 0 0.984808,
+                          -0.5 0 0.866025,
+                          -0.5 0 0.866025,
+                          -0.766044 0 0.642788,
+                          -0.173648 0 0.984808,
+                          -0.5 0 0.866025,
+                          -0.5 0 0.866025,
+                          -0.766044 0 0.642788,
+                          -0.766044 0 0.642788,
+                          -0.939693 0 0.34202,
+                          -0.5 0 0.866025,
+                          -0.766044 0 0.642788,
+                          -0.766044 0 0.642788,
+                          -0.939693 0 0.34202,
+                          -0.939693 0 0.34202,
+                          -1 0 -1.22461e-16,
+                          -0.766044 0 0.642788,
+                          -0.939693 0 0.34202,
+                          -0.939693 0 0.34202,
+                          -1 0 -1.22461e-16,
+                          -1 0 -1.22461e-16,
+                          -0.939693 0 -0.34202,
+                          -0.939693 0 0.34202,
+                          -1 0 -1.22461e-16,
+                          -1 0 -1.22461e-16,
+                          -0.939693 0 -0.34202,
+                          -0.939693 0 -0.34202,
+                          -0.766044 0 -0.642788,
+                          -1 0 -1.22461e-16,
+                          -0.939693 0 -0.34202,
+                          -0.939693 0 -0.34202,
+                          -0.766044 0 -0.642788,
+                          -0.766044 0 -0.642788,
+                          -0.5 0 -0.866025,
+                          -0.939693 0 -0.34202,
+                          -0.766044 0 -0.642788,
+                          -0.766044 0 -0.642788,
+                          -0.5 0 -0.866025,
+                          -0.5 0 -0.866025,
+                          -0.173648 0 -0.984808,
+                          -0.766044 0 -0.642788,
+                          -0.5 0 -0.866025,
+                          -0.5 0 -0.866025,
+                          -0.173648 0 -0.984808,
+                          -0.173648 0 -0.984808,
+                          0.173648 0 -0.984808,
+                          -0.5 0 -0.866025,
+                          -0.173648 0 -0.984808,
+                          -0.173648 0 -0.984808,
+                          0.173648 0 -0.984808,
+                          0.173648 0 -0.984808,
+                          0.5 0 -0.866025,
+                          -0.173648 0 -0.984808,
+                          0.173648 0 -0.984808,
+                          0.173648 0 -0.984808,
+                          0.5 0 -0.866025,
+                          0.5 0 -0.866025,
+                          0.766044 0 -0.642788,
+                          0.173648 0 -0.984808,
+                          0.5 0 -0.866025,
+                          0.5 0 -0.866025,
+                          0.766044 0 -0.642788,
+                          0.766044 0 -0.642788,
+                          0.939693 0 -0.34202,
+                          0.5 0 -0.866025,
+                          0.766044 0 -0.642788,
+                          0.766044 0 -0.642788,
+                          0.766044 0 -0.642788,
+                          0.939693 0 -0.34202,
+                          0.939693 0 -0.34202,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          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 -1.83691e-16 1.22461e-16,
+                          1 -1.83691e-16 1.22461e-16,
+                          0.951057 -1.747e-16 -0.309017,
+                          0.951057 -1.747e-16 0.309017,
+                          0.951057 -1.747e-16 0.309017,
+                          1 -1.83691e-16 1.22461e-16,
+                          1 -1.83691e-16 1.22461e-16,
+                          0.951057 -1.747e-16 0.309017,
+                          1 -1.83691e-16 1.22461e-16,
+                          0.951057 -1.747e-16 -0.309017,
+                          0.951057 -1.747e-16 -0.309017,
+                          0.809017 -1.48609e-16 -0.587785,
+                          0.951057 -1.747e-16 -0.309017,
+                          1 -1.83691e-16 1.22461e-16,
+                          0.951057 -1.747e-16 -0.309017,
+                          0.809017 -1.48609e-16 -0.587785,
+                          0.809017 -1.48609e-16 -0.587785,
+                          0.587785 -1.07971e-16 -0.809017,
+                          0.951057 -1.747e-16 -0.309017,
+                          0.809017 -1.48609e-16 -0.587785,
+                          0.809017 -1.48609e-16 -0.587785,
+                          0.587785 -1.07971e-16 -0.809017,
+                          0.587785 -1.07971e-16 -0.809017,
+                          0.309017 -5.67636e-17 -0.951057,
+                          0.809017 -1.48609e-16 -0.587785,
+                          0.587785 -1.07971e-16 -0.809017,
+                          0.587785 -1.07971e-16 -0.809017,
+                          0.309017 -5.67636e-17 -0.951057,
+                          0.309017 -5.67636e-17 -0.951057,
+                          1.07187e-15 0 -1,
+                          0.587785 -1.07971e-16 -0.809017,
+                          0.309017 -5.67636e-17 -0.951057,
+                          0.309017 -5.67636e-17 -0.951057,
+                          1.83691e-16 0 -1,
+                          1.07187e-15 0 -1,
+                          -0.309017 5.67636e-17 -0.951057,
+                          0.309017 -5.67636e-17 -0.951057,
+                          1.07187e-15 0 -1,
+                          1.83691e-16 0 -1,
+                          -0.309017 5.67636e-17 -0.951057,
+                          -0.309017 5.67636e-17 -0.951057,
+                          -0.587785 1.07971e-16 -0.809017,
+                          1.83691e-16 0 -1,
+                          -0.309017 5.67636e-17 -0.951057,
+                          -0.309017 5.67636e-17 -0.951057,
+                          -0.587785 1.07971e-16 -0.809017,
+                          -0.587785 1.07971e-16 -0.809017,
+                          -0.809017 1.48609e-16 -0.587785,
+                          -0.309017 5.67636e-17 -0.951057,
+                          -0.587785 1.07971e-16 -0.809017,
+                          -0.587785 1.07971e-16 -0.809017,
+                          -0.809017 1.48609e-16 -0.587785,
+                          -0.809017 1.48609e-16 -0.587785,
+                          -0.951057 1.747e-16 -0.309017,
+                          -0.587785 1.07971e-16 -0.809017,
+                          -0.809017 1.48609e-16 -0.587785,
+                          -0.809017 1.48609e-16 -0.587785,
+                          -0.951057 1.747e-16 -0.309017,
+                          -0.951057 1.747e-16 -0.309017,
+                          -1 1.83691e-16 -2.44921e-16,
+                          -0.809017 1.48609e-16 -0.587785,
+                          -0.951057 1.747e-16 -0.309017,
+                          -0.951057 1.747e-16 -0.309017,
+                          -1 1.83691e-16 0,
+                          -1 1.83691e-16 0,
+                          -0.951057 1.747e-16 0.309017,
+                          -0.951057 1.747e-16 -0.309017,
+                          -1 1.83691e-16 -2.44921e-16,
+                          -1 1.83691e-16 -2.44921e-16,
+                          -0.951057 1.747e-16 0.309017,
+                          -0.951057 1.747e-16 0.309017,
+                          -0.809017 1.48609e-16 0.587785,
+                          -0.951057 1.747e-16 0.309017,
+                          -1 1.83691e-16 0,
+                          -0.951057 1.747e-16 0.309017,
+                          -0.809017 1.48609e-16 0.587785,
+                          -0.809017 1.48609e-16 0.587785,
+                          -0.587785 1.07971e-16 0.809017,
+                          -0.809017 1.48609e-16 0.587785,
+                          -0.951057 1.747e-16 0.309017,
+                          -0.809017 1.48609e-16 0.587785,
+                          -0.587785 1.07971e-16 0.809017,
+                          -0.587785 1.07971e-16 0.809017,
+                          -0.309017 5.67636e-17 0.951057,
+                          -0.587785 1.07971e-16 0.809017,
+                          -0.809017 1.48609e-16 0.587785,
+                          -0.587785 1.07971e-16 0.809017,
+                          -0.309017 5.67636e-17 0.951057,
+                          -0.309017 5.67636e-17 0.951057,
+                          -6.12303e-17 0 1,
+                          -0.309017 5.67636e-17 0.951057,
+                          -0.587785 1.07971e-16 0.809017,
+                          -0.309017 5.67636e-17 0.951057,
+                          -6.12303e-17 0 1,
+                          -6.12303e-17 0 1,
+                          0.309017 -5.67636e-17 0.951057,
+                          -6.12303e-17 0 1,
+                          -0.309017 5.67636e-17 0.951057,
+                          -6.12303e-17 0 1,
+                          0.309017 -5.67636e-17 0.951057,
+                          0.309017 -5.67636e-17 0.951057,
+                          0.587785 -1.07971e-16 0.809017,
+                          0.309017 -5.67636e-17 0.951057,
+                          -6.12303e-17 0 1,
+                          0.309017 -5.67636e-17 0.951057,
+                          0.587785 -1.07971e-16 0.809017,
+                          0.587785 -1.07971e-16 0.809017,
+                          0.809017 -1.48609e-16 0.587785,
+                          0.587785 -1.07971e-16 0.809017,
+                          0.309017 -5.67636e-17 0.951057,
+                          0.587785 -1.07971e-16 0.809017,
+                          0.809017 -1.48609e-16 0.587785,
+                          0.809017 -1.48609e-16 0.587785,
+                          0.951057 -1.747e-16 0.309017,
+                          0.809017 -1.48609e-16 0.587785,
+                          0.587785 -1.07971e-16 0.809017,
+                          0.809017 -1.48609e-16 0.587785,
+                          0.951057 -1.747e-16 0.309017,
+                          0.809017 -1.48609e-16 0.587785,
+                          0.951057 -1.747e-16 0.309017,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 32.526 115 -8.01798,
+                          41.4339 115 -9.45776,
+                          42.5 115 -5.20458e-15,
+                          42.5 152 -5.20458e-15,
+                          42.5 115 -5.20458e-15,
+                          41.4339 115 -9.45776,
+                          33.5 115 -4.10243e-15,
+                          42.5 115 -5.20458e-15,
+                          41.4339 115 9.45776,
+                          41.5617 152 8.8804,
+                          41.4339 115 9.45776,
+                          42.5 115 -5.20458e-15,
+                          32.526 115 -8.01798,
+                          42.5 115 -5.20458e-15,
+                          33.5 115 -4.10243e-15,
+                          41.5617 152 8.8804,
+                          42.5 115 -5.20458e-15,
+                          42.5 152 -5.20458e-15,
+                          29.6634 115 -15.5666,
+                          38.2919 115 -18.4384,
+                          41.4339 115 -9.45776,
+                          38.7901 152 -17.3656,
+                          41.4339 115 -9.45776,
+                          38.2919 115 -18.4384,
+                          32.526 115 -8.01798,
+                          29.6634 115 -15.5666,
+                          41.4339 115 -9.45776,
+                          41.5617 152 -8.8804,
+                          42.5 152 -5.20458e-15,
+                          41.4339 115 -9.45776,
+                          38.7901 152 -17.3656,
+                          41.5617 152 -8.8804,
+                          41.4339 115 -9.45776,
+                          25.0739 115 -22.2158,
+                          33.2265 115 -26.4996,
+                          38.2919 115 -18.4384,
+                          34.3057 152 -25.0873,
+                          38.2919 115 -18.4384,
+                          33.2265 115 -26.4996,
+                          29.6634 115 -15.5666,
+                          25.0739 115 -22.2158,
+                          38.2919 115 -18.4384,
+                          34.3057 152 -25.0873,
+                          38.7901 152 -17.3656,
+                          38.2919 115 -18.4384,
+                          11.8803 115 -31.3226,
+                          26.4996 115 -33.2265,
+                          33.2265 115 -26.4996,
+                          28.3067 152 -31.7011,
+                          33.2265 115 -26.4996,
+                          26.4996 115 -33.2265,
+                          19.0302 115 -27.5694,
+                          11.8803 115 -31.3226,
+                          33.2265 115 -26.4996,
+                          25.0739 115 -22.2158,
+                          19.0302 115 -27.5694,
+                          33.2265 115 -26.4996,
+                          28.3067 152 -31.7011,
+                          34.3057 152 -25.0873,
+                          33.2265 115 -26.4996,
+                          -18.4384 115 -38.2919,
+                          18.4384 115 -38.2919,
+                          26.4996 115 -33.2265,
+                          21.0613 152 -36.9141,
+                          26.4996 115 -33.2265,
+                          18.4384 115 -38.2919,
+                          4.03642 115 -33.2556,
+                          -18.4384 115 -38.2919,
+                          26.4996 115 -33.2265,
+                          11.8803 115 -31.3226,
+                          4.03642 115 -33.2556,
+                          26.4996 115 -33.2265,
+                          21.0613 152 -36.9141,
+                          28.3067 152 -31.7011,
+                          26.4996 115 -33.2265,
+                          -9.45776 115 -41.4339,
+                          9.45776 115 -41.4339,
+                          18.4384 115 -38.2919,
+                          12.8841 152 -40.5,
+                          18.4384 115 -38.2919,
+                          9.45776 115 -41.4339,
+                          -18.4384 115 -38.2919,
+                          -9.45776 115 -41.4339,
+                          18.4384 115 -38.2919,
+                          12.8841 152 -40.5,
+                          21.0613 152 -36.9141,
+                          18.4384 115 -38.2919,
+                          -9.45776 115 -41.4339,
+                          -3.951e-15 115 -42.5,
+                          9.45776 115 -41.4339,
+                          4.35422 152 -42.2762,
+                          9.45776 115 -41.4339,
+                          -3.951e-15 115 -42.5,
+                          4.35422 152 -42.2762,
+                          12.8841 152 -40.5,
+                          9.45776 115 -41.4339,
+                          -4.35422 152 -42.2762,
+                          -3.951e-15 115 -42.5,
+                          -9.45776 115 -41.4339,
+                          -4.35422 152 -42.2762,
+                          4.35422 152 -42.2762,
+                          -3.951e-15 115 -42.5,
+                          -12.8841 152 -40.5,
+                          -9.45776 115 -41.4339,
+                          -18.4384 115 -38.2919,
+                          -12.8841 152 -40.5,
+                          -4.35422 152 -42.2762,
+                          -9.45776 115 -41.4339,
+                          -4.03642 115 -33.2556,
+                          -26.4996 115 -33.2265,
+                          -18.4384 115 -38.2919,
+                          -21.0613 152 -36.9141,
+                          -18.4384 115 -38.2919,
+                          -26.4996 115 -33.2265,
+                          4.03642 115 -33.2556,
+                          -4.03642 115 -33.2556,
+                          -18.4384 115 -38.2919,
+                          -21.0613 152 -36.9141,
+                          -12.8841 152 -40.5,
+                          -18.4384 115 -38.2919,
+                          -19.0302 115 -27.5694,
+                          -33.2265 115 -26.4996,
+                          -26.4996 115 -33.2265,
+                          -28.3067 152 -31.7011,
+                          -26.4996 115 -33.2265,
+                          -33.2265 115 -26.4996,
+                          -11.8803 115 -31.3226,
+                          -19.0302 115 -27.5694,
+                          -26.4996 115 -33.2265,
+                          -4.03642 115 -33.2556,
+                          -11.8803 115 -31.3226,
+                          -26.4996 115 -33.2265,
+                          -28.3067 152 -31.7011,
+                          -21.0613 152 -36.9141,
+                          -26.4996 115 -33.2265,
+                          -25.0739 115 -22.2158,
+                          -38.2919 115 -18.4384,
+                          -33.2265 115 -26.4996,
+                          -34.3057 152 -25.0873,
+                          -33.2265 115 -26.4996,
+                          -38.2919 115 -18.4384,
+                          -19.0302 115 -27.5694,
+                          -25.0739 115 -22.2158,
+                          -33.2265 115 -26.4996,
+                          -34.3057 152 -25.0873,
+                          -28.3067 152 -31.7011,
+                          -33.2265 115 -26.4996,
+                          -29.6634 115 -15.5666,
+                          -41.4339 115 -9.45776,
+                          -38.2919 115 -18.4384,
+                          -38.7901 152 -17.3656,
+                          -38.2919 115 -18.4384,
+                          -41.4339 115 -9.45776,
+                          -25.0739 115 -22.2158,
+                          -29.6634 115 -15.5666,
+                          -38.2919 115 -18.4384,
+                          -38.7901 152 -17.3656,
+                          -34.3057 152 -25.0873,
+                          -38.2919 115 -18.4384,
+                          -33.5 115 4.10243e-15,
+                          -42.5 115 5.20458e-15,
+                          -41.4339 115 -9.45776,
+                          -41.5617 152 -8.8804,
+                          -41.4339 115 -9.45776,
+                          -42.5 115 5.20458e-15,
+                          -32.526 115 -8.01798,
+                          -33.5 115 4.10243e-15,
+                          -41.4339 115 -9.45776,
+                          -29.6634 115 -15.5666,
+                          -32.526 115 -8.01798,
+                          -41.4339 115 -9.45776,
+                          -41.5617 152 -8.8804,
+                          -38.7901 152 -17.3656,
+                          -41.4339 115 -9.45776,
+                          -32.526 115 8.01798,
+                          -41.4339 115 9.45776,
+                          -42.5 115 5.20458e-15,
+                          -42.5 152 5.20458e-15,
+                          -42.5 115 5.20458e-15,
+                          -41.4339 115 9.45776,
+                          -33.5 115 4.10243e-15,
+                          -32.526 115 8.01798,
+                          -42.5 115 5.20458e-15,
+                          -41.5617 152 -8.8804,
+                          -42.5 115 5.20458e-15,
+                          -42.5 152 5.20458e-15,
+                          -29.6634 115 15.5666,
+                          -38.2919 115 18.4384,
+                          -41.4339 115 9.45776,
+                          -38.7901 152 17.3656,
+                          -41.4339 115 9.45776,
+                          -38.2919 115 18.4384,
+                          -32.526 115 8.01798,
+                          -29.6634 115 15.5666,
+                          -41.4339 115 9.45776,
+                          -41.5617 152 8.8804,
+                          -42.5 152 5.20458e-15,
+                          -41.4339 115 9.45776,
+                          -38.7901 152 17.3656,
+                          -41.5617 152 8.8804,
+                          -41.4339 115 9.45776,
+                          -25.0739 115 22.2158,
+                          -33.2265 115 26.4996,
+                          -38.2919 115 18.4384,
+                          -34.3057 152 25.0873,
+                          -38.2919 115 18.4384,
+                          -33.2265 115 26.4996,
+                          -29.6634 115 15.5666,
+                          -25.0739 115 22.2158,
+                          -38.2919 115 18.4384,
+                          -34.3057 152 25.0873,
+                          -38.7901 152 17.3656,
+                          -38.2919 115 18.4384,
+                          -11.8803 115 31.3226,
+                          -26.4996 115 33.2265,
+                          -33.2265 115 26.4996,
+                          -28.3067 152 31.7011,
+                          -33.2265 115 26.4996,
+                          -26.4996 115 33.2265,
+                          -19.0302 115 27.5694,
+                          -11.8803 115 31.3226,
+                          -33.2265 115 26.4996,
+                          -25.0739 115 22.2158,
+                          -19.0302 115 27.5694,
+                          -33.2265 115 26.4996,
+                          -28.3067 152 31.7011,
+                          -34.3057 152 25.0873,
+                          -33.2265 115 26.4996,
+                          18.4384 115 38.2919,
+                          -18.4384 115 38.2919,
+                          -26.4996 115 33.2265,
+                          -21.0613 152 36.9141,
+                          -26.4996 115 33.2265,
+                          -18.4384 115 38.2919,
+                          -4.03642 115 33.2556,
+                          18.4384 115 38.2919,
+                          -26.4996 115 33.2265,
+                          -11.8803 115 31.3226,
+                          -4.03642 115 33.2556,
+                          -26.4996 115 33.2265,
+                          -21.0613 152 36.9141,
+                          -28.3067 152 31.7011,
+                          -26.4996 115 33.2265,
+                          9.45776 115 41.4339,
+                          -9.45776 115 41.4339,
+                          -18.4384 115 38.2919,
+                          -12.8841 152 40.5,
+                          -18.4384 115 38.2919,
+                          -9.45776 115 41.4339,
+                          18.4384 115 38.2919,
+                          9.45776 115 41.4339,
+                          -18.4384 115 38.2919,
+                          -12.8841 152 40.5,
+                          -21.0613 152 36.9141,
+                          -18.4384 115 38.2919,
+                          9.45776 115 41.4339,
+                          6.45815e-15 115 42.5,
+                          -9.45776 115 41.4339,
+                          -4.35422 152 42.2762,
+                          -9.45776 115 41.4339,
+                          6.45815e-15 115 42.5,
+                          -4.35422 152 42.2762,
+                          -12.8841 152 40.5,
+                          -9.45776 115 41.4339,
+                          4.35422 152 42.2762,
+                          6.45815e-15 115 42.5,
+                          9.45776 115 41.4339,
+                          4.35422 152 42.2762,
+                          -4.35422 152 42.2762,
+                          6.45815e-15 115 42.5,
+                          12.8841 152 40.5,
+                          9.45776 115 41.4339,
+                          18.4384 115 38.2919,
+                          12.8841 152 40.5,
+                          4.35422 152 42.2762,
+                          9.45776 115 41.4339,
+                          4.03642 115 33.2556,
+                          26.4996 115 33.2265,
+                          18.4384 115 38.2919,
+                          21.0613 152 36.9141,
+                          18.4384 115 38.2919,
+                          26.4996 115 33.2265,
+                          -4.03642 115 33.2556,
+                          4.03642 115 33.2556,
+                          18.4384 115 38.2919,
+                          21.0613 152 36.9141,
+                          12.8841 152 40.5,
+                          18.4384 115 38.2919,
+                          19.0302 115 27.5694,
+                          33.2265 115 26.4996,
+                          26.4996 115 33.2265,
+                          28.3067 152 31.7011,
+                          26.4996 115 33.2265,
+                          33.2265 115 26.4996,
+                          11.8803 115 31.3226,
+                          19.0302 115 27.5694,
+                          26.4996 115 33.2265,
+                          4.03642 115 33.2556,
+                          11.8803 115 31.3226,
+                          26.4996 115 33.2265,
+                          28.3067 152 31.7011,
+                          21.0613 152 36.9141,
+                          26.4996 115 33.2265,
+                          25.0739 115 22.2158,
+                          38.2919 115 18.4384,
+                          33.2265 115 26.4996,
+                          34.3057 152 25.0873,
+                          33.2265 115 26.4996,
+                          38.2919 115 18.4384,
+                          19.0302 115 27.5694,
+                          25.0739 115 22.2158,
+                          33.2265 115 26.4996,
+                          34.3057 152 25.0873,
+                          28.3067 152 31.7011,
+                          33.2265 115 26.4996,
+                          29.6634 115 15.5666,
+                          41.4339 115 9.45776,
+                          38.2919 115 18.4384,
+                          38.7901 152 17.3656,
+                          38.2919 115 18.4384,
+                          41.4339 115 9.45776,
+                          25.0739 115 22.2158,
+                          29.6634 115 15.5666,
+                          38.2919 115 18.4384,
+                          38.7901 152 17.3656,
+                          34.3057 152 25.0873,
+                          38.2919 115 18.4384,
+                          32.526 115 8.01798,
+                          33.5 115 -4.10243e-15,
+                          41.4339 115 9.45776,
+                          29.6634 115 15.5666,
+                          32.526 115 8.01798,
+                          41.4339 115 9.45776,
+                          41.5617 152 8.8804,
+                          38.7901 152 17.3656,
+                          41.4339 115 9.45776,
+                          33.5 152 -4.10243e-15,
+                          33.5 115 -4.10243e-15,
+                          32.526 115 8.01798,
+                          32.526 152 -8.01831,
+                          32.526 115 -8.01798,
+                          33.5 115 -4.10243e-15,
+                          33.5 152 -4.10243e-15,
+                          32.526 152 -8.01831,
+                          33.5 115 -4.10243e-15,
+                          32.526 152 8.01831,
+                          32.526 115 8.01798,
+                          29.6634 115 15.5666,
+                          32.526 152 8.01831,
+                          33.5 152 -4.10243e-15,
+                          32.526 115 8.01798,
+                          29.6629 152 15.5673,
+                          29.6634 115 15.5666,
+                          25.0739 115 22.2158,
+                          29.6629 152 15.5673,
+                          32.526 152 8.01831,
+                          29.6634 115 15.5666,
+                          25.0757 152 22.2139,
+                          25.0739 115 22.2158,
+                          19.0302 115 27.5694,
+                          25.0757 152 22.2139,
+                          29.6629 152 15.5673,
+                          25.0739 115 22.2158,
+                          19.0288 152 27.5707,
+                          19.0302 115 27.5694,
+                          11.8803 115 31.3226,
+                          19.0288 152 27.5707,
+                          25.0757 152 22.2139,
+                          19.0302 115 27.5694,
+                          11.8794 152 31.3226,
+                          11.8803 115 31.3226,
+                          4.03642 115 33.2556,
+                          11.8794 152 31.3226,
+                          19.0288 152 27.5707,
+                          11.8803 115 31.3226,
+                          4.03942 152 33.2555,
+                          4.03642 115 33.2556,
+                          -4.03642 115 33.2556,
+                          4.03942 152 33.2555,
+                          11.8794 152 31.3226,
+                          4.03642 115 33.2556,
+                          -4.03942 152 33.2555,
+                          -4.03642 115 33.2556,
+                          -11.8803 115 31.3226,
+                          -4.03942 152 33.2555,
+                          4.03942 152 33.2555,
+                          -4.03642 115 33.2556,
+                          -11.8794 152 31.3226,
+                          -11.8803 115 31.3226,
+                          -19.0302 115 27.5694,
+                          -11.8794 152 31.3226,
+                          -4.03942 152 33.2555,
+                          -11.8803 115 31.3226,
+                          -19.0288 152 27.5707,
+                          -19.0302 115 27.5694,
+                          -25.0739 115 22.2158,
+                          -19.0288 152 27.5707,
+                          -11.8794 152 31.3226,
+                          -19.0302 115 27.5694,
+                          -25.0757 152 22.2139,
+                          -25.0739 115 22.2158,
+                          -29.6634 115 15.5666,
+                          -25.0757 152 22.2139,
+                          -19.0288 152 27.5707,
+                          -25.0739 115 22.2158,
+                          -29.6629 152 15.5673,
+                          -29.6634 115 15.5666,
+                          -32.526 115 8.01798,
+                          -29.6629 152 15.5673,
+                          -25.0757 152 22.2139,
+                          -29.6634 115 15.5666,
+                          -32.526 152 8.01831,
+                          -32.526 115 8.01798,
+                          -33.5 115 4.10243e-15,
+                          -32.526 152 8.01831,
+                          -29.6629 152 15.5673,
+                          -32.526 115 8.01798,
+                          -33.5 152 4.10243e-15,
+                          -33.5 115 4.10243e-15,
+                          -32.526 115 -8.01798,
+                          -32.526 152 8.01831,
+                          -33.5 115 4.10243e-15,
+                          -33.5 152 4.10243e-15,
+                          -32.526 152 -8.01831,
+                          -32.526 115 -8.01798,
+                          -29.6634 115 -15.5666,
+                          -32.526 152 -8.01831,
+                          -33.5 152 4.10243e-15,
+                          -32.526 115 -8.01798,
+                          -29.6629 152 -15.5673,
+                          -29.6634 115 -15.5666,
+                          -25.0739 115 -22.2158,
+                          -29.6629 152 -15.5673,
+                          -32.526 152 -8.01831,
+                          -29.6634 115 -15.5666,
+                          -25.0757 152 -22.2139,
+                          -25.0739 115 -22.2158,
+                          -19.0302 115 -27.5694,
+                          -25.0757 152 -22.2139,
+                          -29.6629 152 -15.5673,
+                          -25.0739 115 -22.2158,
+                          -19.0288 152 -27.5707,
+                          -19.0302 115 -27.5694,
+                          -11.8803 115 -31.3226,
+                          -19.0288 152 -27.5707,
+                          -25.0757 152 -22.2139,
+                          -19.0302 115 -27.5694,
+                          -11.8794 152 -31.3226,
+                          -11.8803 115 -31.3226,
+                          -4.03642 115 -33.2556,
+                          -11.8794 152 -31.3226,
+                          -19.0288 152 -27.5707,
+                          -11.8803 115 -31.3226,
+                          -4.03942 152 -33.2555,
+                          -4.03642 115 -33.2556,
+                          4.03642 115 -33.2556,
+                          -4.03942 152 -33.2555,
+                          -11.8794 152 -31.3226,
+                          -4.03642 115 -33.2556,
+                          4.03942 152 -33.2555,
+                          4.03642 115 -33.2556,
+                          11.8803 115 -31.3226,
+                          4.03942 152 -33.2555,
+                          -4.03942 152 -33.2555,
+                          4.03642 115 -33.2556,
+                          11.8794 152 -31.3226,
+                          11.8803 115 -31.3226,
+                          19.0302 115 -27.5694,
+                          11.8794 152 -31.3226,
+                          4.03942 152 -33.2555,
+                          11.8803 115 -31.3226,
+                          19.0288 152 -27.5707,
+                          19.0302 115 -27.5694,
+                          25.0739 115 -22.2158,
+                          19.0288 152 -27.5707,
+                          11.8794 152 -31.3226,
+                          19.0302 115 -27.5694,
+                          25.0757 152 -22.2139,
+                          25.0739 115 -22.2158,
+                          29.6634 115 -15.5666,
+                          25.0757 152 -22.2139,
+                          19.0288 152 -27.5707,
+                          25.0739 115 -22.2158,
+                          29.6629 152 -15.5673,
+                          29.6634 115 -15.5666,
+                          32.526 115 -8.01798,
+                          29.6629 152 -15.5673,
+                          25.0757 152 -22.2139,
+                          29.6634 115 -15.5666,
+                          32.526 152 -8.01831,
+                          29.6629 152 -15.5673,
+                          32.526 115 -8.01798,
+                          45.5 152 40.5,
+                          41.5617 152 8.8804,
+                          42.5 152 -5.20458e-15,
+                          45.5 152 -40.5,
+                          42.5 152 -5.20458e-15,
+                          41.5617 152 -8.8804,
+                          45.5 152 -40.5,
+                          45.5 152 40.5,
+                          42.5 152 -5.20458e-15,
+                          -45.5 152 40.5,
+                          -42.5 152 5.20458e-15,
+                          -41.5617 152 8.8804,
+                          -45.5 152 -40.5,
+                          -41.5617 152 -8.8804,
+                          -42.5 152 5.20458e-15,
+                          -45.5 152 40.5,
+                          -45.5 152 -40.5,
+                          -42.5 152 5.20458e-15,
+                          -45.5 152 40.5,
+                          -41.5617 152 8.8804,
+                          -38.7901 152 17.3656,
+                          -45.5 152 40.5,
+                          -38.7901 152 17.3656,
+                          -34.3057 152 25.0873,
+                          -45.5 152 40.5,
+                          -34.3057 152 25.0873,
+                          -28.3067 152 31.7011,
+                          -45.5 152 40.5,
+                          -28.3067 152 31.7011,
+                          -21.0613 152 36.9141,
+                          -45.5 152 40.5,
+                          -21.0613 152 36.9141,
+                          -12.8841 152 40.5,
+                          12.8841 152 40.5,
+                          -12.8841 152 40.5,
+                          -4.35422 152 42.2762,
+                          -45.5 157 40.5,
+                          -12.8841 152 40.5,
+                          12.8841 152 40.5,
+                          -45.5 157 40.5,
+                          -45.5 152 40.5,
+                          -12.8841 152 40.5,
+                          12.8841 152 40.5,
+                          -4.35422 152 42.2762,
+                          4.35422 152 42.2762,
+                          45.5 152 40.5,
+                          12.8841 152 40.5,
+                          21.0613 152 36.9141,
+                          -45.5 157 40.5,
+                          12.8841 152 40.5,
+                          45.5 152 40.5,
+                          45.5 152 40.5,
+                          21.0613 152 36.9141,
+                          28.3067 152 31.7011,
+                          45.5 152 40.5,
+                          28.3067 152 31.7011,
+                          34.3057 152 25.0873,
+                          45.5 152 40.5,
+                          34.3057 152 25.0873,
+                          38.7901 152 17.3656,
+                          45.5 152 40.5,
+                          38.7901 152 17.3656,
+                          41.5617 152 8.8804,
+                          -32.526 152 8.01831,
+                          -33.5 152 4.10243e-15,
+                          -32.526 152 -8.01831,
+                          -32.526 152 8.01831,
+                          -32.526 152 -8.01831,
+                          -29.6629 152 -15.5673,
+                          -29.6629 152 15.5673,
+                          -29.6629 152 -15.5673,
+                          -25.0757 152 -22.2139,
+                          -32.526 152 8.01831,
+                          -29.6629 152 -15.5673,
+                          -29.6629 152 15.5673,
+                          -25.0757 152 22.2139,
+                          -25.0757 152 -22.2139,
+                          -19.0288 152 -27.5707,
+                          -29.6629 152 15.5673,
+                          -25.0757 152 -22.2139,
+                          -25.0757 152 22.2139,
+                          -19.0288 152 27.5707,
+                          -19.0288 152 -27.5707,
+                          -11.8794 152 -31.3226,
+                          -25.0757 152 22.2139,
+                          -19.0288 152 -27.5707,
+                          -19.0288 152 27.5707,
+                          -11.4895 152 -9.64285,
+                          -11.8794 152 -31.3226,
+                          -4.03942 152 -33.2555,
+                          -15 152 -1.83691e-15,
+                          -19.0288 152 27.5707,
+                          -11.8794 152 -31.3226,
+                          -14.0949 152 -5.13142,
+                          -15 152 -1.83691e-15,
+                          -11.8794 152 -31.3226,
+                          -11.4895 152 -9.64285,
+                          -14.0949 152 -5.13142,
+                          -11.8794 152 -31.3226,
+                          -2.60423 152 -14.7718,
+                          -4.03942 152 -33.2555,
+                          4.03942 152 -33.2555,
+                          -7.49882 152 -12.9907,
+                          -11.4895 152 -9.64285,
+                          -4.03942 152 -33.2555,
+                          -2.60423 152 -14.7718,
+                          -7.49882 152 -12.9907,
+                          -4.03942 152 -33.2555,
+                          7.49882 152 -12.9907,
+                          4.03942 152 -33.2555,
+                          11.8794 152 -31.3226,
+                          2.60423 152 -14.7718,
+                          -2.60423 152 -14.7718,
+                          4.03942 152 -33.2555,
+                          7.49882 152 -12.9907,
+                          2.60423 152 -14.7718,
+                          4.03942 152 -33.2555,
+                          14.0949 152 -5.13142,
+                          11.8794 152 -31.3226,
+                          19.0288 152 -27.5707,
+                          11.4895 152 -9.64285,
+                          7.49882 152 -12.9907,
+                          11.8794 152 -31.3226,
+                          14.0949 152 -5.13142,
+                          11.4895 152 -9.64285,
+                          11.8794 152 -31.3226,
+                          19.0288 152 27.5707,
+                          19.0288 152 -27.5707,
+                          25.0757 152 -22.2139,
+                          11.8794 152 31.3226,
+                          19.0288 152 -27.5707,
+                          19.0288 152 27.5707,
+                          15 152 1.83691e-15,
+                          19.0288 152 -27.5707,
+                          11.8794 152 31.3226,
+                          15 152 1.83691e-15,
+                          14.0949 152 -5.13142,
+                          19.0288 152 -27.5707,
+                          25.0757 152 22.2139,
+                          25.0757 152 -22.2139,
+                          29.6629 152 -15.5673,
+                          19.0288 152 27.5707,
+                          25.0757 152 -22.2139,
+                          25.0757 152 22.2139,
+                          29.6629 152 15.5673,
+                          29.6629 152 -15.5673,
+                          32.526 152 -8.01831,
+                          25.0757 152 22.2139,
+                          29.6629 152 -15.5673,
+                          29.6629 152 15.5673,
+                          32.526 152 8.01831,
+                          32.526 152 -8.01831,
+                          33.5 152 -4.10243e-15,
+                          29.6629 152 15.5673,
+                          32.526 152 -8.01831,
+                          32.526 152 8.01831,
+                          45.5 152 -40.5,
+                          41.5617 152 -8.8804,
+                          38.7901 152 -17.3656,
+                          45.5 152 -40.5,
+                          38.7901 152 -17.3656,
+                          34.3057 152 -25.0873,
+                          45.5 152 -40.5,
+                          34.3057 152 -25.0873,
+                          28.3067 152 -31.7011,
+                          45.5 152 -40.5,
+                          28.3067 152 -31.7011,
+                          21.0613 152 -36.9141,
+                          45.5 152 -40.5,
+                          21.0613 152 -36.9141,
+                          12.8841 152 -40.5,
+                          -12.8841 152 -40.5,
+                          12.8841 152 -40.5,
+                          4.35422 152 -42.2762,
+                          45.5 157 -40.5,
+                          12.8841 152 -40.5,
+                          -12.8841 152 -40.5,
+                          45.5 157 -40.5,
+                          45.5 152 -40.5,
+                          12.8841 152 -40.5,
+                          -12.8841 152 -40.5,
+                          4.35422 152 -42.2762,
+                          -4.35422 152 -42.2762,
+                          -45.5 152 -40.5,
+                          -12.8841 152 -40.5,
+                          -21.0613 152 -36.9141,
+                          45.5 157 -40.5,
+                          -12.8841 152 -40.5,
+                          -45.5 152 -40.5,
+                          -45.5 152 -40.5,
+                          -21.0613 152 -36.9141,
+                          -28.3067 152 -31.7011,
+                          -45.5 152 -40.5,
+                          -28.3067 152 -31.7011,
+                          -34.3057 152 -25.0873,
+                          -45.5 152 -40.5,
+                          -34.3057 152 -25.0873,
+                          -38.7901 152 -17.3656,
+                          -45.5 152 -40.5,
+                          -38.7901 152 -17.3656,
+                          -41.5617 152 -8.8804,
+                          11.4895 152 9.64285,
+                          11.8794 152 31.3226,
+                          4.03942 152 33.2555,
+                          14.0949 152 5.13142,
+                          15 152 1.83691e-15,
+                          11.8794 152 31.3226,
+                          11.4895 152 9.64285,
+                          14.0949 152 5.13142,
+                          11.8794 152 31.3226,
+                          2.60423 152 14.7718,
+                          4.03942 152 33.2555,
+                          -4.03942 152 33.2555,
+                          7.49882 152 12.9907,
+                          11.4895 152 9.64285,
+                          4.03942 152 33.2555,
+                          2.60423 152 14.7718,
+                          7.49882 152 12.9907,
+                          4.03942 152 33.2555,
+                          -7.49882 152 12.9907,
+                          -4.03942 152 33.2555,
+                          -11.8794 152 31.3226,
+                          -2.60423 152 14.7718,
+                          2.60423 152 14.7718,
+                          -4.03942 152 33.2555,
+                          -7.49882 152 12.9907,
+                          -2.60423 152 14.7718,
+                          -4.03942 152 33.2555,
+                          -14.0949 152 5.13142,
+                          -11.8794 152 31.3226,
+                          -19.0288 152 27.5707,
+                          -11.4895 152 9.64285,
+                          -7.49882 152 12.9907,
+                          -11.8794 152 31.3226,
+                          -14.0949 152 5.13142,
+                          -11.4895 152 9.64285,
+                          -11.8794 152 31.3226,
+                          -14.0949 152 5.13142,
+                          -19.0288 152 27.5707,
+                          -15 152 -1.83691e-15,
+                          45.5 157 40.5,
+                          45.5 152 40.5,
+                          45.5 152 -40.5,
+                          -45.5 157 40.5,
+                          45.5 152 40.5,
+                          45.5 157 40.5,
+                          45.5 157 40.5,
+                          45.5 152 -40.5,
+                          45.5 157 -40.5,
+                          -45.5 157 -40.5,
+                          -45.5 152 -40.5,
+                          -45.5 152 40.5,
+                          -45.5 157 -40.5,
+                          45.5 157 -40.5,
+                          -45.5 152 -40.5,
+                          -45.5 157 -40.5,
+                          -45.5 152 40.5,
+                          -45.5 157 40.5,
+                          -15 178 -1.83691e-15,
+                          -15 152 -1.83691e-15,
+                          -14.0949 152 -5.13142,
+                          -14.0949 178 5.13142,
+                          -14.0949 152 5.13142,
+                          -15 152 -1.83691e-15,
+                          -14.0949 178 5.13142,
+                          -15 152 -1.83691e-15,
+                          -15 178 -1.83691e-15,
+                          -14.0949 178 -5.13142,
+                          -14.0949 152 -5.13142,
+                          -11.4895 152 -9.64285,
+                          -14.0949 178 -5.13142,
+                          -15 178 -1.83691e-15,
+                          -14.0949 152 -5.13142,
+                          -11.4895 178 -9.64285,
+                          -11.4895 152 -9.64285,
+                          -7.49882 152 -12.9907,
+                          -14.0949 178 -5.13142,
+                          -11.4895 152 -9.64285,
+                          -11.4895 178 -9.64285,
+                          -7.49882 178 -12.9907,
+                          -7.49882 152 -12.9907,
+                          -2.60423 152 -14.7718,
+                          -11.4895 178 -9.64285,
+                          -7.49882 152 -12.9907,
+                          -7.49882 178 -12.9907,
+                          -2.60423 178 -14.7718,
+                          -2.60423 152 -14.7718,
+                          2.60423 152 -14.7718,
+                          -7.49882 178 -12.9907,
+                          -2.60423 152 -14.7718,
+                          -2.60423 178 -14.7718,
+                          2.60423 178 -14.7718,
+                          2.60423 152 -14.7718,
+                          7.49882 152 -12.9907,
+                          -2.60423 178 -14.7718,
+                          2.60423 152 -14.7718,
+                          2.60423 178 -14.7718,
+                          7.49882 178 -12.9907,
+                          7.49882 152 -12.9907,
+                          11.4895 152 -9.64285,
+                          2.60423 178 -14.7718,
+                          7.49882 152 -12.9907,
+                          7.49882 178 -12.9907,
+                          11.4895 178 -9.64285,
+                          11.4895 152 -9.64285,
+                          14.0949 152 -5.13142,
+                          7.49882 178 -12.9907,
+                          11.4895 152 -9.64285,
+                          11.4895 178 -9.64285,
+                          14.0949 178 -5.13142,
+                          14.0949 152 -5.13142,
+                          15 152 1.83691e-15,
+                          11.4895 178 -9.64285,
+                          14.0949 152 -5.13142,
+                          14.0949 178 -5.13142,
+                          15 178 1.83691e-15,
+                          15 152 1.83691e-15,
+                          14.0949 152 5.13142,
+                          14.0949 178 -5.13142,
+                          15 152 1.83691e-15,
+                          15 178 1.83691e-15,
+                          14.0949 178 5.13142,
+                          14.0949 152 5.13142,
+                          11.4895 152 9.64285,
+                          15 178 1.83691e-15,
+                          14.0949 152 5.13142,
+                          14.0949 178 5.13142,
+                          11.4895 178 9.64285,
+                          11.4895 152 9.64285,
+                          7.49882 152 12.9907,
+                          14.0949 178 5.13142,
+                          11.4895 152 9.64285,
+                          11.4895 178 9.64285,
+                          7.49882 178 12.9907,
+                          7.49882 152 12.9907,
+                          2.60423 152 14.7718,
+                          11.4895 178 9.64285,
+                          7.49882 152 12.9907,
+                          7.49882 178 12.9907,
+                          2.60423 178 14.7718,
+                          2.60423 152 14.7718,
+                          -2.60423 152 14.7718,
+                          7.49882 178 12.9907,
+                          2.60423 152 14.7718,
+                          2.60423 178 14.7718,
+                          -2.60423 178 14.7718,
+                          -2.60423 152 14.7718,
+                          -7.49882 152 12.9907,
+                          2.60423 178 14.7718,
+                          -2.60423 152 14.7718,
+                          -2.60423 178 14.7718,
+                          -7.49882 178 12.9907,
+                          -7.49882 152 12.9907,
+                          -11.4895 152 9.64285,
+                          -2.60423 178 14.7718,
+                          -7.49882 152 12.9907,
+                          -7.49882 178 12.9907,
+                          -11.4895 178 9.64285,
+                          -11.4895 152 9.64285,
+                          -14.0949 152 5.13142,
+                          -7.49882 178 12.9907,
+                          -11.4895 152 9.64285,
+                          -11.4895 178 9.64285,
+                          -11.4895 178 9.64285,
+                          -14.0949 152 5.13142,
+                          -14.0949 178 5.13142,
+                          16.1794 157 -11.7568,
+                          45.5 157 40.5,
+                          45.5 157 -40.5,
+                          6.17955 157 -19.021,
+                          45.5 157 -40.5,
+                          -45.5 157 -40.5,
+                          11.7545 157 -16.1809,
+                          16.1794 157 -11.7568,
+                          45.5 157 -40.5,
+                          6.17955 157 -19.021,
+                          11.7545 157 -16.1809,
+                          45.5 157 -40.5,
+                          -6.17955 157 19.021,
+                          -45.5 157 40.5,
+                          45.5 157 40.5,
+                          19.0208 157 -6.18136,
+                          20 157 2.44921e-15,
+                          45.5 157 40.5,
+                          19.0208 157 6.18136,
+                          45.5 157 40.5,
+                          20 157 2.44921e-15,
+                          16.1794 157 -11.7568,
+                          19.0208 157 -6.18136,
+                          45.5 157 40.5,
+                          -3.44169e-15 157 19.9997,
+                          -6.17955 157 19.021,
+                          45.5 157 40.5,
+                          6.17955 157 19.021,
+                          -3.44169e-15 157 19.9997,
+                          45.5 157 40.5,
+                          11.7545 157 16.1809,
+                          6.17955 157 19.021,
+                          45.5 157 40.5,
+                          16.1794 157 11.7568,
+                          11.7545 157 16.1809,
+                          45.5 157 40.5,
+                          19.0208 157 6.18136,
+                          16.1794 157 11.7568,
+                          45.5 157 40.5,
+                          -16.1794 157 11.7568,
+                          -45.5 157 -40.5,
+                          -45.5 157 40.5,
+                          -11.7545 157 16.1809,
+                          -16.1794 157 11.7568,
+                          -45.5 157 40.5,
+                          -6.17955 157 19.021,
+                          -11.7545 157 16.1809,
+                          -45.5 157 40.5,
+                          2.25375e-14 157 -19.9997,
+                          6.17955 157 -19.021,
+                          -45.5 157 -40.5,
+                          -6.17955 157 -19.021,
+                          2.25375e-14 157 -19.9997,
+                          -45.5 157 -40.5,
+                          -11.7545 157 -16.1809,
+                          -6.17955 157 -19.021,
+                          -45.5 157 -40.5,
+                          -16.1794 157 -11.7568,
+                          -11.7545 157 -16.1809,
+                          -45.5 157 -40.5,
+                          -19.0208 157 -6.18136,
+                          -16.1794 157 -11.7568,
+                          -45.5 157 -40.5,
+                          -20 157 -2.44921e-15,
+                          -19.0208 157 -6.18136,
+                          -45.5 157 -40.5,
+                          -19.0208 157 6.18136,
+                          -20 157 -2.44921e-15,
+                          -45.5 157 -40.5,
+                          -16.1794 157 11.7568,
+                          -19.0208 157 6.18136,
+                          -45.5 157 -40.5,
+                          20 178 0,
+                          20 157 2.44921e-15,
+                          19.0208 157 -6.18136,
+                          19.0204 178 6.18191,
+                          19.0208 157 6.18136,
+                          20 157 2.44921e-15,
+                          20 178 0,
+                          19.0204 178 6.18191,
+                          20 157 2.44921e-15,
+                          19.0204 178 -6.18191,
+                          19.0208 157 -6.18136,
+                          16.1794 157 -11.7568,
+                          19.0204 178 -6.18191,
+                          20 178 0,
+                          19.0208 157 -6.18136,
+                          16.1795 178 -11.7562,
+                          16.1794 157 -11.7568,
+                          11.7545 157 -16.1809,
+                          19.0204 178 -6.18191,
+                          16.1794 157 -11.7568,
+                          16.1795 178 -11.7562,
+                          11.7562 178 -16.1795,
+                          11.7545 157 -16.1809,
+                          6.17955 157 -19.021,
+                          16.1795 178 -11.7562,
+                          11.7545 157 -16.1809,
+                          11.7562 178 -16.1795,
+                          6.18191 178 -19.0204,
+                          6.17955 157 -19.021,
+                          2.25375e-14 157 -19.9997,
+                          11.7562 178 -16.1795,
+                          6.17955 157 -19.021,
+                          6.18191 178 -19.0204,
+                          5.08047e-15 178 -20,
+                          2.25375e-14 157 -19.9997,
+                          -6.17955 157 -19.021,
+                          6.18191 178 -19.0204,
+                          2.25375e-14 157 -19.9997,
+                          5.08047e-15 178 -20,
+                          -6.18191 178 -19.0204,
+                          -6.17955 157 -19.021,
+                          -11.7545 157 -16.1809,
+                          5.08047e-15 178 -20,
+                          -6.17955 157 -19.021,
+                          -6.18191 178 -19.0204,
+                          -11.7562 178 -16.1795,
+                          -11.7545 157 -16.1809,
+                          -16.1794 157 -11.7568,
+                          -6.18191 178 -19.0204,
+                          -11.7545 157 -16.1809,
+                          -11.7562 178 -16.1795,
+                          -16.1795 178 -11.7562,
+                          -16.1794 157 -11.7568,
+                          -19.0208 157 -6.18136,
+                          -11.7562 178 -16.1795,
+                          -16.1794 157 -11.7568,
+                          -16.1795 178 -11.7562,
+                          -19.0204 178 -6.18191,
+                          -19.0208 157 -6.18136,
+                          -20 157 -2.44921e-15,
+                          -16.1795 178 -11.7562,
+                          -19.0208 157 -6.18136,
+                          -19.0204 178 -6.18191,
+                          -20 178 0,
+                          -20 157 -2.44921e-15,
+                          -19.0208 157 6.18136,
+                          -19.0204 178 -6.18191,
+                          -20 157 -2.44921e-15,
+                          -20 178 0,
+                          -19.0204 178 6.18191,
+                          -19.0208 157 6.18136,
+                          -16.1794 157 11.7568,
+                          -19.0204 178 6.18191,
+                          -20 178 0,
+                          -19.0208 157 6.18136,
+                          -16.1795 178 11.7562,
+                          -16.1794 157 11.7568,
+                          -11.7545 157 16.1809,
+                          -16.1795 178 11.7562,
+                          -19.0204 178 6.18191,
+                          -16.1794 157 11.7568,
+                          -11.7562 178 16.1795,
+                          -11.7545 157 16.1809,
+                          -6.17955 157 19.021,
+                          -11.7562 178 16.1795,
+                          -16.1795 178 11.7562,
+                          -11.7545 157 16.1809,
+                          -6.18191 178 19.0204,
+                          -6.17955 157 19.021,
+                          -3.44169e-15 157 19.9997,
+                          -6.18191 178 19.0204,
+                          -11.7562 178 16.1795,
+                          -6.17955 157 19.021,
+                          5.08047e-15 178 20,
+                          -3.44169e-15 157 19.9997,
+                          6.17955 157 19.021,
+                          5.08047e-15 178 20,
+                          -6.18191 178 19.0204,
+                          -3.44169e-15 157 19.9997,
+                          6.18191 178 19.0204,
+                          6.17955 157 19.021,
+                          11.7545 157 16.1809,
+                          6.18191 178 19.0204,
+                          5.08047e-15 178 20,
+                          6.17955 157 19.021,
+                          11.7562 178 16.1795,
+                          11.7545 157 16.1809,
+                          16.1794 157 11.7568,
+                          11.7562 178 16.1795,
+                          6.18191 178 19.0204,
+                          11.7545 157 16.1809,
+                          16.1795 178 11.7562,
+                          16.1794 157 11.7568,
+                          19.0208 157 6.18136,
+                          16.1795 178 11.7562,
+                          11.7562 178 16.1795,
+                          16.1794 157 11.7568,
+                          19.0204 178 6.18191,
+                          16.1795 178 11.7562,
+                          19.0208 157 6.18136,
+                          -15 178 -1.83691e-15,
+                          -20 178 0,
+                          -19.0204 178 6.18191,
+                          -14.0949 178 -5.13142,
+                          -19.0204 178 -6.18191,
+                          -20 178 0,
+                          -14.0949 178 -5.13142,
+                          -20 178 0,
+                          -15 178 -1.83691e-15,
+                          -11.4895 178 9.64285,
+                          -19.0204 178 6.18191,
+                          -16.1795 178 11.7562,
+                          -14.0949 178 5.13142,
+                          -15 178 -1.83691e-15,
+                          -19.0204 178 6.18191,
+                          -11.4895 178 9.64285,
+                          -14.0949 178 5.13142,
+                          -19.0204 178 6.18191,
+                          -7.49882 178 12.9907,
+                          -16.1795 178 11.7562,
+                          -11.7562 178 16.1795,
+                          -7.49882 178 12.9907,
+                          -11.4895 178 9.64285,
+                          -16.1795 178 11.7562,
+                          11.7562 178 16.1795,
+                          -11.7562 178 16.1795,
+                          -6.18191 178 19.0204,
+                          2.60423 178 14.7718,
+                          -11.7562 178 16.1795,
+                          11.7562 178 16.1795,
+                          -2.60423 178 14.7718,
+                          -7.49882 178 12.9907,
+                          -11.7562 178 16.1795,
+                          2.60423 178 14.7718,
+                          -2.60423 178 14.7718,
+                          -11.7562 178 16.1795,
+                          6.18191 178 19.0204,
+                          -6.18191 178 19.0204,
+                          5.08047e-15 178 20,
+                          11.7562 178 16.1795,
+                          -6.18191 178 19.0204,
+                          6.18191 178 19.0204,
+                          2.60423 178 14.7718,
+                          11.7562 178 16.1795,
+                          16.1795 178 11.7562,
+                          11.4895 178 9.64285,
+                          16.1795 178 11.7562,
+                          19.0204 178 6.18191,
+                          7.49882 178 12.9907,
+                          2.60423 178 14.7718,
+                          16.1795 178 11.7562,
+                          11.4895 178 9.64285,
+                          7.49882 178 12.9907,
+                          16.1795 178 11.7562,
+                          14.0949 178 5.13142,
+                          19.0204 178 6.18191,
+                          20 178 0,
+                          14.0949 178 5.13142,
+                          11.4895 178 9.64285,
+                          19.0204 178 6.18191,
+                          15 178 1.83691e-15,
+                          20 178 0,
+                          19.0204 178 -6.18191,
+                          15 178 1.83691e-15,
+                          14.0949 178 5.13142,
+                          20 178 0,
+                          -11.4895 178 -9.64285,
+                          -16.1795 178 -11.7562,
+                          -19.0204 178 -6.18191,
+                          -14.0949 178 -5.13142,
+                          -11.4895 178 -9.64285,
+                          -19.0204 178 -6.18191,
+                          -2.60423 178 -14.7718,
+                          -11.7562 178 -16.1795,
+                          -16.1795 178 -11.7562,
+                          -7.49882 178 -12.9907,
+                          -2.60423 178 -14.7718,
+                          -16.1795 178 -11.7562,
+                          -11.4895 178 -9.64285,
+                          -7.49882 178 -12.9907,
+                          -16.1795 178 -11.7562,
+                          6.18191 178 -19.0204,
+                          -6.18191 178 -19.0204,
+                          -11.7562 178 -16.1795,
+                          11.7562 178 -16.1795,
+                          6.18191 178 -19.0204,
+                          -11.7562 178 -16.1795,
+                          -2.60423 178 -14.7718,
+                          11.7562 178 -16.1795,
+                          -11.7562 178 -16.1795,
+                          6.18191 178 -19.0204,
+                          5.08047e-15 178 -20,
+                          -6.18191 178 -19.0204,
+                          7.49882 178 -12.9907,
+                          16.1795 178 -11.7562,
+                          11.7562 178 -16.1795,
+                          2.60423 178 -14.7718,
+                          7.49882 178 -12.9907,
+                          11.7562 178 -16.1795,
+                          -2.60423 178 -14.7718,
+                          2.60423 178 -14.7718,
+                          11.7562 178 -16.1795,
+                          11.4895 178 -9.64285,
+                          19.0204 178 -6.18191,
+                          16.1795 178 -11.7562,
+                          7.49882 178 -12.9907,
+                          11.4895 178 -9.64285,
+                          16.1795 178 -11.7562,
+                          14.0949 178 -5.13142,
+                          15 178 1.83691e-15,
+                          19.0204 178 -6.18191,
+                          11.4895 178 -9.64285,
+                          14.0949 178 -5.13142,
+                          19.0204 178 -6.18191 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          1 0 1.22461e-16,
+                          1 0 1.22461e-16,
+                          0.974928 0 -0.222521,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.974928 0 0.222521,
+                          0.974928 0 0.222521,
+                          1 0 1.22461e-16,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          1 0 1.22461e-16,
+                          0.974928 0 0.222521,
+                          1 0 1.22461e-16,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.974928 0 -0.222521,
+                          0.974928 0 -0.222521,
+                          0.900969 0 -0.433884,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.974928 0 -0.222521,
+                          1 0 1.22461e-16,
+                          0.974928 0 -0.222521,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.900969 0 -0.433884,
+                          0.900969 0 -0.433884,
+                          0.781832 0 -0.62349,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.974928 0 -0.222521,
+                          0.900969 0 -0.433884,
+                          0.900969 0 -0.433884,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.781832 0 -0.62349,
+                          0.781832 0 -0.62349,
+                          0.62349 0 -0.781832,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.900969 0 -0.433884,
+                          0.781832 0 -0.62349,
+                          0.781832 0 -0.62349,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.62349 0 -0.781832,
+                          0.62349 0 -0.781832,
+                          0.433884 0 -0.900969,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.781832 0 -0.62349,
+                          0.62349 0 -0.781832,
+                          0.62349 0 -0.781832,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.433884 0 -0.900969,
+                          0.433884 0 -0.900969,
+                          0.222521 0 -0.974928,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.62349 0 -0.781832,
+                          0.433884 0 -0.900969,
+                          0.433884 0 -0.900969,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.222521 0 -0.974928,
+                          0.222521 0 -0.974928,
+                          1.83691e-16 0 -1,
+                          0.433884 0 -0.900969,
+                          0.222521 0 -0.974928,
+                          0.222521 0 -0.974928,
+                          1.83691e-16 0 -1,
+                          1.83691e-16 0 -1,
+                          -0.222521 0 -0.974928,
+                          0.222521 0 -0.974928,
+                          1.83691e-16 0 -1,
+                          1.83691e-16 0 -1,
+                          -0.222521 0 -0.974928,
+                          -0.222521 0 -0.974928,
+                          -0.433884 0 -0.900969,
+                          1.83691e-16 0 -1,
+                          -0.222521 0 -0.974928,
+                          -0.222521 0 -0.974928,
+                          -0.433884 0 -0.900969,
+                          -0.433884 0 -0.900969,
+                          -0.62349 0 -0.781832,
+                          -0.222521 0 -0.974928,
+                          -0.433884 0 -0.900969,
+                          -0.433884 0 -0.900969,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.62349 0 -0.781832,
+                          -0.62349 0 -0.781832,
+                          -0.781832 0 -0.62349,
+                          -0.433884 0 -0.900969,
+                          -0.62349 0 -0.781832,
+                          -0.62349 0 -0.781832,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.781832 0 -0.62349,
+                          -0.781832 0 -0.62349,
+                          -0.900969 0 -0.433884,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.62349 0 -0.781832,
+                          -0.781832 0 -0.62349,
+                          -0.781832 0 -0.62349,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.900969 0 -0.433884,
+                          -0.900969 0 -0.433884,
+                          -0.974928 0 -0.222521,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.781832 0 -0.62349,
+                          -0.900969 0 -0.433884,
+                          -0.900969 0 -0.433884,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.974928 0 -0.222521,
+                          -0.974928 0 -0.222521,
+                          -1 0 -2.44921e-16,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.900969 0 -0.433884,
+                          -0.974928 0 -0.222521,
+                          -0.974928 0 -0.222521,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.974928 0 0.222521,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.974928 0 -0.222521,
+                          -1 0 -2.44921e-16,
+                          -1 0 -2.44921e-16,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.974928 0 0.222521,
+                          -0.974928 0 0.222521,
+                          -0.900969 0 0.433884,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.974928 0 0.222521,
+                          -1 0 0,
+                          -0.974928 0 0.222521,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.900969 0 0.433884,
+                          -0.900969 0 0.433884,
+                          -0.781832 0 0.62349,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.900969 0 0.433884,
+                          -0.974928 0 0.222521,
+                          -0.900969 0 0.433884,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.781832 0 0.62349,
+                          -0.781832 0 0.62349,
+                          -0.62349 0 0.781832,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.781832 0 0.62349,
+                          -0.900969 0 0.433884,
+                          -0.781832 0 0.62349,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.62349 0 0.781832,
+                          -0.62349 0 0.781832,
+                          -0.433884 0 0.900969,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.62349 0 0.781832,
+                          -0.781832 0 0.62349,
+                          -0.62349 0 0.781832,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.433884 0 0.900969,
+                          -0.433884 0 0.900969,
+                          -0.222521 0 0.974928,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.433884 0 0.900969,
+                          -0.62349 0 0.781832,
+                          -0.433884 0 0.900969,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.222521 0 0.974928,
+                          -0.222521 0 0.974928,
+                          -6.12303e-17 0 1,
+                          -0.222521 0 0.974928,
+                          -0.433884 0 0.900969,
+                          -0.222521 0 0.974928,
+                          -6.12303e-17 0 1,
+                          -6.12303e-17 0 1,
+                          0.222521 0 0.974928,
+                          -6.12303e-17 0 1,
+                          -0.222521 0 0.974928,
+                          -6.12303e-17 0 1,
+                          0.222521 0 0.974928,
+                          0.222521 0 0.974928,
+                          0.433884 0 0.900969,
+                          0.222521 0 0.974928,
+                          -6.12303e-17 0 1,
+                          0.222521 0 0.974928,
+                          0.433884 0 0.900969,
+                          0.433884 0 0.900969,
+                          0.62349 0 0.781832,
+                          0.433884 0 0.900969,
+                          0.222521 0 0.974928,
+                          0.433884 0 0.900969,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.62349 0 0.781832,
+                          0.62349 0 0.781832,
+                          0.781832 0 0.62349,
+                          0.62349 0 0.781832,
+                          0.433884 0 0.900969,
+                          0.62349 0 0.781832,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.781832 0 0.62349,
+                          0.781832 0 0.62349,
+                          0.900969 0 0.433884,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.781832 0 0.62349,
+                          0.62349 0 0.781832,
+                          0.781832 0 0.62349,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.900969 0 0.433884,
+                          0.900969 0 0.433884,
+                          0.974928 0 0.222521,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.900969 0 0.433884,
+                          0.781832 0 0.62349,
+                          0.900969 0 0.433884,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.974928 0 0.222521,
+                          0.900969 0 0.433884,
+                          0.974928 0 0.222521,
+                          1 0 1.22461e-16,
+                          1 0 1.22461e-16,
+                          0.965926 0 0.258819,
+                          0.965926 0 -0.258819,
+                          0.965926 0 -0.258819,
+                          1 0 1.22461e-16,
+                          0.965926 0 -0.258819,
+                          1 0 1.22461e-16,
+                          1 0 1.22461e-16,
+                          0.965926 0 0.258819,
+                          0.965926 0 0.258819,
+                          0.866025 0 0.5,
+                          0.965926 0 0.258819,
+                          1 0 1.22461e-16,
+                          0.965926 0 0.258819,
+                          0.866025 0 0.5,
+                          0.866025 0 0.5,
+                          0.707107 0 0.707107,
+                          0.866025 0 0.5,
+                          0.965926 0 0.258819,
+                          0.866025 0 0.5,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          0.5 0 0.866025,
+                          0.707107 0 0.707107,
+                          0.866025 0 0.5,
+                          0.707107 0 0.707107,
+                          0.5 0 0.866025,
+                          0.5 0 0.866025,
+                          0.258819 0 0.965926,
+                          0.5 0 0.866025,
+                          0.707107 0 0.707107,
+                          0.5 0 0.866025,
+                          0.258819 0 0.965926,
+                          0.258819 0 0.965926,
+                          -6.12303e-17 0 1,
+                          0.258819 0 0.965926,
+                          0.5 0 0.866025,
+                          0.258819 0 0.965926,
+                          -6.12303e-17 0 1,
+                          -6.12303e-17 0 1,
+                          -0.258819 0 0.965926,
+                          -6.12303e-17 0 1,
+                          0.258819 0 0.965926,
+                          -6.12303e-17 0 1,
+                          -0.258819 0 0.965926,
+                          -0.258819 0 0.965926,
+                          -0.5 0 0.866025,
+                          -0.258819 0 0.965926,
+                          -6.12303e-17 0 1,
+                          -0.258819 0 0.965926,
+                          -0.5 0 0.866025,
+                          -0.5 0 0.866025,
+                          -0.707107 0 0.707107,
+                          -0.5 0 0.866025,
+                          -0.258819 0 0.965926,
+                          -0.5 0 0.866025,
+                          -0.707107 0 0.707107,
+                          -0.707107 0 0.707107,
+                          -0.866025 0 0.5,
+                          -0.707107 0 0.707107,
+                          -0.5 0 0.866025,
+                          -0.707107 0 0.707107,
+                          -0.866025 0 0.5,
+                          -0.866025 0 0.5,
+                          -0.965926 0 0.258819,
+                          -0.866025 0 0.5,
+                          -0.707107 0 0.707107,
+                          -0.866025 0 0.5,
+                          -0.965926 0 0.258819,
+                          -0.965926 0 0.258819,
+                          -1 0 0,
+                          -0.965926 0 0.258819,
+                          -0.866025 0 0.5,
+                          -0.965926 0 0.258819,
+                          -1 0 -2.44921e-16,
+                          -1 0 -2.44921e-16,
+                          -0.965926 0 -0.258819,
+                          -1 0 0,
+                          -0.965926 0 0.258819,
+                          -1 0 0,
+                          -0.965926 0 -0.258819,
+                          -0.965926 0 -0.258819,
+                          -0.866025 0 -0.5,
+                          -0.965926 0 -0.258819,
+                          -1 0 -2.44921e-16,
+                          -0.965926 0 -0.258819,
+                          -0.866025 0 -0.5,
+                          -0.866025 0 -0.5,
+                          -0.707107 0 -0.707107,
+                          -0.965926 0 -0.258819,
+                          -0.866025 0 -0.5,
+                          -0.866025 0 -0.5,
+                          -0.707107 0 -0.707107,
+                          -0.707107 0 -0.707107,
+                          -0.5 0 -0.866025,
+                          -0.866025 0 -0.5,
+                          -0.707107 0 -0.707107,
+                          -0.707107 0 -0.707107,
+                          -0.5 0 -0.866025,
+                          -0.5 0 -0.866025,
+                          -0.258819 0 -0.965926,
+                          -0.707107 0 -0.707107,
+                          -0.5 0 -0.866025,
+                          -0.5 0 -0.866025,
+                          -0.258819 0 -0.965926,
+                          -0.258819 0 -0.965926,
+                          1.83691e-16 0 -1,
+                          -0.5 0 -0.866025,
+                          -0.258819 0 -0.965926,
+                          -0.258819 0 -0.965926,
+                          1.83691e-16 0 -1,
+                          1.83691e-16 0 -1,
+                          0.258819 0 -0.965926,
+                          -0.258819 0 -0.965926,
+                          1.83691e-16 0 -1,
+                          1.83691e-16 0 -1,
+                          0.258819 0 -0.965926,
+                          0.258819 0 -0.965926,
+                          0.5 0 -0.866025,
+                          1.83691e-16 0 -1,
+                          0.258819 0 -0.965926,
+                          0.258819 0 -0.965926,
+                          0.5 0 -0.866025,
+                          0.5 0 -0.866025,
+                          0.707107 0 -0.707107,
+                          0.258819 0 -0.965926,
+                          0.5 0 -0.866025,
+                          0.5 0 -0.866025,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          0.866025 0 -0.5,
+                          0.5 0 -0.866025,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          0.866025 0 -0.5,
+                          0.866025 0 -0.5,
+                          0.965926 0 -0.258819,
+                          0.707107 0 -0.707107,
+                          0.866025 0 -0.5,
+                          0.866025 0 -0.5,
+                          0.866025 0 -0.5,
+                          0.965926 0 -0.258819,
+                          0.965926 0 -0.258819,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          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.22461e-16,
+                          -1 0 -1.22461e-16,
+                          -0.959493 0 0.281733,
+                          -0.959493 0 -0.281733,
+                          -0.959493 0 -0.281733,
+                          -1 0 -1.22461e-16,
+                          -1 0 -1.22461e-16,
+                          -0.959493 0 -0.281733,
+                          -1 0 -1.22461e-16,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.959493 0 0.281733,
+                          -0.959493 0 0.281733,
+                          -0.841254 0 0.540641,
+                          -0.959493 0 0.281733,
+                          -1 0 -1.22461e-16,
+                          -0.959493 0 0.281733,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.841254 0 0.540641,
+                          -0.841254 0 0.540641,
+                          -0.654861 0 0.75575,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.959493 0 0.281733,
+                          -0.841254 0 0.540641,
+                          -0.841254 0 0.540641,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.654861 0 0.75575,
+                          -0.654861 0 0.75575,
+                          -0.415415 0 0.909632,
+                          -0.841254 0 0.540641,
+                          -0.654861 0 0.75575,
+                          -0.654861 0 0.75575,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.415415 0 0.909632,
+                          -0.415415 0 0.909632,
+                          -0.142315 0 0.989821,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.654861 0 0.75575,
+                          -0.415415 0 0.909632,
+                          -0.415415 0 0.909632,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.142315 0 0.989821,
+                          -0.142315 0 0.989821,
+                          0.142315 0 0.989821,
+                          -0.415415 0 0.909632,
+                          -0.142315 0 0.989821,
+                          -0.142315 0 0.989821,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.142315 0 0.989821,
+                          0.142315 0 0.989821,
+                          0.415415 0 0.909632,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.142315 0 0.989821,
+                          0.142315 0 0.989821,
+                          0.142315 0 0.989821,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.415415 0 0.909632,
+                          0.415415 0 0.909632,
+                          0.654861 0 0.75575,
+                          0.142315 0 0.989821,
+                          0.415415 0 0.909632,
+                          0.415415 0 0.909632,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.654861 0 0.75575,
+                          0.654861 0 0.75575,
+                          0.841254 0 0.540641,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.415415 0 0.909632,
+                          0.654861 0 0.75575,
+                          0.654861 0 0.75575,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.841254 0 0.540641,
+                          0.841254 0 0.540641,
+                          0.959493 0 0.281733,
+                          0.654861 0 0.75575,
+                          0.841254 0 0.540641,
+                          0.841254 0 0.540641,
+                          0.959493 0 0.281733,
+                          0.959493 0 0.281733,
+                          1 0 2.44921e-16,
+                          0.841254 0 0.540641,
+                          0.959493 0 0.281733,
+                          0.959493 0 0.281733,
+                          1 0 0,
+                          1 0 0,
+                          0.959493 0 -0.281733,
+                          0.959493 0 0.281733,
+                          1 0 2.44921e-16,
+                          1 0 2.44921e-16,
+                          0.959493 0 -0.281733,
+                          0.959493 0 -0.281733,
+                          0.841254 0 -0.540641,
+                          0.959493 0 -0.281733,
+                          1 0 0,
+                          0.959493 0 -0.281733,
+                          0.841254 0 -0.540641,
+                          0.841254 0 -0.540641,
+                          0.654861 0 -0.75575,
+                          0.841254 0 -0.540641,
+                          0.959493 0 -0.281733,
+                          0.841254 0 -0.540641,
+                          0.654861 0 -0.75575,
+                          0.654861 0 -0.75575,
+                          0.415415 0 -0.909632,
+                          0.654861 0 -0.75575,
+                          0.841254 0 -0.540641,
+                          0.654861 0 -0.75575,
+                          0.415415 0 -0.909632,
+                          0.415415 0 -0.909632,
+                          0.142315 0 -0.989821,
+                          0.415415 0 -0.909632,
+                          0.654861 0 -0.75575,
+                          0.415415 0 -0.909632,
+                          0.142315 0 -0.989821,
+                          0.142315 0 -0.989821,
+                          -0.142315 0 -0.989821,
+                          0.142315 0 -0.989821,
+                          0.415415 0 -0.909632,
+                          0.142315 0 -0.989821,
+                          -0.142315 0 -0.989821,
+                          -0.142315 0 -0.989821,
+                          -0.415415 0 -0.909632,
+                          -0.142315 0 -0.989821,
+                          0.142315 0 -0.989821,
+                          -0.142315 0 -0.989821,
+                          -0.415415 0 -0.909632,
+                          -0.415415 0 -0.909632,
+                          -0.654861 0 -0.75575,
+                          -0.415415 0 -0.909632,
+                          -0.142315 0 -0.989821,
+                          -0.415415 0 -0.909632,
+                          -0.654861 0 -0.75575,
+                          -0.654861 0 -0.75575,
+                          -0.841254 0 -0.540641,
+                          -0.654861 0 -0.75575,
+                          -0.415415 0 -0.909632,
+                          -0.654861 0 -0.75575,
+                          -0.841254 0 -0.540641,
+                          -0.841254 0 -0.540641,
+                          -0.959493 0 -0.281733,
+                          -0.841254 0 -0.540641,
+                          -0.654861 0 -0.75575,
+                          -0.841254 0 -0.540641,
+                          -0.959493 0 -0.281733,
+                          -0.841254 0 -0.540641,
+                          -0.959493 0 -0.281733,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          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.22461e-16,
+                          -1 0 -1.22461e-16,
+                          -0.900969 0 0.433884,
+                          -0.900969 0 -0.433884,
+                          -0.900969 0 -0.433884,
+                          -1 0 -1.22461e-16,
+                          -1 0 -1.22461e-16,
+                          -0.900969 0 -0.433884,
+                          -1 0 -1.22461e-16,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.900969 0 0.433884,
+                          -0.900969 0 0.433884,
+                          -0.62349 0 0.781832,
+                          -0.900969 0 0.433884,
+                          -1 0 -1.22461e-16,
+                          -0.900969 0 0.433884,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.62349 0 0.781832,
+                          -0.62349 0 0.781832,
+                          -0.222521 0 0.974928,
+                          -0.900969 0 0.433884,
+                          -0.62349 0 0.781832,
+                          -0.62349 0 0.781832,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.222521 0 0.974928,
+                          -0.222521 0 0.974928,
+                          0.222521 0 0.974928,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.62349 0 0.781832,
+                          -0.222521 0 0.974928,
+                          -0.222521 0 0.974928,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.222521 0 0.974928,
+                          0.222521 0 0.974928,
+                          0.62349 0 0.781832,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.222521 0 0.974928,
+                          0.222521 0 0.974928,
+                          0.222521 0 0.974928,
+                          0.62349 0 0.781832,
+                          0.62349 0 0.781832,
+                          0.900969 0 0.433884,
+                          0.222521 0 0.974928,
+                          0.62349 0 0.781832,
+                          0.62349 0 0.781832,
+                          0.900969 0 0.433884,
+                          0.900969 0 0.433884,
+                          1 0 2.44921e-16,
+                          0.62349 0 0.781832,
+                          0.900969 0 0.433884,
+                          0.900969 0 0.433884,
+                          1 0 0,
+                          1 0 0,
+                          0.900969 0 -0.433884,
+                          0.900969 0 0.433884,
+                          1 0 2.44921e-16,
+                          1 0 2.44921e-16,
+                          0.900969 0 -0.433884,
+                          0.900969 0 -0.433884,
+                          0.62349 0 -0.781832,
+                          0.900969 0 -0.433884,
+                          1 0 0,
+                          0.900969 0 -0.433884,
+                          0.62349 0 -0.781832,
+                          0.62349 0 -0.781832,
+                          0.222521 0 -0.974928,
+                          0.62349 0 -0.781832,
+                          0.900969 0 -0.433884,
+                          0.62349 0 -0.781832,
+                          0.222521 0 -0.974928,
+                          0.222521 0 -0.974928,
+                          -0.222521 0 -0.974928,
+                          0.222521 0 -0.974928,
+                          0.62349 0 -0.781832,
+                          0.222521 0 -0.974928,
+                          -0.222521 0 -0.974928,
+                          -0.222521 0 -0.974928,
+                          -0.62349 0 -0.781832,
+                          -0.222521 0 -0.974928,
+                          0.222521 0 -0.974928,
+                          -0.222521 0 -0.974928,
+                          -0.62349 0 -0.781832,
+                          -0.62349 0 -0.781832,
+                          -0.900969 0 -0.433884,
+                          -0.62349 0 -0.781832,
+                          -0.222521 0 -0.974928,
+                          -0.62349 0 -0.781832,
+                          -0.900969 0 -0.433884,
+                          -0.62349 0 -0.781832,
+                          -0.900969 0 -0.433884,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 26.08 112 -6.98764,
+                          41.4344 112 -9.45713,
+                          42.5 112 0,
+                          42.5 115 0,
+                          42.5 112 0,
+                          41.4344 112 -9.45713,
+                          27 112 0,
+                          42.5 112 0,
+                          41.4344 112 9.45713,
+                          41.4344 115 9.45713,
+                          41.4344 112 9.45713,
+                          42.5 112 0,
+                          26.08 112 -6.98764,
+                          42.5 112 0,
+                          27 112 0,
+                          42.5 115 0,
+                          41.4344 115 9.45713,
+                          42.5 112 0,
+                          23.3824 112 -13.5004,
+                          38.2912 112 -18.4401,
+                          41.4344 112 -9.45713,
+                          41.4344 115 -9.45713,
+                          41.4344 112 -9.45713,
+                          38.2912 112 -18.4401,
+                          26.08 112 -6.98764,
+                          23.3824 112 -13.5004,
+                          41.4344 112 -9.45713,
+                          41.4344 115 -9.45713,
+                          42.5 115 0,
+                          41.4344 112 -9.45713,
+                          6.98764 112 -26.08,
+                          33.2278 112 -26.4983,
+                          38.2912 112 -18.4401,
+                          38.2912 115 -18.4401,
+                          38.2912 112 -18.4401,
+                          33.2278 112 -26.4983,
+                          13.5004 112 -23.3824,
+                          6.98764 112 -26.08,
+                          38.2912 112 -18.4401,
+                          19.0919 112 -19.0919,
+                          13.5004 112 -23.3824,
+                          38.2912 112 -18.4401,
+                          23.3824 112 -13.5004,
+                          19.0919 112 -19.0919,
+                          38.2912 112 -18.4401,
+                          41.4344 115 -9.45713,
+                          38.2912 112 -18.4401,
+                          38.2912 115 -18.4401,
+                          -26.4983 112 -33.2278,
+                          26.4983 112 -33.2278,
+                          33.2278 112 -26.4983,
+                          33.2278 115 -26.4983,
+                          33.2278 112 -26.4983,
+                          26.4983 112 -33.2278,
+                          1.65322e-15 112 -27,
+                          -26.4983 112 -33.2278,
+                          33.2278 112 -26.4983,
+                          6.98764 112 -26.08,
+                          1.65322e-15 112 -27,
+                          33.2278 112 -26.4983,
+                          38.2912 115 -18.4401,
+                          33.2278 112 -26.4983,
+                          33.2278 115 -26.4983,
+                          -18.44 112 -38.2911,
+                          18.44 112 -38.2911,
+                          26.4983 112 -33.2278,
+                          26.4983 115 -33.2278,
+                          26.4983 112 -33.2278,
+                          18.44 112 -38.2911,
+                          -26.4983 112 -33.2278,
+                          -18.44 112 -38.2911,
+                          26.4983 112 -33.2278,
+                          33.2278 115 -26.4983,
+                          26.4983 112 -33.2278,
+                          26.4983 115 -33.2278,
+                          -9.45714 112 -41.4344,
+                          9.45714 112 -41.4344,
+                          18.44 112 -38.2911,
+                          18.44 115 -38.2911,
+                          18.44 112 -38.2911,
+                          9.45714 112 -41.4344,
+                          -18.44 112 -38.2911,
+                          -9.45714 112 -41.4344,
+                          18.44 112 -38.2911,
+                          26.4983 115 -33.2278,
+                          18.44 112 -38.2911,
+                          18.44 115 -38.2911,
+                          -9.45714 112 -41.4344,
+                          7.32747e-15 112 -42.4999,
+                          9.45714 112 -41.4344,
+                          9.45714 115 -41.4344,
+                          9.45714 112 -41.4344,
+                          7.32747e-15 112 -42.4999,
+                          18.44 115 -38.2911,
+                          9.45714 112 -41.4344,
+                          9.45714 115 -41.4344,
+                          7.32747e-15 115 -42.4999,
+                          7.32747e-15 112 -42.4999,
+                          -9.45714 112 -41.4344,
+                          9.45714 115 -41.4344,
+                          7.32747e-15 112 -42.4999,
+                          7.32747e-15 115 -42.4999,
+                          -9.45714 115 -41.4344,
+                          -9.45714 112 -41.4344,
+                          -18.44 112 -38.2911,
+                          7.32747e-15 115 -42.4999,
+                          -9.45714 112 -41.4344,
+                          -9.45714 115 -41.4344,
+                          -18.44 115 -38.2911,
+                          -18.44 112 -38.2911,
+                          -26.4983 112 -33.2278,
+                          -9.45714 115 -41.4344,
+                          -18.44 112 -38.2911,
+                          -18.44 115 -38.2911,
+                          1.65322e-15 112 -27,
+                          -33.2278 112 -26.4983,
+                          -26.4983 112 -33.2278,
+                          -26.4983 115 -33.2278,
+                          -26.4983 112 -33.2278,
+                          -33.2278 112 -26.4983,
+                          -18.44 115 -38.2911,
+                          -26.4983 112 -33.2278,
+                          -26.4983 115 -33.2278,
+                          -19.0919 112 -19.0919,
+                          -38.2912 112 -18.4401,
+                          -33.2278 112 -26.4983,
+                          -33.2278 115 -26.4983,
+                          -33.2278 112 -26.4983,
+                          -38.2912 112 -18.4401,
+                          -13.5004 112 -23.3824,
+                          -19.0919 112 -19.0919,
+                          -33.2278 112 -26.4983,
+                          -6.98764 112 -26.08,
+                          -13.5004 112 -23.3824,
+                          -33.2278 112 -26.4983,
+                          1.65322e-15 112 -27,
+                          -6.98764 112 -26.08,
+                          -33.2278 112 -26.4983,
+                          -26.4983 115 -33.2278,
+                          -33.2278 112 -26.4983,
+                          -33.2278 115 -26.4983,
+                          -23.3824 112 -13.5004,
+                          -41.4344 112 -9.45713,
+                          -38.2912 112 -18.4401,
+                          -38.2912 115 -18.4401,
+                          -38.2912 112 -18.4401,
+                          -41.4344 112 -9.45713,
+                          -19.0919 112 -19.0919,
+                          -23.3824 112 -13.5004,
+                          -38.2912 112 -18.4401,
+                          -33.2278 115 -26.4983,
+                          -38.2912 112 -18.4401,
+                          -38.2912 115 -18.4401,
+                          -27 112 0,
+                          -42.5 112 0,
+                          -41.4344 112 -9.45713,
+                          -41.4344 115 -9.45713,
+                          -41.4344 112 -9.45713,
+                          -42.5 112 0,
+                          -26.08 112 -6.98764,
+                          -27 112 0,
+                          -41.4344 112 -9.45713,
+                          -23.3824 112 -13.5004,
+                          -26.08 112 -6.98764,
+                          -41.4344 112 -9.45713,
+                          -38.2912 115 -18.4401,
+                          -41.4344 112 -9.45713,
+                          -41.4344 115 -9.45713,
+                          -26.08 112 6.98764,
+                          -41.4344 112 9.45713,
+                          -42.5 112 0,
+                          -42.5 115 0,
+                          -42.5 112 0,
+                          -41.4344 112 9.45713,
+                          -27 112 0,
+                          -26.08 112 6.98764,
+                          -42.5 112 0,
+                          -41.4344 115 -9.45713,
+                          -42.5 112 0,
+                          -42.5 115 0,
+                          -23.3824 112 13.5004,
+                          -38.2912 112 18.4401,
+                          -41.4344 112 9.45713,
+                          -41.4344 115 9.45713,
+                          -41.4344 112 9.45713,
+                          -38.2912 112 18.4401,
+                          -26.08 112 6.98764,
+                          -23.3824 112 13.5004,
+                          -41.4344 112 9.45713,
+                          -41.4344 115 9.45713,
+                          -42.5 115 0,
+                          -41.4344 112 9.45713,
+                          -6.98764 112 26.08,
+                          -33.2278 112 26.4983,
+                          -38.2912 112 18.4401,
+                          -38.2912 115 18.4401,
+                          -38.2912 112 18.4401,
+                          -33.2278 112 26.4983,
+                          -13.5004 112 23.3824,
+                          -6.98764 112 26.08,
+                          -38.2912 112 18.4401,
+                          -19.0919 112 19.0919,
+                          -13.5004 112 23.3824,
+                          -38.2912 112 18.4401,
+                          -23.3824 112 13.5004,
+                          -19.0919 112 19.0919,
+                          -38.2912 112 18.4401,
+                          -38.2912 115 18.4401,
+                          -41.4344 115 9.45713,
+                          -38.2912 112 18.4401,
+                          26.4983 112 33.2278,
+                          -26.4983 112 33.2278,
+                          -33.2278 112 26.4983,
+                          -33.2278 115 26.4983,
+                          -33.2278 112 26.4983,
+                          -26.4983 112 33.2278,
+                          1.65322e-15 112 27,
+                          26.4983 112 33.2278,
+                          -33.2278 112 26.4983,
+                          -6.98764 112 26.08,
+                          1.65322e-15 112 27,
+                          -33.2278 112 26.4983,
+                          -33.2278 115 26.4983,
+                          -38.2912 115 18.4401,
+                          -33.2278 112 26.4983,
+                          18.44 112 38.2911,
+                          -18.44 112 38.2911,
+                          -26.4983 112 33.2278,
+                          -26.4983 115 33.2278,
+                          -26.4983 112 33.2278,
+                          -18.44 112 38.2911,
+                          26.4983 112 33.2278,
+                          18.44 112 38.2911,
+                          -26.4983 112 33.2278,
+                          -26.4983 115 33.2278,
+                          -33.2278 115 26.4983,
+                          -26.4983 112 33.2278,
+                          9.45714 112 41.4344,
+                          -9.45714 112 41.4344,
+                          -18.44 112 38.2911,
+                          -18.44 115 38.2911,
+                          -18.44 112 38.2911,
+                          -9.45714 112 41.4344,
+                          18.44 112 38.2911,
+                          9.45714 112 41.4344,
+                          -18.44 112 38.2911,
+                          -18.44 115 38.2911,
+                          -26.4983 115 33.2278,
+                          -18.44 112 38.2911,
+                          9.45714 112 41.4344,
+                          7.32747e-15 112 42.4999,
+                          -9.45714 112 41.4344,
+                          -9.45714 115 41.4344,
+                          -9.45714 112 41.4344,
+                          7.32747e-15 112 42.4999,
+                          -9.45714 115 41.4344,
+                          -18.44 115 38.2911,
+                          -9.45714 112 41.4344,
+                          7.32747e-15 115 42.4999,
+                          7.32747e-15 112 42.4999,
+                          9.45714 112 41.4344,
+                          7.32747e-15 115 42.4999,
+                          -9.45714 115 41.4344,
+                          7.32747e-15 112 42.4999,
+                          9.45714 115 41.4344,
+                          9.45714 112 41.4344,
+                          18.44 112 38.2911,
+                          9.45714 115 41.4344,
+                          7.32747e-15 115 42.4999,
+                          9.45714 112 41.4344,
+                          18.44 115 38.2911,
+                          18.44 112 38.2911,
+                          26.4983 112 33.2278,
+                          18.44 115 38.2911,
+                          9.45714 115 41.4344,
+                          18.44 112 38.2911,
+                          1.65322e-15 112 27,
+                          33.2278 112 26.4983,
+                          26.4983 112 33.2278,
+                          26.4983 115 33.2278,
+                          26.4983 112 33.2278,
+                          33.2278 112 26.4983,
+                          26.4983 115 33.2278,
+                          18.44 115 38.2911,
+                          26.4983 112 33.2278,
+                          19.0919 112 19.0919,
+                          38.2912 112 18.4401,
+                          33.2278 112 26.4983,
+                          33.2278 115 26.4983,
+                          33.2278 112 26.4983,
+                          38.2912 112 18.4401,
+                          13.5004 112 23.3824,
+                          19.0919 112 19.0919,
+                          33.2278 112 26.4983,
+                          6.98764 112 26.08,
+                          13.5004 112 23.3824,
+                          33.2278 112 26.4983,
+                          1.65322e-15 112 27,
+                          6.98764 112 26.08,
+                          33.2278 112 26.4983,
+                          33.2278 115 26.4983,
+                          26.4983 115 33.2278,
+                          33.2278 112 26.4983,
+                          23.3824 112 13.5004,
+                          41.4344 112 9.45713,
+                          38.2912 112 18.4401,
+                          38.2912 115 18.4401,
+                          38.2912 112 18.4401,
+                          41.4344 112 9.45713,
+                          19.0919 112 19.0919,
+                          23.3824 112 13.5004,
+                          38.2912 112 18.4401,
+                          38.2912 115 18.4401,
+                          33.2278 115 26.4983,
+                          38.2912 112 18.4401,
+                          26.08 112 6.98764,
+                          27 112 0,
+                          41.4344 112 9.45713,
+                          23.3824 112 13.5004,
+                          26.08 112 6.98764,
+                          41.4344 112 9.45713,
+                          41.4344 115 9.45713,
+                          38.2912 115 18.4401,
+                          41.4344 112 9.45713,
+                          27 104 0,
+                          27 112 0,
+                          26.08 112 6.98764,
+                          26.08 104 -6.98764,
+                          26.08 112 -6.98764,
+                          27 112 0,
+                          26.08 104 -6.98764,
+                          27 112 0,
+                          27 104 0,
+                          26.08 104 6.98764,
+                          26.08 112 6.98764,
+                          23.3824 112 13.5004,
+                          26.08 104 6.98764,
+                          27 104 0,
+                          26.08 112 6.98764,
+                          23.3824 104 13.5004,
+                          23.3824 112 13.5004,
+                          19.0919 112 19.0919,
+                          23.3824 104 13.5004,
+                          26.08 104 6.98764,
+                          23.3824 112 13.5004,
+                          19.0919 104 19.0919,
+                          19.0919 112 19.0919,
+                          13.5004 112 23.3824,
+                          19.0919 104 19.0919,
+                          23.3824 104 13.5004,
+                          19.0919 112 19.0919,
+                          13.5004 104 23.3824,
+                          13.5004 112 23.3824,
+                          6.98764 112 26.08,
+                          13.5004 104 23.3824,
+                          19.0919 104 19.0919,
+                          13.5004 112 23.3824,
+                          6.98764 104 26.08,
+                          6.98764 112 26.08,
+                          1.65322e-15 112 27,
+                          6.98764 104 26.08,
+                          13.5004 104 23.3824,
+                          6.98764 112 26.08,
+                          1.65322e-15 104 27,
+                          1.65322e-15 112 27,
+                          -6.98764 112 26.08,
+                          1.65322e-15 104 27,
+                          6.98764 104 26.08,
+                          1.65322e-15 112 27,
+                          -6.98764 104 26.08,
+                          -6.98764 112 26.08,
+                          -13.5004 112 23.3824,
+                          -6.98764 104 26.08,
+                          1.65322e-15 104 27,
+                          -6.98764 112 26.08,
+                          -13.5004 104 23.3824,
+                          -13.5004 112 23.3824,
+                          -19.0919 112 19.0919,
+                          -13.5004 104 23.3824,
+                          -6.98764 104 26.08,
+                          -13.5004 112 23.3824,
+                          -19.0919 104 19.0919,
+                          -19.0919 112 19.0919,
+                          -23.3824 112 13.5004,
+                          -19.0919 104 19.0919,
+                          -13.5004 104 23.3824,
+                          -19.0919 112 19.0919,
+                          -23.3824 104 13.5004,
+                          -23.3824 112 13.5004,
+                          -26.08 112 6.98764,
+                          -23.3824 104 13.5004,
+                          -19.0919 104 19.0919,
+                          -23.3824 112 13.5004,
+                          -26.08 104 6.98764,
+                          -26.08 112 6.98764,
+                          -27 112 0,
+                          -26.08 104 6.98764,
+                          -23.3824 104 13.5004,
+                          -26.08 112 6.98764,
+                          -27 104 0,
+                          -27 112 0,
+                          -26.08 112 -6.98764,
+                          -27 104 0,
+                          -26.08 104 6.98764,
+                          -27 112 0,
+                          -26.08 104 -6.98764,
+                          -26.08 112 -6.98764,
+                          -23.3824 112 -13.5004,
+                          -26.08 104 -6.98764,
+                          -27 104 0,
+                          -26.08 112 -6.98764,
+                          -23.3824 104 -13.5004,
+                          -23.3824 112 -13.5004,
+                          -19.0919 112 -19.0919,
+                          -26.08 104 -6.98764,
+                          -23.3824 112 -13.5004,
+                          -23.3824 104 -13.5004,
+                          -19.0919 104 -19.0919,
+                          -19.0919 112 -19.0919,
+                          -13.5004 112 -23.3824,
+                          -23.3824 104 -13.5004,
+                          -19.0919 112 -19.0919,
+                          -19.0919 104 -19.0919,
+                          -13.5004 104 -23.3824,
+                          -13.5004 112 -23.3824,
+                          -6.98764 112 -26.08,
+                          -19.0919 104 -19.0919,
+                          -13.5004 112 -23.3824,
+                          -13.5004 104 -23.3824,
+                          -6.98764 104 -26.08,
+                          -6.98764 112 -26.08,
+                          1.65322e-15 112 -27,
+                          -13.5004 104 -23.3824,
+                          -6.98764 112 -26.08,
+                          -6.98764 104 -26.08,
+                          1.65322e-15 104 -27,
+                          1.65322e-15 112 -27,
+                          6.98764 112 -26.08,
+                          -6.98764 104 -26.08,
+                          1.65322e-15 112 -27,
+                          1.65322e-15 104 -27,
+                          6.98764 104 -26.08,
+                          6.98764 112 -26.08,
+                          13.5004 112 -23.3824,
+                          1.65322e-15 104 -27,
+                          6.98764 112 -26.08,
+                          6.98764 104 -26.08,
+                          13.5004 104 -23.3824,
+                          13.5004 112 -23.3824,
+                          19.0919 112 -19.0919,
+                          6.98764 104 -26.08,
+                          13.5004 112 -23.3824,
+                          13.5004 104 -23.3824,
+                          19.0919 104 -19.0919,
+                          19.0919 112 -19.0919,
+                          23.3824 112 -13.5004,
+                          13.5004 104 -23.3824,
+                          19.0919 112 -19.0919,
+                          19.0919 104 -19.0919,
+                          23.3824 104 -13.5004,
+                          23.3824 112 -13.5004,
+                          26.08 112 -6.98764,
+                          19.0919 104 -19.0919,
+                          23.3824 112 -13.5004,
+                          23.3824 104 -13.5004,
+                          23.3824 104 -13.5004,
+                          26.08 112 -6.98764,
+                          26.08 104 -6.98764,
+                          -24 115 0,
+                          -42.5 115 0,
+                          -41.4344 115 9.45713,
+                          -24 115 0,
+                          -23.0279 115 -6.76112,
+                          -42.5 115 0,
+                          -41.4344 115 -9.45713,
+                          -42.5 115 0,
+                          -23.0279 115 -6.76112,
+                          -20.1897 115 12.9759,
+                          -41.4344 115 9.45713,
+                          -38.2912 115 18.4401,
+                          -23.0279 115 6.76112,
+                          -24 115 0,
+                          -41.4344 115 9.45713,
+                          -20.1897 115 12.9759,
+                          -23.0279 115 6.76112,
+                          -41.4344 115 9.45713,
+                          -9.97006 115 21.831,
+                          -38.2912 115 18.4401,
+                          -33.2278 115 26.4983,
+                          -15.717 115 18.1377,
+                          -20.1897 115 12.9759,
+                          -38.2912 115 18.4401,
+                          -9.97006 115 21.831,
+                          -15.717 115 18.1377,
+                          -38.2912 115 18.4401,
+                          33.2278 115 26.4983,
+                          -33.2278 115 26.4983,
+                          -26.4983 115 33.2278,
+                          3.41489 115 23.7558,
+                          -33.2278 115 26.4983,
+                          33.2278 115 26.4983,
+                          -3.41489 115 23.7558,
+                          -9.97006 115 21.831,
+                          -33.2278 115 26.4983,
+                          3.41489 115 23.7558,
+                          -3.41489 115 23.7558,
+                          -33.2278 115 26.4983,
+                          26.4983 115 33.2278,
+                          -26.4983 115 33.2278,
+                          -18.44 115 38.2911,
+                          33.2278 115 26.4983,
+                          -26.4983 115 33.2278,
+                          26.4983 115 33.2278,
+                          18.44 115 38.2911,
+                          -18.44 115 38.2911,
+                          -9.45714 115 41.4344,
+                          26.4983 115 33.2278,
+                          -18.44 115 38.2911,
+                          18.44 115 38.2911,
+                          9.45714 115 41.4344,
+                          -9.45714 115 41.4344,
+                          7.32747e-15 115 42.4999,
+                          18.44 115 38.2911,
+                          -9.45714 115 41.4344,
+                          9.45714 115 41.4344,
+                          3.41489 115 23.7558,
+                          33.2278 115 26.4983,
+                          38.2912 115 18.4401,
+                          15.717 115 18.1377,
+                          38.2912 115 18.4401,
+                          41.4344 115 9.45713,
+                          9.97006 115 21.831,
+                          3.41489 115 23.7558,
+                          38.2912 115 18.4401,
+                          15.717 115 18.1377,
+                          9.97006 115 21.831,
+                          38.2912 115 18.4401,
+                          23.0279 115 6.76112,
+                          41.4344 115 9.45713,
+                          42.5 115 0,
+                          20.1897 115 12.9759,
+                          15.717 115 18.1377,
+                          41.4344 115 9.45713,
+                          23.0279 115 6.76112,
+                          20.1897 115 12.9759,
+                          41.4344 115 9.45713,
+                          23.0279 115 6.76112,
+                          42.5 115 0,
+                          24 115 0,
+                          41.4344 115 -9.45713,
+                          24 115 0,
+                          42.5 115 0,
+                          41.4344 115 -9.45713,
+                          23.0279 115 -6.76112,
+                          24 115 0,
+                          24 107 0,
+                          24 115 0,
+                          23.0279 115 -6.76112,
+                          23.0279 107 6.76112,
+                          23.0279 115 6.76112,
+                          24 115 0,
+                          24 107 0,
+                          23.0279 107 6.76112,
+                          24 115 0,
+                          41.4344 115 -9.45713,
+                          20.1897 115 -12.9759,
+                          23.0279 115 -6.76112,
+                          23.0279 107 -6.76112,
+                          23.0279 115 -6.76112,
+                          20.1897 115 -12.9759,
+                          23.0279 107 -6.76112,
+                          24 107 0,
+                          23.0279 115 -6.76112,
+                          38.2912 115 -18.4401,
+                          15.717 115 -18.1377,
+                          20.1897 115 -12.9759,
+                          20.1897 107 -12.9759,
+                          20.1897 115 -12.9759,
+                          15.717 115 -18.1377,
+                          41.4344 115 -9.45713,
+                          38.2912 115 -18.4401,
+                          20.1897 115 -12.9759,
+                          23.0279 107 -6.76112,
+                          20.1897 115 -12.9759,
+                          20.1897 107 -12.9759,
+                          38.2912 115 -18.4401,
+                          9.97006 115 -21.831,
+                          15.717 115 -18.1377,
+                          15.717 107 -18.1377,
+                          15.717 115 -18.1377,
+                          9.97006 115 -21.831,
+                          20.1897 107 -12.9759,
+                          15.717 115 -18.1377,
+                          15.717 107 -18.1377,
+                          33.2278 115 -26.4983,
+                          3.41489 115 -23.7558,
+                          9.97006 115 -21.831,
+                          9.97006 107 -21.831,
+                          9.97006 115 -21.831,
+                          3.41489 115 -23.7558,
+                          38.2912 115 -18.4401,
+                          33.2278 115 -26.4983,
+                          9.97006 115 -21.831,
+                          15.717 107 -18.1377,
+                          9.97006 115 -21.831,
+                          9.97006 107 -21.831,
+                          33.2278 115 -26.4983,
+                          -3.41489 115 -23.7558,
+                          3.41489 115 -23.7558,
+                          3.41489 107 -23.7558,
+                          3.41489 115 -23.7558,
+                          -3.41489 115 -23.7558,
+                          9.97006 107 -21.831,
+                          3.41489 115 -23.7558,
+                          3.41489 107 -23.7558,
+                          -38.2912 115 -18.4401,
+                          -9.97006 115 -21.831,
+                          -3.41489 115 -23.7558,
+                          -3.41489 107 -23.7558,
+                          -3.41489 115 -23.7558,
+                          -9.97006 115 -21.831,
+                          -33.2278 115 -26.4983,
+                          -38.2912 115 -18.4401,
+                          -3.41489 115 -23.7558,
+                          33.2278 115 -26.4983,
+                          -33.2278 115 -26.4983,
+                          -3.41489 115 -23.7558,
+                          3.41489 107 -23.7558,
+                          -3.41489 115 -23.7558,
+                          -3.41489 107 -23.7558,
+                          -38.2912 115 -18.4401,
+                          -15.717 115 -18.1377,
+                          -9.97006 115 -21.831,
+                          -9.97006 107 -21.831,
+                          -9.97006 115 -21.831,
+                          -15.717 115 -18.1377,
+                          -3.41489 107 -23.7558,
+                          -9.97006 115 -21.831,
+                          -9.97006 107 -21.831,
+                          -41.4344 115 -9.45713,
+                          -20.1897 115 -12.9759,
+                          -15.717 115 -18.1377,
+                          -15.717 107 -18.1377,
+                          -15.717 115 -18.1377,
+                          -20.1897 115 -12.9759,
+                          -38.2912 115 -18.4401,
+                          -41.4344 115 -9.45713,
+                          -15.717 115 -18.1377,
+                          -9.97006 107 -21.831,
+                          -15.717 115 -18.1377,
+                          -15.717 107 -18.1377,
+                          -41.4344 115 -9.45713,
+                          -23.0279 115 -6.76112,
+                          -20.1897 115 -12.9759,
+                          -20.1897 107 -12.9759,
+                          -20.1897 115 -12.9759,
+                          -23.0279 115 -6.76112,
+                          -15.717 107 -18.1377,
+                          -20.1897 115 -12.9759,
+                          -20.1897 107 -12.9759,
+                          -23.0279 107 -6.76112,
+                          -23.0279 115 -6.76112,
+                          -24 115 0,
+                          -20.1897 107 -12.9759,
+                          -23.0279 115 -6.76112,
+                          -23.0279 107 -6.76112,
+                          -24 107 0,
+                          -24 115 0,
+                          -23.0279 115 6.76112,
+                          -23.0279 107 -6.76112,
+                          -24 115 0,
+                          -24 107 0,
+                          -23.0279 107 6.76112,
+                          -23.0279 115 6.76112,
+                          -20.1897 115 12.9759,
+                          -23.0279 107 6.76112,
+                          -24 107 0,
+                          -23.0279 115 6.76112,
+                          -20.1897 107 12.9759,
+                          -20.1897 115 12.9759,
+                          -15.717 115 18.1377,
+                          -20.1897 107 12.9759,
+                          -23.0279 107 6.76112,
+                          -20.1897 115 12.9759,
+                          -15.717 107 18.1377,
+                          -15.717 115 18.1377,
+                          -9.97006 115 21.831,
+                          -15.717 107 18.1377,
+                          -20.1897 107 12.9759,
+                          -15.717 115 18.1377,
+                          -9.97006 107 21.831,
+                          -9.97006 115 21.831,
+                          -3.41489 115 23.7558,
+                          -9.97006 107 21.831,
+                          -15.717 107 18.1377,
+                          -9.97006 115 21.831,
+                          -3.41489 107 23.7558,
+                          -3.41489 115 23.7558,
+                          3.41489 115 23.7558,
+                          -3.41489 107 23.7558,
+                          -9.97006 107 21.831,
+                          -3.41489 115 23.7558,
+                          3.41489 107 23.7558,
+                          3.41489 115 23.7558,
+                          9.97006 115 21.831,
+                          3.41489 107 23.7558,
+                          -3.41489 107 23.7558,
+                          3.41489 115 23.7558,
+                          9.97006 107 21.831,
+                          9.97006 115 21.831,
+                          15.717 115 18.1377,
+                          9.97006 107 21.831,
+                          3.41489 107 23.7558,
+                          9.97006 115 21.831,
+                          15.717 107 18.1377,
+                          15.717 115 18.1377,
+                          20.1897 115 12.9759,
+                          15.717 107 18.1377,
+                          9.97006 107 21.831,
+                          15.717 115 18.1377,
+                          20.1897 107 12.9759,
+                          20.1897 115 12.9759,
+                          23.0279 115 6.76112,
+                          20.1897 107 12.9759,
+                          15.717 107 18.1377,
+                          20.1897 115 12.9759,
+                          23.0279 107 6.76112,
+                          20.1897 107 12.9759,
+                          23.0279 115 6.76112,
+                          26.4983 115 -33.2278,
+                          -26.4983 115 -33.2278,
+                          -33.2278 115 -26.4983,
+                          33.2278 115 -26.4983,
+                          26.4983 115 -33.2278,
+                          -33.2278 115 -26.4983,
+                          18.44 115 -38.2911,
+                          -18.44 115 -38.2911,
+                          -26.4983 115 -33.2278,
+                          26.4983 115 -33.2278,
+                          18.44 115 -38.2911,
+                          -26.4983 115 -33.2278,
+                          9.45714 115 -41.4344,
+                          -9.45714 115 -41.4344,
+                          -18.44 115 -38.2911,
+                          18.44 115 -38.2911,
+                          9.45714 115 -41.4344,
+                          -18.44 115 -38.2911,
+                          9.45714 115 -41.4344,
+                          7.32747e-15 115 -42.4999,
+                          -9.45714 115 -41.4344,
+                          -8 107 0,
+                          -24 107 0,
+                          -23.0279 107 6.76112,
+                          -7.20744 107 -3.47151,
+                          -4.988 107 -6.25442,
+                          -24 107 0,
+                          -23.0279 107 -6.76112,
+                          -24 107 0,
+                          -4.988 107 -6.25442,
+                          -8 107 0,
+                          -7.20744 107 -3.47151,
+                          -24 107 0,
+                          -1.78067 107 7.79927,
+                          -23.0279 107 6.76112,
+                          -20.1897 107 12.9759,
+                          -7.20744 107 3.47151,
+                          -8 107 0,
+                          -23.0279 107 6.76112,
+                          -4.988 107 6.25442,
+                          -7.20744 107 3.47151,
+                          -23.0279 107 6.76112,
+                          -1.78067 107 7.79927,
+                          -4.988 107 6.25442,
+                          -23.0279 107 6.76112,
+                          20.1897 107 12.9759,
+                          -20.1897 107 12.9759,
+                          -15.717 107 18.1377,
+                          23.0279 107 6.76112,
+                          -20.1897 107 12.9759,
+                          20.1897 107 12.9759,
+                          1.78067 107 7.79927,
+                          -20.1897 107 12.9759,
+                          23.0279 107 6.76112,
+                          1.78067 107 7.79927,
+                          -1.78067 107 7.79927,
+                          -20.1897 107 12.9759,
+                          15.717 107 18.1377,
+                          -15.717 107 18.1377,
+                          -9.97006 107 21.831,
+                          20.1897 107 12.9759,
+                          -15.717 107 18.1377,
+                          15.717 107 18.1377,
+                          9.97006 107 21.831,
+                          -9.97006 107 21.831,
+                          -3.41489 107 23.7558,
+                          15.717 107 18.1377,
+                          -9.97006 107 21.831,
+                          9.97006 107 21.831,
+                          9.97006 107 21.831,
+                          -3.41489 107 23.7558,
+                          3.41489 107 23.7558,
+                          4.988 107 6.25442,
+                          23.0279 107 6.76112,
+                          24 107 0,
+                          4.988 107 6.25442,
+                          1.78067 107 7.79927,
+                          23.0279 107 6.76112,
+                          7.20744 107 3.47151,
+                          24 107 0,
+                          8 107 0,
+                          23.0279 107 -6.76112,
+                          8 107 0,
+                          24 107 0,
+                          7.20744 107 3.47151,
+                          4.988 107 6.25442,
+                          24 107 0,
+                          23.0279 107 -6.76112,
+                          7.20744 107 -3.47151,
+                          8 107 0,
+                          8 104 0,
+                          8 107 0,
+                          7.20744 107 -3.47151,
+                          7.20744 104 3.47151,
+                          7.20744 107 3.47151,
+                          8 107 0,
+                          8 104 0,
+                          7.20744 104 3.47151,
+                          8 107 0,
+                          23.0279 107 -6.76112,
+                          4.988 107 -6.25442,
+                          7.20744 107 -3.47151,
+                          7.20744 104 -3.47151,
+                          7.20744 107 -3.47151,
+                          4.988 107 -6.25442,
+                          7.20744 104 -3.47151,
+                          8 104 0,
+                          7.20744 107 -3.47151,
+                          23.0279 107 -6.76112,
+                          1.78067 107 -7.79927,
+                          4.988 107 -6.25442,
+                          4.988 104 -6.25442,
+                          4.988 107 -6.25442,
+                          1.78067 107 -7.79927,
+                          7.20744 104 -3.47151,
+                          4.988 107 -6.25442,
+                          4.988 104 -6.25442,
+                          20.1897 107 -12.9759,
+                          -1.78067 107 -7.79927,
+                          1.78067 107 -7.79927,
+                          1.78067 104 -7.79927,
+                          1.78067 107 -7.79927,
+                          -1.78067 107 -7.79927,
+                          23.0279 107 -6.76112,
+                          20.1897 107 -12.9759,
+                          1.78067 107 -7.79927,
+                          4.988 104 -6.25442,
+                          1.78067 107 -7.79927,
+                          1.78067 104 -7.79927,
+                          -23.0279 107 -6.76112,
+                          -4.988 107 -6.25442,
+                          -1.78067 107 -7.79927,
+                          -1.78067 104 -7.79927,
+                          -1.78067 107 -7.79927,
+                          -4.988 107 -6.25442,
+                          20.1897 107 -12.9759,
+                          -23.0279 107 -6.76112,
+                          -1.78067 107 -7.79927,
+                          1.78067 104 -7.79927,
+                          -1.78067 107 -7.79927,
+                          -1.78067 104 -7.79927,
+                          -4.988 104 -6.25442,
+                          -4.988 107 -6.25442,
+                          -7.20744 107 -3.47151,
+                          -1.78067 104 -7.79927,
+                          -4.988 107 -6.25442,
+                          -4.988 104 -6.25442,
+                          -7.20744 104 -3.47151,
+                          -7.20744 107 -3.47151,
+                          -8 107 0,
+                          -4.988 104 -6.25442,
+                          -7.20744 107 -3.47151,
+                          -7.20744 104 -3.47151,
+                          -8 104 0,
+                          -8 107 0,
+                          -7.20744 107 3.47151,
+                          -7.20744 104 -3.47151,
+                          -8 107 0,
+                          -8 104 0,
+                          -7.20744 104 3.47151,
+                          -7.20744 107 3.47151,
+                          -4.988 107 6.25442,
+                          -7.20744 104 3.47151,
+                          -8 104 0,
+                          -7.20744 107 3.47151,
+                          -4.988 104 6.25442,
+                          -4.988 107 6.25442,
+                          -1.78067 107 7.79927,
+                          -4.988 104 6.25442,
+                          -7.20744 104 3.47151,
+                          -4.988 107 6.25442,
+                          -1.78067 104 7.79927,
+                          -1.78067 107 7.79927,
+                          1.78067 107 7.79927,
+                          -1.78067 104 7.79927,
+                          -4.988 104 6.25442,
+                          -1.78067 107 7.79927,
+                          1.78067 104 7.79927,
+                          1.78067 107 7.79927,
+                          4.988 107 6.25442,
+                          1.78067 104 7.79927,
+                          -1.78067 104 7.79927,
+                          1.78067 107 7.79927,
+                          4.988 104 6.25442,
+                          4.988 107 6.25442,
+                          7.20744 107 3.47151,
+                          4.988 104 6.25442,
+                          1.78067 104 7.79927,
+                          4.988 107 6.25442,
+                          7.20744 104 3.47151,
+                          4.988 104 6.25442,
+                          7.20744 107 3.47151,
+                          20.1897 107 -12.9759,
+                          -20.1897 107 -12.9759,
+                          -23.0279 107 -6.76112,
+                          15.717 107 -18.1377,
+                          -15.717 107 -18.1377,
+                          -20.1897 107 -12.9759,
+                          20.1897 107 -12.9759,
+                          15.717 107 -18.1377,
+                          -20.1897 107 -12.9759,
+                          9.97006 107 -21.831,
+                          -9.97006 107 -21.831,
+                          -15.717 107 -18.1377,
+                          15.717 107 -18.1377,
+                          9.97006 107 -21.831,
+                          -15.717 107 -18.1377,
+                          3.41489 107 -23.7558,
+                          -3.41489 107 -23.7558,
+                          -9.97006 107 -21.831,
+                          9.97006 107 -21.831,
+                          3.41489 107 -23.7558,
+                          -9.97006 107 -21.831,
+                          -24 104 0,
+                          -8 104 0,
+                          -7.20744 104 3.47151,
+                          -24 104 0,
+                          -23.0279 104 -6.76112,
+                          -8 104 0,
+                          -7.20744 104 -3.47151,
+                          -8 104 0,
+                          -23.0279 104 -6.76112,
+                          -24 104 0,
+                          -7.20744 104 3.47151,
+                          -4.988 104 6.25442,
+                          -23.0279 104 6.76112,
+                          -4.988 104 6.25442,
+                          -1.78067 104 7.79927,
+                          -23.0279 104 6.76112,
+                          -24 104 0,
+                          -4.988 104 6.25442,
+                          20.1897 104 12.9759,
+                          -1.78067 104 7.79927,
+                          1.78067 104 7.79927,
+                          20.1897 104 12.9759,
+                          -23.0279 104 6.76112,
+                          -1.78067 104 7.79927,
+                          23.0279 104 6.76112,
+                          1.78067 104 7.79927,
+                          4.988 104 6.25442,
+                          23.0279 104 6.76112,
+                          20.1897 104 12.9759,
+                          1.78067 104 7.79927,
+                          23.0279 104 6.76112,
+                          4.988 104 6.25442,
+                          7.20744 104 3.47151,
+                          23.0279 104 6.76112,
+                          7.20744 104 3.47151,
+                          8 104 0,
+                          23.0279 104 6.76112,
+                          8 104 0,
+                          24 104 0,
+                          7.20744 104 -3.47151,
+                          24 104 0,
+                          8 104 0,
+                          4.988 104 -6.25442,
+                          23.0279 104 -6.76112,
+                          24 104 0,
+                          27 104 0,
+                          24 104 0,
+                          23.0279 104 -6.76112,
+                          26.08 104 6.98764,
+                          23.0279 104 6.76112,
+                          24 104 0,
+                          7.20744 104 -3.47151,
+                          4.988 104 -6.25442,
+                          24 104 0,
+                          26.08 104 6.98764,
+                          24 104 0,
+                          27 104 0,
+                          -20.1897 104 -12.9759,
+                          20.1897 104 -12.9759,
+                          23.0279 104 -6.76112,
+                          26.08 104 -6.98764,
+                          23.0279 104 -6.76112,
+                          20.1897 104 -12.9759,
+                          1.78067 104 -7.79927,
+                          -20.1897 104 -12.9759,
+                          23.0279 104 -6.76112,
+                          4.988 104 -6.25442,
+                          1.78067 104 -7.79927,
+                          23.0279 104 -6.76112,
+                          26.08 104 -6.98764,
+                          27 104 0,
+                          23.0279 104 -6.76112,
+                          -15.717 104 -18.1377,
+                          15.717 104 -18.1377,
+                          20.1897 104 -12.9759,
+                          23.3824 104 -13.5004,
+                          20.1897 104 -12.9759,
+                          15.717 104 -18.1377,
+                          -20.1897 104 -12.9759,
+                          -15.717 104 -18.1377,
+                          20.1897 104 -12.9759,
+                          23.3824 104 -13.5004,
+                          26.08 104 -6.98764,
+                          20.1897 104 -12.9759,
+                          -9.97006 104 -21.831,
+                          9.97006 104 -21.831,
+                          15.717 104 -18.1377,
+                          19.0919 104 -19.0919,
+                          15.717 104 -18.1377,
+                          9.97006 104 -21.831,
+                          -15.717 104 -18.1377,
+                          -9.97006 104 -21.831,
+                          15.717 104 -18.1377,
+                          19.0919 104 -19.0919,
+                          23.3824 104 -13.5004,
+                          15.717 104 -18.1377,
+                          -3.41489 104 -23.7558,
+                          3.41489 104 -23.7558,
+                          9.97006 104 -21.831,
+                          13.5004 104 -23.3824,
+                          9.97006 104 -21.831,
+                          3.41489 104 -23.7558,
+                          -9.97006 104 -21.831,
+                          -3.41489 104 -23.7558,
+                          9.97006 104 -21.831,
+                          13.5004 104 -23.3824,
+                          19.0919 104 -19.0919,
+                          9.97006 104 -21.831,
+                          -6.98764 104 -26.08,
+                          3.41489 104 -23.7558,
+                          -3.41489 104 -23.7558,
+                          -6.98764 104 -26.08,
+                          13.5004 104 -23.3824,
+                          3.41489 104 -23.7558,
+                          -13.5004 104 -23.3824,
+                          -3.41489 104 -23.7558,
+                          -9.97006 104 -21.831,
+                          -13.5004 104 -23.3824,
+                          -6.98764 104 -26.08,
+                          -3.41489 104 -23.7558,
+                          -19.0919 104 -19.0919,
+                          -9.97006 104 -21.831,
+                          -15.717 104 -18.1377,
+                          -19.0919 104 -19.0919,
+                          -13.5004 104 -23.3824,
+                          -9.97006 104 -21.831,
+                          -23.3824 104 -13.5004,
+                          -15.717 104 -18.1377,
+                          -20.1897 104 -12.9759,
+                          -23.3824 104 -13.5004,
+                          -19.0919 104 -19.0919,
+                          -15.717 104 -18.1377,
+                          -1.78067 104 -7.79927,
+                          -23.0279 104 -6.76112,
+                          -20.1897 104 -12.9759,
+                          -26.08 104 -6.98764,
+                          -20.1897 104 -12.9759,
+                          -23.0279 104 -6.76112,
+                          1.78067 104 -7.79927,
+                          -1.78067 104 -7.79927,
+                          -20.1897 104 -12.9759,
+                          -26.08 104 -6.98764,
+                          -23.3824 104 -13.5004,
+                          -20.1897 104 -12.9759,
+                          -26.08 104 -6.98764,
+                          -23.0279 104 -6.76112,
+                          -24 104 0,
+                          -4.988 104 -6.25442,
+                          -7.20744 104 -3.47151,
+                          -23.0279 104 -6.76112,
+                          -1.78067 104 -7.79927,
+                          -4.988 104 -6.25442,
+                          -23.0279 104 -6.76112,
+                          -27 104 0,
+                          -24 104 0,
+                          -23.0279 104 6.76112,
+                          -26.08 104 -6.98764,
+                          -24 104 0,
+                          -27 104 0,
+                          20.1897 104 12.9759,
+                          -20.1897 104 12.9759,
+                          -23.0279 104 6.76112,
+                          -26.08 104 6.98764,
+                          -23.0279 104 6.76112,
+                          -20.1897 104 12.9759,
+                          -27 104 0,
+                          -23.0279 104 6.76112,
+                          -26.08 104 6.98764,
+                          15.717 104 18.1377,
+                          -15.717 104 18.1377,
+                          -20.1897 104 12.9759,
+                          -23.3824 104 13.5004,
+                          -20.1897 104 12.9759,
+                          -15.717 104 18.1377,
+                          20.1897 104 12.9759,
+                          15.717 104 18.1377,
+                          -20.1897 104 12.9759,
+                          -26.08 104 6.98764,
+                          -20.1897 104 12.9759,
+                          -23.3824 104 13.5004,
+                          9.97006 104 21.831,
+                          -9.97006 104 21.831,
+                          -15.717 104 18.1377,
+                          -19.0919 104 19.0919,
+                          -15.717 104 18.1377,
+                          -9.97006 104 21.831,
+                          15.717 104 18.1377,
+                          9.97006 104 21.831,
+                          -15.717 104 18.1377,
+                          -23.3824 104 13.5004,
+                          -15.717 104 18.1377,
+                          -19.0919 104 19.0919,
+                          3.41489 104 23.7558,
+                          -3.41489 104 23.7558,
+                          -9.97006 104 21.831,
+                          -13.5004 104 23.3824,
+                          -9.97006 104 21.831,
+                          -3.41489 104 23.7558,
+                          9.97006 104 21.831,
+                          3.41489 104 23.7558,
+                          -9.97006 104 21.831,
+                          -19.0919 104 19.0919,
+                          -9.97006 104 21.831,
+                          -13.5004 104 23.3824,
+                          6.98764 104 26.08,
+                          -3.41489 104 23.7558,
+                          3.41489 104 23.7558,
+                          -13.5004 104 23.3824,
+                          -3.41489 104 23.7558,
+                          6.98764 104 26.08,
+                          13.5004 104 23.3824,
+                          3.41489 104 23.7558,
+                          9.97006 104 21.831,
+                          6.98764 104 26.08,
+                          3.41489 104 23.7558,
+                          13.5004 104 23.3824,
+                          19.0919 104 19.0919,
+                          9.97006 104 21.831,
+                          15.717 104 18.1377,
+                          13.5004 104 23.3824,
+                          9.97006 104 21.831,
+                          19.0919 104 19.0919,
+                          23.3824 104 13.5004,
+                          15.717 104 18.1377,
+                          20.1897 104 12.9759,
+                          19.0919 104 19.0919,
+                          15.717 104 18.1377,
+                          23.3824 104 13.5004,
+                          26.08 104 6.98764,
+                          20.1897 104 12.9759,
+                          23.0279 104 6.76112,
+                          23.3824 104 13.5004,
+                          20.1897 104 12.9759,
+                          26.08 104 6.98764,
+                          -6.98764 104 26.08,
+                          6.98764 104 26.08,
+                          1.65322e-15 104 27,
+                          -13.5004 104 23.3824,
+                          6.98764 104 26.08,
+                          -6.98764 104 26.08,
+                          -6.98764 104 -26.08,
+                          6.98764 104 -26.08,
+                          13.5004 104 -23.3824,
+                          -6.98764 104 -26.08,
+                          1.65322e-15 104 -27,
+                          6.98764 104 -26.08 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          1 -1.22461e-16 1.22461e-16,
+                          1 -1.22461e-16 1.22461e-16,
+                          0.974928 -1.1939e-16 -0.222521,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          0.974928 -1.1939e-16 0.222521,
+                          0.974928 -1.1939e-16 0.222521,
+                          1 -1.22461e-16 1.22461e-16,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          1 -1.22461e-16 1.22461e-16,
+                          0.974928 -1.1939e-16 0.222521,
+                          1 -1.22461e-16 1.22461e-16,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          0.974928 -1.1939e-16 -0.222521,
+                          0.974928 -1.1939e-16 -0.222521,
+                          0.900969 -1.10333e-16 -0.433884,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          0.974928 -1.1939e-16 -0.222521,
+                          1 -1.22461e-16 1.22461e-16,
+                          0.974928 -1.1939e-16 -0.222521,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          0.900969 -1.10333e-16 -0.433884,
+                          0.900969 -1.10333e-16 -0.433884,
+                          0.781832 -9.57436e-17 -0.62349,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          0.974928 -1.1939e-16 -0.222521,
+                          0.900969 -1.10333e-16 -0.433884,
+                          0.900969 -1.10333e-16 -0.433884,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          0.781832 -9.57436e-17 -0.62349,
+                          0.781832 -9.57436e-17 -0.62349,
+                          0.62349 -7.6353e-17 -0.781832,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          0.900969 -1.10333e-16 -0.433884,
+                          0.781832 -9.57436e-17 -0.62349,
+                          0.781832 -9.57436e-17 -0.62349,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          0.62349 -7.6353e-17 -0.781832,
+                          0.62349 -7.6353e-17 -0.781832,
+                          0.433884 -5.31337e-17 -0.900969,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          0.781832 -9.57436e-17 -0.62349,
+                          0.62349 -7.6353e-17 -0.781832,
+                          0.62349 -7.6353e-17 -0.781832,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          0.433884 -5.31337e-17 -0.900969,
+                          0.433884 -5.31337e-17 -0.900969,
+                          0.222521 -2.72501e-17 -0.974928,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          0.62349 -7.6353e-17 -0.781832,
+                          0.433884 -5.31337e-17 -0.900969,
+                          0.433884 -5.31337e-17 -0.900969,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          0.222521 -2.72501e-17 -0.974928,
+                          0.222521 -2.72501e-17 -0.974928,
+                          1.83691e-16 0 -1,
+                          0.433884 -5.31337e-17 -0.900969,
+                          0.222521 -2.72501e-17 -0.974928,
+                          0.222521 -2.72501e-17 -0.974928,
+                          1.83691e-16 0 -1,
+                          1.83691e-16 0 -1,
+                          -0.222521 2.72501e-17 -0.974928,
+                          0.222521 -2.72501e-17 -0.974928,
+                          1.83691e-16 0 -1,
+                          1.83691e-16 0 -1,
+                          -0.222521 2.72501e-17 -0.974928,
+                          -0.222521 2.72501e-17 -0.974928,
+                          -0.433884 5.31337e-17 -0.900969,
+                          1.83691e-16 0 -1,
+                          -0.222521 2.72501e-17 -0.974928,
+                          -0.222521 2.72501e-17 -0.974928,
+                          -0.433884 5.31337e-17 -0.900969,
+                          -0.433884 5.31337e-17 -0.900969,
+                          -0.62349 7.6353e-17 -0.781832,
+                          -0.222521 2.72501e-17 -0.974928,
+                          -0.433884 5.31337e-17 -0.900969,
+                          -0.433884 5.31337e-17 -0.900969,
+                          -0.62349 7.6353e-17 -0.781832,
+                          -0.62349 7.6353e-17 -0.781832,
+                          -0.781832 9.57436e-17 -0.62349,
+                          -0.433884 5.31337e-17 -0.900969,
+                          -0.62349 7.6353e-17 -0.781832,
+                          -0.62349 7.6353e-17 -0.781832,
+                          -0.781832 9.57436e-17 -0.62349,
+                          -0.781832 9.57436e-17 -0.62349,
+                          -0.900969 1.10333e-16 -0.433884,
+                          -0.62349 7.6353e-17 -0.781832,
+                          -0.781832 9.57436e-17 -0.62349,
+                          -0.781832 9.57436e-17 -0.62349,
+                          -0.900969 1.10333e-16 -0.433884,
+                          -0.900969 1.10333e-16 -0.433884,
+                          -0.974928 1.1939e-16 -0.222521,
+                          -0.781832 9.57436e-17 -0.62349,
+                          -0.900969 1.10333e-16 -0.433884,
+                          -0.900969 1.10333e-16 -0.433884,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -0.974928 1.1939e-16 -0.222521,
+                          -0.974928 1.1939e-16 -0.222521,
+                          -1 1.22461e-16 -2.44921e-16,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -0.900969 1.10333e-16 -0.433884,
+                          -0.974928 1.1939e-16 -0.222521,
+                          -0.974928 1.1939e-16 -0.222521,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1 1.22461e-16 0,
+                          -1 1.22461e-16 0,
+                          -0.974928 1.1939e-16 0.222521,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -0.974928 1.1939e-16 -0.222521,
+                          -1 1.22461e-16 -2.44921e-16,
+                          -1 1.22461e-16 -2.44921e-16,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -0.974928 1.1939e-16 0.222521,
+                          -0.974928 1.1939e-16 0.222521,
+                          -0.900969 1.10333e-16 0.433884,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -0.974928 1.1939e-16 0.222521,
+                          -1 1.22461e-16 0,
+                          -0.974928 1.1939e-16 0.222521,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -0.900969 1.10333e-16 0.433884,
+                          -0.900969 1.10333e-16 0.433884,
+                          -0.781832 9.57436e-17 0.62349,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -0.900969 1.10333e-16 0.433884,
+                          -0.974928 1.1939e-16 0.222521,
+                          -0.900969 1.10333e-16 0.433884,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -0.781832 9.57436e-17 0.62349,
+                          -0.781832 9.57436e-17 0.62349,
+                          -0.62349 7.6353e-17 0.781832,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -0.781832 9.57436e-17 0.62349,
+                          -0.900969 1.10333e-16 0.433884,
+                          -0.781832 9.57436e-17 0.62349,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -0.62349 7.6353e-17 0.781832,
+                          -0.62349 7.6353e-17 0.781832,
+                          -0.433884 5.31337e-17 0.900969,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -0.62349 7.6353e-17 0.781832,
+                          -0.781832 9.57436e-17 0.62349,
+                          -0.62349 7.6353e-17 0.781832,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -0.433884 5.31337e-17 0.900969,
+                          -0.433884 5.31337e-17 0.900969,
+                          -0.222521 2.72501e-17 0.974928,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -0.433884 5.31337e-17 0.900969,
+                          -0.62349 7.6353e-17 0.781832,
+                          -0.433884 5.31337e-17 0.900969,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -0.222521 2.72501e-17 0.974928,
+                          -0.222521 2.72501e-17 0.974928,
+                          -6.12303e-17 0 1,
+                          -0.222521 2.72501e-17 0.974928,
+                          -0.433884 5.31337e-17 0.900969,
+                          -0.222521 2.72501e-17 0.974928,
+                          -6.12303e-17 0 1,
+                          -6.12303e-17 0 1,
+                          0.222521 -2.72501e-17 0.974928,
+                          -6.12303e-17 0 1,
+                          -0.222521 2.72501e-17 0.974928,
+                          -6.12303e-17 0 1,
+                          0.222521 -2.72501e-17 0.974928,
+                          0.222521 -2.72501e-17 0.974928,
+                          0.433884 -5.31337e-17 0.900969,
+                          0.222521 -2.72501e-17 0.974928,
+                          -6.12303e-17 0 1,
+                          0.222521 -2.72501e-17 0.974928,
+                          0.433884 -5.31337e-17 0.900969,
+                          0.433884 -5.31337e-17 0.900969,
+                          0.62349 -7.6353e-17 0.781832,
+                          0.433884 -5.31337e-17 0.900969,
+                          0.222521 -2.72501e-17 0.974928,
+                          0.433884 -5.31337e-17 0.900969,
+                          0.62349 -7.6353e-17 0.781832,
+                          0.62349 -7.6353e-17 0.781832,
+                          0.781832 -9.57436e-17 0.62349,
+                          0.62349 -7.6353e-17 0.781832,
+                          0.433884 -5.31337e-17 0.900969,
+                          0.62349 -7.6353e-17 0.781832,
+                          0.781832 -9.57436e-17 0.62349,
+                          0.781832 -9.57436e-17 0.62349,
+                          0.900969 -1.10333e-16 0.433884,
+                          0.781832 -9.57436e-17 0.62349,
+                          0.62349 -7.6353e-17 0.781832,
+                          0.781832 -9.57436e-17 0.62349,
+                          0.900969 -1.10333e-16 0.433884,
+                          0.900969 -1.10333e-16 0.433884,
+                          0.974928 -1.1939e-16 0.222521,
+                          0.900969 -1.10333e-16 0.433884,
+                          0.781832 -9.57436e-17 0.62349,
+                          0.900969 -1.10333e-16 0.433884,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          0.974928 -1.1939e-16 0.222521,
+                          0.900969 -1.10333e-16 0.433884,
+                          0.974928 -1.1939e-16 0.222521,
+                          -1 1.22461e-16 0,
+                          -1 1.22461e-16 1.22461e-16,
+                          -0.866025 1.06054e-16 -0.5,
+                          -0.866025 1.06054e-16 0.5,
+                          -0.866025 1.06054e-16 0.5,
+                          -1 1.22461e-16 2.44921e-16,
+                          -0.866025 1.06054e-16 0.5,
+                          -1 1.22461e-16 2.44921e-16,
+                          -1 1.22461e-16 2.44921e-16,
+                          -0.866025 1.06054e-16 -0.5,
+                          -0.866025 1.06054e-16 -0.5,
+                          -0.5 6.12303e-17 -0.866025,
+                          -0.866025 1.06054e-16 -0.5,
+                          -1 1.22461e-16 0,
+                          -0.866025 1.06054e-16 -0.5,
+                          -0.5 6.12303e-17 -0.866025,
+                          -0.5 6.12303e-17 -0.866025,
+                          1.60814e-16 0 -1,
+                          -0.866025 1.06054e-16 -0.5,
+                          -0.5 6.12303e-17 -0.866025,
+                          -0.5 6.12303e-17 -0.866025,
+                          1.60814e-16 0 -1,
+                          1.60814e-16 0 -1,
+                          0.5 -6.12303e-17 -0.866025,
+                          -0.5 6.12303e-17 -0.866025,
+                          1.60814e-16 0 -1,
+                          1.60814e-16 0 -1,
+                          0.5 -6.12303e-17 -0.866025,
+                          0.5 -6.12303e-17 -0.866025,
+                          0.866025 -1.06054e-16 -0.5,
+                          1.60814e-16 0 -1,
+                          0.5 -6.12303e-17 -0.866025,
+                          0.5 -6.12303e-17 -0.866025,
+                          0.866025 -1.06054e-16 -0.5,
+                          0.866025 -1.06054e-16 -0.5,
+                          1 -1.22461e-16 -1.22461e-16,
+                          0.5 -6.12303e-17 -0.866025,
+                          0.866025 -1.06054e-16 -0.5,
+                          0.866025 -1.06054e-16 -0.5,
+                          1 -1.22461e-16 -1.22461e-16,
+                          1 -1.22461e-16 -1.22461e-16,
+                          0.866025 -1.06054e-16 0.5,
+                          0.866025 -1.06054e-16 -0.5,
+                          1 -1.22461e-16 -1.22461e-16,
+                          1 -1.22461e-16 -1.22461e-16,
+                          0.866025 -1.06054e-16 0.5,
+                          0.866025 -1.06054e-16 0.5,
+                          0.5 -6.12303e-17 0.866025,
+                          1 -1.22461e-16 -1.22461e-16,
+                          0.866025 -1.06054e-16 0.5,
+                          0.866025 -1.06054e-16 0.5,
+                          0.5 -6.12303e-17 0.866025,
+                          0.5 -6.12303e-17 0.866025,
+                          1.83691e-16 0 1,
+                          0.866025 -1.06054e-16 0.5,
+                          0.5 -6.12303e-17 0.866025,
+                          0.5 -6.12303e-17 0.866025,
+                          1.83691e-16 0 1,
+                          1.83691e-16 0 1,
+                          -0.5 6.12303e-17 0.866025,
+                          0.5 -6.12303e-17 0.866025,
+                          1.83691e-16 0 1,
+                          1.83691e-16 0 1,
+                          -0.5 6.12303e-17 0.866025,
+                          -0.5 6.12303e-17 0.866025,
+                          -0.866025 1.06054e-16 0.5,
+                          1.83691e-16 0 1,
+                          -0.5 6.12303e-17 0.866025,
+                          -0.5 6.12303e-17 0.866025,
+                          -0.5 6.12303e-17 0.866025,
+                          -0.866025 1.06054e-16 0.5,
+                          -0.866025 1.06054e-16 0.5,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0,
+                          1.22461e-16 1 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -41.9218 181 -9.56839,
+                          41.9218 181 -9.56839,
+                          43 181 0,
+                          43 188 0,
+                          43 181 0,
+                          41.9218 181 -9.56839,
+                          -1.35542e-15 181 -3.99968,
+                          -41.9218 181 -9.56839,
+                          43 181 0,
+                          4 181 -4.89836e-16,
+                          43 181 0,
+                          41.9218 181 9.56839,
+                          41.9218 188 9.56839,
+                          41.9218 181 9.56839,
+                          43 181 0,
+                          3.46445 181 -1.9992,
+                          43 181 0,
+                          4 181 -4.89836e-16,
+                          2.00048 181 -3.46353,
+                          -1.35542e-15 181 -3.99968,
+                          43 181 0,
+                          3.46445 181 -1.9992,
+                          2.00048 181 -3.46353,
+                          43 181 0,
+                          43 188 0,
+                          41.9218 188 9.56839,
+                          43 181 0,
+                          -38.7417 181 -18.657,
+                          38.7417 181 -18.657,
+                          41.9218 181 -9.56839,
+                          41.9218 188 -9.56839,
+                          41.9218 181 -9.56839,
+                          38.7417 181 -18.657,
+                          -41.9218 181 -9.56839,
+                          -38.7417 181 -18.657,
+                          41.9218 181 -9.56839,
+                          41.9218 188 -9.56839,
+                          43 188 0,
+                          41.9218 181 -9.56839,
+                          -33.6187 181 -26.81,
+                          33.6187 181 -26.81,
+                          38.7417 181 -18.657,
+                          38.7417 188 -18.657,
+                          38.7417 181 -18.657,
+                          33.6187 181 -26.81,
+                          -38.7417 181 -18.657,
+                          -33.6187 181 -26.81,
+                          38.7417 181 -18.657,
+                          41.9218 188 -9.56839,
+                          38.7417 181 -18.657,
+                          38.7417 188 -18.657,
+                          -26.8101 181 -33.6188,
+                          26.8101 181 -33.6188,
+                          33.6187 181 -26.81,
+                          33.6187 188 -26.81,
+                          33.6187 181 -26.81,
+                          26.8101 181 -33.6188,
+                          -33.6187 181 -26.81,
+                          -26.8101 181 -33.6188,
+                          33.6187 181 -26.81,
+                          38.7417 188 -18.657,
+                          33.6187 181 -26.81,
+                          33.6187 188 -26.81,
+                          -18.657 181 -38.7416,
+                          18.657 181 -38.7416,
+                          26.8101 181 -33.6188,
+                          26.8101 188 -33.6188,
+                          26.8101 181 -33.6188,
+                          18.657 181 -38.7416,
+                          -26.8101 181 -33.6188,
+                          -18.657 181 -38.7416,
+                          26.8101 181 -33.6188,
+                          33.6187 188 -26.81,
+                          26.8101 181 -33.6188,
+                          26.8101 188 -33.6188,
+                          -9.5684 181 -41.9219,
+                          9.5684 181 -41.9219,
+                          18.657 181 -38.7416,
+                          18.657 188 -38.7416,
+                          18.657 181 -38.7416,
+                          9.5684 181 -41.9219,
+                          -18.657 181 -38.7416,
+                          -9.5684 181 -41.9219,
+                          18.657 181 -38.7416,
+                          26.8101 188 -33.6188,
+                          18.657 181 -38.7416,
+                          18.657 188 -38.7416,
+                          -9.5684 181 -41.9219,
+                          6.58267e-15 181 -42.9999,
+                          9.5684 181 -41.9219,
+                          9.5684 188 -41.9219,
+                          9.5684 181 -41.9219,
+                          6.58267e-15 181 -42.9999,
+                          18.657 188 -38.7416,
+                          9.5684 181 -41.9219,
+                          9.5684 188 -41.9219,
+                          7.4399e-15 188 -42.9999,
+                          6.58267e-15 181 -42.9999,
+                          -9.5684 181 -41.9219,
+                          9.5684 188 -41.9219,
+                          6.58267e-15 181 -42.9999,
+                          7.4399e-15 188 -42.9999,
+                          -9.5684 188 -41.9219,
+                          -9.5684 181 -41.9219,
+                          -18.657 181 -38.7416,
+                          7.4399e-15 188 -42.9999,
+                          -9.5684 181 -41.9219,
+                          -9.5684 188 -41.9219,
+                          -18.657 188 -38.7416,
+                          -18.657 181 -38.7416,
+                          -26.8101 181 -33.6188,
+                          -9.5684 188 -41.9219,
+                          -18.657 181 -38.7416,
+                          -18.657 188 -38.7416,
+                          -26.8101 188 -33.6188,
+                          -26.8101 181 -33.6188,
+                          -33.6187 181 -26.81,
+                          -18.657 188 -38.7416,
+                          -26.8101 181 -33.6188,
+                          -26.8101 188 -33.6188,
+                          -33.6187 188 -26.81,
+                          -33.6187 181 -26.81,
+                          -38.7417 181 -18.657,
+                          -26.8101 188 -33.6188,
+                          -33.6187 181 -26.81,
+                          -33.6187 188 -26.81,
+                          -38.7417 188 -18.657,
+                          -38.7417 181 -18.657,
+                          -41.9218 181 -9.56839,
+                          -33.6187 188 -26.81,
+                          -38.7417 181 -18.657,
+                          -38.7417 188 -18.657,
+                          -4 181 4.89849e-16,
+                          -43 181 0,
+                          -41.9218 181 -9.56839,
+                          -41.9218 188 -9.56839,
+                          -41.9218 181 -9.56839,
+                          -43 181 0,
+                          -3.46445 181 -1.9992,
+                          -4 181 4.89849e-16,
+                          -41.9218 181 -9.56839,
+                          -2.00048 181 -3.46353,
+                          -3.46445 181 -1.9992,
+                          -41.9218 181 -9.56839,
+                          -1.35542e-15 181 -3.99968,
+                          -2.00048 181 -3.46353,
+                          -41.9218 181 -9.56839,
+                          -38.7417 188 -18.657,
+                          -41.9218 181 -9.56839,
+                          -41.9218 188 -9.56839,
+                          41.9218 181 9.56839,
+                          -41.9218 181 9.56839,
+                          -43 181 0,
+                          -43 188 0,
+                          -43 181 0,
+                          -41.9218 181 9.56839,
+                          -1.60522e-15 181 3.99968,
+                          41.9218 181 9.56839,
+                          -43 181 0,
+                          -2.00048 181 3.46353,
+                          -1.60522e-15 181 3.99968,
+                          -43 181 0,
+                          -3.46445 181 1.9992,
+                          -2.00048 181 3.46353,
+                          -43 181 0,
+                          -4 181 4.89849e-16,
+                          -3.46445 181 1.9992,
+                          -43 181 0,
+                          -41.9218 188 -9.56839,
+                          -43 181 0,
+                          -43 188 0,
+                          38.7417 181 18.657,
+                          -38.7417 181 18.657,
+                          -41.9218 181 9.56839,
+                          -41.9218 188 9.56839,
+                          -41.9218 181 9.56839,
+                          -38.7417 181 18.657,
+                          41.9218 181 9.56839,
+                          38.7417 181 18.657,
+                          -41.9218 181 9.56839,
+                          -41.9218 188 9.56839,
+                          -43 188 0,
+                          -41.9218 181 9.56839,
+                          33.6187 181 26.81,
+                          -33.6187 181 26.81,
+                          -38.7417 181 18.657,
+                          -38.7417 188 18.657,
+                          -38.7417 181 18.657,
+                          -33.6187 181 26.81,
+                          38.7417 181 18.657,
+                          33.6187 181 26.81,
+                          -38.7417 181 18.657,
+                          -38.7417 188 18.657,
+                          -41.9218 188 9.56839,
+                          -38.7417 181 18.657,
+                          26.8101 181 33.6188,
+                          -26.8101 181 33.6188,
+                          -33.6187 181 26.81,
+                          -33.6187 188 26.81,
+                          -33.6187 181 26.81,
+                          -26.8101 181 33.6188,
+                          33.6187 181 26.81,
+                          26.8101 181 33.6188,
+                          -33.6187 181 26.81,
+                          -33.6187 188 26.81,
+                          -38.7417 188 18.657,
+                          -33.6187 181 26.81,
+                          18.657 181 38.7416,
+                          -18.657 181 38.7416,
+                          -26.8101 181 33.6188,
+                          -26.8101 188 33.6188,
+                          -26.8101 181 33.6188,
+                          -18.657 181 38.7416,
+                          26.8101 181 33.6188,
+                          18.657 181 38.7416,
+                          -26.8101 181 33.6188,
+                          -26.8101 188 33.6188,
+                          -33.6187 188 26.81,
+                          -26.8101 181 33.6188,
+                          9.5684 181 41.9219,
+                          -9.5684 181 41.9219,
+                          -18.657 181 38.7416,
+                          -18.657 188 38.7416,
+                          -18.657 181 38.7416,
+                          -9.5684 181 41.9219,
+                          18.657 181 38.7416,
+                          9.5684 181 41.9219,
+                          -18.657 181 38.7416,
+                          -18.657 188 38.7416,
+                          -26.8101 188 33.6188,
+                          -18.657 181 38.7416,
+                          9.5684 181 41.9219,
+                          6.58267e-15 181 42.9999,
+                          -9.5684 181 41.9219,
+                          -9.5684 188 41.9219,
+                          -9.5684 181 41.9219,
+                          6.58267e-15 181 42.9999,
+                          -9.5684 188 41.9219,
+                          -18.657 188 38.7416,
+                          -9.5684 181 41.9219,
+                          7.4399e-15 188 42.9999,
+                          6.58267e-15 181 42.9999,
+                          9.5684 181 41.9219,
+                          7.4399e-15 188 42.9999,
+                          -9.5684 188 41.9219,
+                          6.58267e-15 181 42.9999,
+                          9.5684 188 41.9219,
+                          9.5684 181 41.9219,
+                          18.657 181 38.7416,
+                          9.5684 188 41.9219,
+                          7.4399e-15 188 42.9999,
+                          9.5684 181 41.9219,
+                          18.657 188 38.7416,
+                          18.657 181 38.7416,
+                          26.8101 181 33.6188,
+                          18.657 188 38.7416,
+                          9.5684 188 41.9219,
+                          18.657 181 38.7416,
+                          26.8101 188 33.6188,
+                          26.8101 181 33.6188,
+                          33.6187 181 26.81,
+                          26.8101 188 33.6188,
+                          18.657 188 38.7416,
+                          26.8101 181 33.6188,
+                          33.6187 188 26.81,
+                          33.6187 181 26.81,
+                          38.7417 181 18.657,
+                          33.6187 188 26.81,
+                          26.8101 188 33.6188,
+                          33.6187 181 26.81,
+                          38.7417 188 18.657,
+                          38.7417 181 18.657,
+                          41.9218 181 9.56839,
+                          38.7417 188 18.657,
+                          33.6187 188 26.81,
+                          38.7417 181 18.657,
+                          3.46445 181 1.9992,
+                          4 181 -4.89836e-16,
+                          41.9218 181 9.56839,
+                          2.00048 181 3.46353,
+                          3.46445 181 1.9992,
+                          41.9218 181 9.56839,
+                          -1.60522e-15 181 3.99968,
+                          2.00048 181 3.46353,
+                          41.9218 181 9.56839,
+                          41.9218 188 9.56839,
+                          38.7417 188 18.657,
+                          41.9218 181 9.56839,
+                          4 188 -4.89836e-16,
+                          4 181 -4.89836e-16,
+                          3.46445 181 1.9992,
+                          3.46445 188 -1.9992,
+                          3.46445 181 -1.9992,
+                          4 181 -4.89836e-16,
+                          3.46445 188 -1.9992,
+                          4 181 -4.89836e-16,
+                          4 188 -4.89836e-16,
+                          3.46445 188 1.9992,
+                          3.46445 181 1.9992,
+                          2.00048 181 3.46353,
+                          3.46445 188 1.9992,
+                          4 188 -4.89836e-16,
+                          3.46445 181 1.9992,
+                          2.00048 188 3.46353,
+                          2.00048 181 3.46353,
+                          -1.60522e-15 181 3.99968,
+                          3.46445 188 1.9992,
+                          2.00048 181 3.46353,
+                          2.00048 188 3.46353,
+                          -8.0351e-16 188 3.99968,
+                          -1.60522e-15 181 3.99968,
+                          -2.00048 181 3.46353,
+                          2.00048 188 3.46353,
+                          -1.60522e-15 181 3.99968,
+                          -8.0351e-16 188 3.99968,
+                          -2.00048 188 3.46353,
+                          -2.00048 181 3.46353,
+                          -3.46445 181 1.9992,
+                          -8.0351e-16 188 3.99968,
+                          -2.00048 181 3.46353,
+                          -2.00048 188 3.46353,
+                          -3.46445 188 1.9992,
+                          -3.46445 181 1.9992,
+                          -4 181 4.89849e-16,
+                          -2.00048 188 3.46353,
+                          -3.46445 181 1.9992,
+                          -3.46445 188 1.9992,
+                          -4 188 4.89849e-16,
+                          -4 181 4.89849e-16,
+                          -3.46445 181 -1.9992,
+                          -3.46445 188 1.9992,
+                          -4 181 4.89849e-16,
+                          -4 188 4.89849e-16,
+                          -3.46445 188 -1.9992,
+                          -3.46445 181 -1.9992,
+                          -2.00048 181 -3.46353,
+                          -4 188 4.89849e-16,
+                          -3.46445 181 -1.9992,
+                          -3.46445 188 -1.9992,
+                          -2.00048 188 -3.46353,
+                          -2.00048 181 -3.46353,
+                          -1.35542e-15 181 -3.99968,
+                          -3.46445 188 -1.9992,
+                          -2.00048 181 -3.46353,
+                          -2.00048 188 -3.46353,
+                          -5.5371e-16 188 -3.99968,
+                          -1.35542e-15 181 -3.99968,
+                          2.00048 181 -3.46353,
+                          -2.00048 188 -3.46353,
+                          -1.35542e-15 181 -3.99968,
+                          -5.5371e-16 188 -3.99968,
+                          2.00048 188 -3.46353,
+                          2.00048 181 -3.46353,
+                          3.46445 181 -1.9992,
+                          -5.5371e-16 188 -3.99968,
+                          2.00048 181 -3.46353,
+                          2.00048 188 -3.46353,
+                          2.00048 188 -3.46353,
+                          3.46445 181 -1.9992,
+                          3.46445 188 -1.9992,
+                          -4 188 4.89849e-16,
+                          -43 188 0,
+                          -41.9218 188 9.56839,
+                          41.9218 188 -9.56839,
+                          -41.9218 188 -9.56839,
+                          -43 188 0,
+                          -5.5371e-16 188 -3.99968,
+                          41.9218 188 -9.56839,
+                          -43 188 0,
+                          -2.00048 188 -3.46353,
+                          -5.5371e-16 188 -3.99968,
+                          -43 188 0,
+                          -3.46445 188 -1.9992,
+                          -2.00048 188 -3.46353,
+                          -43 188 0,
+                          -4 188 4.89849e-16,
+                          -3.46445 188 -1.9992,
+                          -43 188 0,
+                          41.9218 188 9.56839,
+                          -41.9218 188 9.56839,
+                          -38.7417 188 18.657,
+                          43 188 0,
+                          -41.9218 188 9.56839,
+                          41.9218 188 9.56839,
+                          -8.0351e-16 188 3.99968,
+                          -41.9218 188 9.56839,
+                          43 188 0,
+                          -3.46445 188 1.9992,
+                          -4 188 4.89849e-16,
+                          -41.9218 188 9.56839,
+                          -2.00048 188 3.46353,
+                          -3.46445 188 1.9992,
+                          -41.9218 188 9.56839,
+                          -8.0351e-16 188 3.99968,
+                          -2.00048 188 3.46353,
+                          -41.9218 188 9.56839,
+                          38.7417 188 18.657,
+                          -38.7417 188 18.657,
+                          -33.6187 188 26.81,
+                          41.9218 188 9.56839,
+                          -38.7417 188 18.657,
+                          38.7417 188 18.657,
+                          33.6187 188 26.81,
+                          -33.6187 188 26.81,
+                          -26.8101 188 33.6188,
+                          38.7417 188 18.657,
+                          -33.6187 188 26.81,
+                          33.6187 188 26.81,
+                          26.8101 188 33.6188,
+                          -26.8101 188 33.6188,
+                          -18.657 188 38.7416,
+                          33.6187 188 26.81,
+                          -26.8101 188 33.6188,
+                          26.8101 188 33.6188,
+                          18.657 188 38.7416,
+                          -18.657 188 38.7416,
+                          -9.5684 188 41.9219,
+                          26.8101 188 33.6188,
+                          -18.657 188 38.7416,
+                          18.657 188 38.7416,
+                          9.5684 188 41.9219,
+                          -9.5684 188 41.9219,
+                          7.4399e-15 188 42.9999,
+                          18.657 188 38.7416,
+                          -9.5684 188 41.9219,
+                          9.5684 188 41.9219,
+                          4 188 -4.89836e-16,
+                          43 188 0,
+                          41.9218 188 -9.56839,
+                          3.46445 188 1.9992,
+                          43 188 0,
+                          4 188 -4.89836e-16,
+                          2.00048 188 3.46353,
+                          -8.0351e-16 188 3.99968,
+                          43 188 0,
+                          3.46445 188 1.9992,
+                          2.00048 188 3.46353,
+                          43 188 0,
+                          38.7417 188 -18.657,
+                          -38.7417 188 -18.657,
+                          -41.9218 188 -9.56839,
+                          41.9218 188 -9.56839,
+                          38.7417 188 -18.657,
+                          -41.9218 188 -9.56839,
+                          33.6187 188 -26.81,
+                          -33.6187 188 -26.81,
+                          -38.7417 188 -18.657,
+                          38.7417 188 -18.657,
+                          33.6187 188 -26.81,
+                          -38.7417 188 -18.657,
+                          26.8101 188 -33.6188,
+                          -26.8101 188 -33.6188,
+                          -33.6187 188 -26.81,
+                          33.6187 188 -26.81,
+                          26.8101 188 -33.6188,
+                          -33.6187 188 -26.81,
+                          18.657 188 -38.7416,
+                          -18.657 188 -38.7416,
+                          -26.8101 188 -33.6188,
+                          26.8101 188 -33.6188,
+                          18.657 188 -38.7416,
+                          -26.8101 188 -33.6188,
+                          9.5684 188 -41.9219,
+                          -9.5684 188 -41.9219,
+                          -18.657 188 -38.7416,
+                          18.657 188 -38.7416,
+                          9.5684 188 -41.9219,
+                          -18.657 188 -38.7416,
+                          9.5684 188 -41.9219,
+                          7.4399e-15 188 -42.9999,
+                          -9.5684 188 -41.9219,
+                          3.46445 188 -1.9992,
+                          4 188 -4.89836e-16,
+                          41.9218 188 -9.56839,
+                          2.00048 188 -3.46353,
+                          3.46445 188 -1.9992,
+                          41.9218 188 -9.56839,
+                          -5.5371e-16 188 -3.99968,
+                          2.00048 188 -3.46353,
+                          41.9218 188 -9.56839 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          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 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          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,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 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 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,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -1.83691e-16 1,
+                          -1.22461e-16 -1.83691e-16 1,
+                          0.34202 -1.72613e-16 0.939693,
+                          -0.34202 -1.72613e-16 0.939693,
+                          -0.34202 -1.72613e-16 0.939693,
+                          -2.44921e-16 -1.83691e-16 1,
+                          -0.34202 -1.72613e-16 0.939693,
+                          -2.44921e-16 -1.83691e-16 1,
+                          -2.44921e-16 -1.83691e-16 1,
+                          0.34202 -1.72613e-16 0.939693,
+                          0.34202 -1.72613e-16 0.939693,
+                          0.642788 -1.40715e-16 0.766044,
+                          0.34202 -1.72613e-16 0.939693,
+                          0 -1.83691e-16 1,
+                          0.34202 -1.72613e-16 0.939693,
+                          0.642788 -1.40715e-16 0.766044,
+                          0.642788 -1.40715e-16 0.766044,
+                          0.866025 -9.18455e-17 0.5,
+                          0.34202 -1.72613e-16 0.939693,
+                          0.642788 -1.40715e-16 0.766044,
+                          0.642788 -1.40715e-16 0.766044,
+                          0.866025 -9.18455e-17 0.5,
+                          0.866025 -9.18455e-17 0.5,
+                          0.984808 -3.18976e-17 0.173648,
+                          0.642788 -1.40715e-16 0.766044,
+                          0.866025 -9.18455e-17 0.5,
+                          0.866025 -9.18455e-17 0.5,
+                          0.984808 -3.18976e-17 0.173648,
+                          0.984808 -3.18976e-17 0.173648,
+                          0.984808 3.18976e-17 -0.173648,
+                          0.866025 -9.18455e-17 0.5,
+                          0.984808 -3.18976e-17 0.173648,
+                          0.984808 -3.18976e-17 0.173648,
+                          0.984808 3.18976e-17 -0.173648,
+                          0.984808 3.18976e-17 -0.173648,
+                          0.866025 9.18455e-17 -0.5,
+                          0.984808 -3.18976e-17 0.173648,
+                          0.984808 3.18976e-17 -0.173648,
+                          0.984808 3.18976e-17 -0.173648,
+                          0.866025 9.18455e-17 -0.5,
+                          0.866025 9.18455e-17 -0.5,
+                          0.642788 1.40715e-16 -0.766044,
+                          0.984808 3.18976e-17 -0.173648,
+                          0.866025 9.18455e-17 -0.5,
+                          0.866025 9.18455e-17 -0.5,
+                          0.642788 1.40715e-16 -0.766044,
+                          0.642788 1.40715e-16 -0.766044,
+                          0.34202 1.72613e-16 -0.939693,
+                          0.866025 9.18455e-17 -0.5,
+                          0.642788 1.40715e-16 -0.766044,
+                          0.642788 1.40715e-16 -0.766044,
+                          0.34202 1.72613e-16 -0.939693,
+                          0.34202 1.72613e-16 -0.939693,
+                          1.22461e-16 1.83691e-16 -1,
+                          0.642788 1.40715e-16 -0.766044,
+                          0.34202 1.72613e-16 -0.939693,
+                          0.34202 1.72613e-16 -0.939693,
+                          1.22461e-16 1.83691e-16 -1,
+                          1.22461e-16 1.83691e-16 -1,
+                          -0.34202 1.72613e-16 -0.939693,
+                          0.34202 1.72613e-16 -0.939693,
+                          1.22461e-16 1.83691e-16 -1,
+                          1.22461e-16 1.83691e-16 -1,
+                          -0.34202 1.72613e-16 -0.939693,
+                          -0.34202 1.72613e-16 -0.939693,
+                          -0.642788 1.40715e-16 -0.766044,
+                          1.22461e-16 1.83691e-16 -1,
+                          -0.34202 1.72613e-16 -0.939693,
+                          -0.34202 1.72613e-16 -0.939693,
+                          -0.642788 1.40715e-16 -0.766044,
+                          -0.642788 1.40715e-16 -0.766044,
+                          -0.866025 9.18455e-17 -0.5,
+                          -0.34202 1.72613e-16 -0.939693,
+                          -0.642788 1.40715e-16 -0.766044,
+                          -0.642788 1.40715e-16 -0.766044,
+                          -0.866025 9.18455e-17 -0.5,
+                          -0.866025 9.18455e-17 -0.5,
+                          -0.984808 3.18976e-17 -0.173648,
+                          -0.642788 1.40715e-16 -0.766044,
+                          -0.866025 9.18455e-17 -0.5,
+                          -0.866025 9.18455e-17 -0.5,
+                          -0.984808 3.18976e-17 -0.173648,
+                          -0.984808 3.18976e-17 -0.173648,
+                          -0.984808 -3.18976e-17 0.173648,
+                          -0.866025 9.18455e-17 -0.5,
+                          -0.984808 3.18976e-17 -0.173648,
+                          -0.984808 3.18976e-17 -0.173648,
+                          -0.984808 -3.18976e-17 0.173648,
+                          -0.984808 -3.18976e-17 0.173648,
+                          -0.866025 -9.18455e-17 0.5,
+                          -0.984808 3.18976e-17 -0.173648,
+                          -0.984808 -3.18976e-17 0.173648,
+                          -0.984808 -3.18976e-17 0.173648,
+                          -0.866025 -9.18455e-17 0.5,
+                          -0.866025 -9.18455e-17 0.5,
+                          -0.642788 -1.40715e-16 0.766044,
+                          -0.984808 -3.18976e-17 0.173648,
+                          -0.866025 -9.18455e-17 0.5,
+                          -0.866025 -9.18455e-17 0.5,
+                          -0.642788 -1.40715e-16 0.766044,
+                          -0.642788 -1.40715e-16 0.766044,
+                          -0.34202 -1.72613e-16 0.939693,
+                          -0.866025 -9.18455e-17 0.5,
+                          -0.642788 -1.40715e-16 0.766044,
+                          -0.642788 -1.40715e-16 0.766044,
+                          -0.642788 -1.40715e-16 0.766044,
+                          -0.34202 -1.72613e-16 0.939693,
+                          -0.34202 -1.72613e-16 0.939693,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          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.22461e-16 1.83691e-16 -1,
+                          -1.22461e-16 1.83691e-16 -1,
+                          0.309017 1.747e-16 -0.951057,
+                          -0.309017 1.747e-16 -0.951057,
+                          -0.309017 1.747e-16 -0.951057,
+                          -1.22461e-16 1.83691e-16 -1,
+                          -1.22461e-16 1.83691e-16 -1,
+                          -0.309017 1.747e-16 -0.951057,
+                          -1.22461e-16 1.83691e-16 -1,
+                          0.309017 1.747e-16 -0.951057,
+                          0.309017 1.747e-16 -0.951057,
+                          0.587785 1.48609e-16 -0.809017,
+                          0.309017 1.747e-16 -0.951057,
+                          -1.22461e-16 1.83691e-16 -1,
+                          0.309017 1.747e-16 -0.951057,
+                          0.587785 1.48609e-16 -0.809017,
+                          0.587785 1.48609e-16 -0.809017,
+                          0.809017 1.07971e-16 -0.587785,
+                          0.309017 1.747e-16 -0.951057,
+                          0.587785 1.48609e-16 -0.809017,
+                          0.587785 1.48609e-16 -0.809017,
+                          0.809017 1.07971e-16 -0.587785,
+                          0.809017 1.07971e-16 -0.587785,
+                          0.951057 5.67636e-17 -0.309017,
+                          0.587785 1.48609e-16 -0.809017,
+                          0.809017 1.07971e-16 -0.587785,
+                          0.809017 1.07971e-16 -0.587785,
+                          0.951057 5.67636e-17 -0.309017,
+                          0.951057 5.67636e-17 -0.309017,
+                          1 0 -1.83691e-16,
+                          0.809017 1.07971e-16 -0.587785,
+                          0.951057 5.67636e-17 -0.309017,
+                          0.951057 5.67636e-17 -0.309017,
+                          1 0 -1.83691e-16,
+                          1 0 -1.83691e-16,
+                          0.951057 -5.67636e-17 0.309017,
+                          0.951057 5.67636e-17 -0.309017,
+                          1 0 -1.83691e-16,
+                          1 0 -1.83691e-16,
+                          0.951057 -5.67636e-17 0.309017,
+                          0.951057 -5.67636e-17 0.309017,
+                          0.809017 -1.07971e-16 0.587785,
+                          1 0 -1.83691e-16,
+                          0.951057 -5.67636e-17 0.309017,
+                          0.951057 -5.67636e-17 0.309017,
+                          0.809017 -1.07971e-16 0.587785,
+                          0.809017 -1.07971e-16 0.587785,
+                          0.587785 -1.48609e-16 0.809017,
+                          0.951057 -5.67636e-17 0.309017,
+                          0.809017 -1.07971e-16 0.587785,
+                          0.809017 -1.07971e-16 0.587785,
+                          0.587785 -1.48609e-16 0.809017,
+                          0.587785 -1.48609e-16 0.809017,
+                          0.309017 -1.747e-16 0.951057,
+                          0.809017 -1.07971e-16 0.587785,
+                          0.587785 -1.48609e-16 0.809017,
+                          0.587785 -1.48609e-16 0.809017,
+                          0.309017 -1.747e-16 0.951057,
+                          0.309017 -1.747e-16 0.951057,
+                          2.44921e-16 -1.83691e-16 1,
+                          0.587785 -1.48609e-16 0.809017,
+                          0.309017 -1.747e-16 0.951057,
+                          0.309017 -1.747e-16 0.951057,
+                          0 -1.83691e-16 1,
+                          0 -1.83691e-16 1,
+                          -0.309017 -1.747e-16 0.951057,
+                          0.309017 -1.747e-16 0.951057,
+                          2.44921e-16 -1.83691e-16 1,
+                          2.44921e-16 -1.83691e-16 1,
+                          -0.309017 -1.747e-16 0.951057,
+                          -0.309017 -1.747e-16 0.951057,
+                          -0.587785 -1.48609e-16 0.809017,
+                          -0.309017 -1.747e-16 0.951057,
+                          0 -1.83691e-16 1,
+                          -0.309017 -1.747e-16 0.951057,
+                          -0.587785 -1.48609e-16 0.809017,
+                          -0.587785 -1.48609e-16 0.809017,
+                          -0.809017 -1.07971e-16 0.587785,
+                          -0.587785 -1.48609e-16 0.809017,
+                          -0.309017 -1.747e-16 0.951057,
+                          -0.587785 -1.48609e-16 0.809017,
+                          -0.809017 -1.07971e-16 0.587785,
+                          -0.809017 -1.07971e-16 0.587785,
+                          -0.951057 -5.67636e-17 0.309017,
+                          -0.809017 -1.07971e-16 0.587785,
+                          -0.587785 -1.48609e-16 0.809017,
+                          -0.809017 -1.07971e-16 0.587785,
+                          -0.951057 -5.67636e-17 0.309017,
+                          -0.951057 -5.67636e-17 0.309017,
+                          -1 0 -3.82859e-16,
+                          -0.951057 -5.67636e-17 0.309017,
+                          -0.809017 -1.07971e-16 0.587785,
+                          -0.951057 -5.67636e-17 0.309017,
+                          -1 0 6.12303e-17,
+                          -1 0 -3.82859e-16,
+                          -0.951057 5.67636e-17 -0.309017,
+                          -1 0 6.12303e-17,
+                          -0.951057 -5.67636e-17 0.309017,
+                          -1 0 -3.82859e-16,
+                          -0.951057 5.67636e-17 -0.309017,
+                          -0.951057 5.67636e-17 -0.309017,
+                          -0.809017 1.07971e-16 -0.587785,
+                          -0.951057 5.67636e-17 -0.309017,
+                          -1 0 6.12303e-17,
+                          -0.951057 5.67636e-17 -0.309017,
+                          -0.809017 1.07971e-16 -0.587785,
+                          -0.809017 1.07971e-16 -0.587785,
+                          -0.587785 1.48609e-16 -0.809017,
+                          -0.809017 1.07971e-16 -0.587785,
+                          -0.951057 5.67636e-17 -0.309017,
+                          -0.809017 1.07971e-16 -0.587785,
+                          -0.587785 1.48609e-16 -0.809017,
+                          -0.587785 1.48609e-16 -0.809017,
+                          -0.309017 1.747e-16 -0.951057,
+                          -0.587785 1.48609e-16 -0.809017,
+                          -0.809017 1.07971e-16 -0.587785,
+                          -0.587785 1.48609e-16 -0.809017,
+                          -0.309017 1.747e-16 -0.951057,
+                          -0.587785 1.48609e-16 -0.809017,
+                          -0.309017 1.747e-16 -0.951057,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 13.4234 -152 -7.75,
+                          45.5 -152 40.5,
+                          45.5 -152 -40.5,
+                          45.5 -162 -40.5,
+                          45.5 -152 -40.5,
+                          45.5 -152 40.5,
+                          5.30131 -152 -14.5652,
+                          45.5 -152 -40.5,
+                          -45.5 -152 -40.5,
+                          -45.5 -162 -40.5,
+                          -45.5 -152 -40.5,
+                          45.5 -152 -40.5,
+                          9.96321 -152 -11.8737,
+                          13.4234 -152 -7.75,
+                          45.5 -152 -40.5,
+                          5.30131 -152 -14.5652,
+                          9.96321 -152 -11.8737,
+                          45.5 -152 -40.5,
+                          -45.5 -162 -40.5,
+                          45.5 -152 -40.5,
+                          45.5 -162 -40.5,
+                          -5.30131 -152 14.5652,
+                          -45.5 -152 40.5,
+                          45.5 -152 40.5,
+                          45.5 -162 40.5,
+                          45.5 -152 40.5,
+                          -45.5 -152 40.5,
+                          -1.89813e-15 -152 15.5,
+                          -5.30131 -152 14.5652,
+                          45.5 -152 40.5,
+                          5.30131 -152 14.5652,
+                          -1.89813e-15 -152 15.5,
+                          45.5 -152 40.5,
+                          9.96321 -152 11.8737,
+                          5.30131 -152 14.5652,
+                          45.5 -152 40.5,
+                          13.4234 -152 7.75,
+                          9.96321 -152 11.8737,
+                          45.5 -152 40.5,
+                          15.2645 -152 2.69155,
+                          13.4234 -152 7.75,
+                          45.5 -152 40.5,
+                          15.2645 -152 -2.69155,
+                          15.2645 -152 2.69155,
+                          45.5 -152 40.5,
+                          13.4234 -152 -7.75,
+                          15.2645 -152 -2.69155,
+                          45.5 -152 40.5,
+                          45.5 -162 40.5,
+                          45.5 -162 -40.5,
+                          45.5 -152 40.5,
+                          -13.4234 -152 7.75,
+                          -45.5 -152 -40.5,
+                          -45.5 -152 40.5,
+                          -45.5 -162 40.5,
+                          -45.5 -152 40.5,
+                          -45.5 -152 -40.5,
+                          -9.96321 -152 11.8737,
+                          -13.4234 -152 7.75,
+                          -45.5 -152 40.5,
+                          -5.30131 -152 14.5652,
+                          -9.96321 -152 11.8737,
+                          -45.5 -152 40.5,
+                          45.5 -162 40.5,
+                          -45.5 -152 40.5,
+                          -45.5 -162 40.5,
+                          -5.30131 -152 -14.5652,
+                          1.89815e-15 -152 -15.5,
+                          -45.5 -152 -40.5,
+                          5.30131 -152 -14.5652,
+                          -45.5 -152 -40.5,
+                          1.89815e-15 -152 -15.5,
+                          -9.96321 -152 -11.8737,
+                          -5.30131 -152 -14.5652,
+                          -45.5 -152 -40.5,
+                          -13.4234 -152 -7.75,
+                          -9.96321 -152 -11.8737,
+                          -45.5 -152 -40.5,
+                          -15.2645 -152 -2.69155,
+                          -13.4234 -152 -7.75,
+                          -45.5 -152 -40.5,
+                          -15.2645 -152 2.69155,
+                          -15.2645 -152 -2.69155,
+                          -45.5 -152 -40.5,
+                          -13.4234 -152 7.75,
+                          -15.2645 -152 2.69155,
+                          -45.5 -152 -40.5,
+                          -45.5 -162 40.5,
+                          -45.5 -152 -40.5,
+                          -45.5 -162 -40.5,
+                          1.89815e-15 -183 -15.5,
+                          1.89815e-15 -152 -15.5,
+                          -5.30131 -152 -14.5652,
+                          5.30131 -183 -14.5652,
+                          5.30131 -152 -14.5652,
+                          1.89815e-15 -152 -15.5,
+                          5.30131 -183 -14.5652,
+                          1.89815e-15 -152 -15.5,
+                          1.89815e-15 -183 -15.5,
+                          -5.30131 -183 -14.5652,
+                          -5.30131 -152 -14.5652,
+                          -9.96321 -152 -11.8737,
+                          -5.30131 -183 -14.5652,
+                          1.89815e-15 -183 -15.5,
+                          -5.30131 -152 -14.5652,
+                          -9.96321 -183 -11.8737,
+                          -9.96321 -152 -11.8737,
+                          -13.4234 -152 -7.75,
+                          -5.30131 -183 -14.5652,
+                          -9.96321 -152 -11.8737,
+                          -9.96321 -183 -11.8737,
+                          -13.4234 -183 -7.75,
+                          -13.4234 -152 -7.75,
+                          -15.2645 -152 -2.69155,
+                          -9.96321 -183 -11.8737,
+                          -13.4234 -152 -7.75,
+                          -13.4234 -183 -7.75,
+                          -15.2645 -183 -2.69155,
+                          -15.2645 -152 -2.69155,
+                          -15.2645 -152 2.69155,
+                          -13.4234 -183 -7.75,
+                          -15.2645 -152 -2.69155,
+                          -15.2645 -183 -2.69155,
+                          -15.2645 -183 2.69155,
+                          -15.2645 -152 2.69155,
+                          -13.4234 -152 7.75,
+                          -15.2645 -183 -2.69155,
+                          -15.2645 -152 2.69155,
+                          -15.2645 -183 2.69155,
+                          -13.4234 -183 7.75,
+                          -13.4234 -152 7.75,
+                          -9.96321 -152 11.8737,
+                          -15.2645 -183 2.69155,
+                          -13.4234 -152 7.75,
+                          -13.4234 -183 7.75,
+                          -9.96321 -183 11.8737,
+                          -9.96321 -152 11.8737,
+                          -5.30131 -152 14.5652,
+                          -13.4234 -183 7.75,
+                          -9.96321 -152 11.8737,
+                          -9.96321 -183 11.8737,
+                          -5.30131 -183 14.5652,
+                          -5.30131 -152 14.5652,
+                          -1.89813e-15 -152 15.5,
+                          -9.96321 -183 11.8737,
+                          -5.30131 -152 14.5652,
+                          -5.30131 -183 14.5652,
+                          -1.89813e-15 -183 15.5,
+                          -1.89813e-15 -152 15.5,
+                          5.30131 -152 14.5652,
+                          -5.30131 -183 14.5652,
+                          -1.89813e-15 -152 15.5,
+                          -1.89813e-15 -183 15.5,
+                          5.30131 -183 14.5652,
+                          5.30131 -152 14.5652,
+                          9.96321 -152 11.8737,
+                          -1.89813e-15 -183 15.5,
+                          5.30131 -152 14.5652,
+                          5.30131 -183 14.5652,
+                          9.96321 -183 11.8737,
+                          9.96321 -152 11.8737,
+                          13.4234 -152 7.75,
+                          5.30131 -183 14.5652,
+                          9.96321 -152 11.8737,
+                          9.96321 -183 11.8737,
+                          13.4234 -183 7.75,
+                          13.4234 -152 7.75,
+                          15.2645 -152 2.69155,
+                          9.96321 -183 11.8737,
+                          13.4234 -152 7.75,
+                          13.4234 -183 7.75,
+                          15.2645 -183 2.69155,
+                          15.2645 -152 2.69155,
+                          15.2645 -152 -2.69155,
+                          13.4234 -183 7.75,
+                          15.2645 -152 2.69155,
+                          15.2645 -183 2.69155,
+                          15.2645 -183 -2.69155,
+                          15.2645 -152 -2.69155,
+                          13.4234 -152 -7.75,
+                          15.2645 -183 2.69155,
+                          15.2645 -152 -2.69155,
+                          15.2645 -183 -2.69155,
+                          13.4234 -183 -7.75,
+                          13.4234 -152 -7.75,
+                          9.96321 -152 -11.8737,
+                          15.2645 -183 -2.69155,
+                          13.4234 -152 -7.75,
+                          13.4234 -183 -7.75,
+                          9.96321 -183 -11.8737,
+                          9.96321 -152 -11.8737,
+                          5.30131 -152 -14.5652,
+                          13.4234 -183 -7.75,
+                          9.96321 -152 -11.8737,
+                          9.96321 -183 -11.8737,
+                          9.96321 -183 -11.8737,
+                          5.30131 -152 -14.5652,
+                          5.30131 -183 -14.5652,
+                          -6.18136 -162 -19.0208,
+                          -45.5 -162 -40.5,
+                          45.5 -162 -40.5,
+                          16.1809 -162 11.7545,
+                          45.5 -162 -40.5,
+                          45.5 -162 40.5,
+                          6.18136 -162 -19.0208,
+                          -2.44921e-15 -162 -20,
+                          45.5 -162 -40.5,
+                          -6.18136 -162 -19.0208,
+                          45.5 -162 -40.5,
+                          -2.44921e-15 -162 -20,
+                          11.7568 -162 -16.1794,
+                          6.18136 -162 -19.0208,
+                          45.5 -162 -40.5,
+                          16.1809 -162 -11.7545,
+                          11.7568 -162 -16.1794,
+                          45.5 -162 -40.5,
+                          19.021 -162 -6.17955,
+                          16.1809 -162 -11.7545,
+                          45.5 -162 -40.5,
+                          19.9997 -162 -2.55351e-15,
+                          19.021 -162 -6.17955,
+                          45.5 -162 -40.5,
+                          19.021 -162 6.17955,
+                          19.9997 -162 -2.55351e-15,
+                          45.5 -162 -40.5,
+                          16.1809 -162 11.7545,
+                          19.021 -162 6.17955,
+                          45.5 -162 -40.5,
+                          -16.1809 -162 -11.7545,
+                          -45.5 -162 40.5,
+                          -45.5 -162 -40.5,
+                          -11.7568 -162 -16.1794,
+                          -16.1809 -162 -11.7545,
+                          -45.5 -162 -40.5,
+                          -6.18136 -162 -19.0208,
+                          -11.7568 -162 -16.1794,
+                          -45.5 -162 -40.5,
+                          6.18136 -162 19.0208,
+                          45.5 -162 40.5,
+                          -45.5 -162 40.5,
+                          2.44922e-15 -162 20,
+                          6.18136 -162 19.0208,
+                          -45.5 -162 40.5,
+                          -6.18136 -162 19.0208,
+                          2.44922e-15 -162 20,
+                          -45.5 -162 40.5,
+                          -11.7568 -162 16.1794,
+                          -6.18136 -162 19.0208,
+                          -45.5 -162 40.5,
+                          -16.1809 -162 11.7545,
+                          -11.7568 -162 16.1794,
+                          -45.5 -162 40.5,
+                          -19.021 -162 6.17955,
+                          -16.1809 -162 11.7545,
+                          -45.5 -162 40.5,
+                          -19.9997 -162 -6.32827e-15,
+                          -19.021 -162 6.17955,
+                          -45.5 -162 40.5,
+                          -19.021 -162 -6.17955,
+                          -19.9997 -162 -6.32827e-15,
+                          -45.5 -162 40.5,
+                          -16.1809 -162 -11.7545,
+                          -19.021 -162 -6.17955,
+                          -45.5 -162 40.5,
+                          11.7568 -162 16.1794,
+                          16.1809 -162 11.7545,
+                          45.5 -162 40.5,
+                          6.18136 -162 19.0208,
+                          11.7568 -162 16.1794,
+                          45.5 -162 40.5,
+                          6.12303e-21 -183 -20,
+                          -2.44921e-15 -162 -20,
+                          6.18136 -162 -19.0208,
+                          -6.18191 -183 -19.0204,
+                          -6.18136 -162 -19.0208,
+                          -2.44921e-15 -162 -20,
+                          6.12303e-21 -183 -20,
+                          -6.18191 -183 -19.0204,
+                          -2.44921e-15 -162 -20,
+                          6.18191 -183 -19.0204,
+                          6.18136 -162 -19.0208,
+                          11.7568 -162 -16.1794,
+                          6.18191 -183 -19.0204,
+                          6.12303e-21 -183 -20,
+                          6.18136 -162 -19.0208,
+                          11.7562 -183 -16.1795,
+                          11.7568 -162 -16.1794,
+                          16.1809 -162 -11.7545,
+                          6.18191 -183 -19.0204,
+                          11.7568 -162 -16.1794,
+                          11.7562 -183 -16.1795,
+                          16.1795 -183 -11.7562,
+                          16.1809 -162 -11.7545,
+                          19.021 -162 -6.17955,
+                          11.7562 -183 -16.1795,
+                          16.1809 -162 -11.7545,
+                          16.1795 -183 -11.7562,
+                          19.0204 -183 -6.18191,
+                          19.021 -162 -6.17955,
+                          19.9997 -162 -2.55351e-15,
+                          16.1795 -183 -11.7562,
+                          19.021 -162 -6.17955,
+                          19.0204 -183 -6.18191,
+                          20 -183 -5.08065e-15,
+                          19.9997 -162 -2.55351e-15,
+                          19.021 -162 6.17955,
+                          19.0204 -183 -6.18191,
+                          19.9997 -162 -2.55351e-15,
+                          20 -183 -5.08065e-15,
+                          19.0204 -183 6.18191,
+                          19.021 -162 6.17955,
+                          16.1809 -162 11.7545,
+                          20 -183 -5.08065e-15,
+                          19.021 -162 6.17955,
+                          19.0204 -183 6.18191,
+                          16.1795 -183 11.7562,
+                          16.1809 -162 11.7545,
+                          11.7568 -162 16.1794,
+                          19.0204 -183 6.18191,
+                          16.1809 -162 11.7545,
+                          16.1795 -183 11.7562,
+                          11.7562 -183 16.1795,
+                          11.7568 -162 16.1794,
+                          6.18136 -162 19.0208,
+                          16.1795 -183 11.7562,
+                          11.7568 -162 16.1794,
+                          11.7562 -183 16.1795,
+                          6.18191 -183 19.0204,
+                          6.18136 -162 19.0208,
+                          2.44922e-15 -162 20,
+                          11.7562 -183 16.1795,
+                          6.18136 -162 19.0208,
+                          6.18191 -183 19.0204,
+                          6.12303e-21 -183 20,
+                          2.44922e-15 -162 20,
+                          -6.18136 -162 19.0208,
+                          6.18191 -183 19.0204,
+                          2.44922e-15 -162 20,
+                          6.12303e-21 -183 20,
+                          -6.18191 -183 19.0204,
+                          -6.18136 -162 19.0208,
+                          -11.7568 -162 16.1794,
+                          -6.18191 -183 19.0204,
+                          6.12303e-21 -183 20,
+                          -6.18136 -162 19.0208,
+                          -11.7562 -183 16.1795,
+                          -11.7568 -162 16.1794,
+                          -16.1809 -162 11.7545,
+                          -11.7562 -183 16.1795,
+                          -6.18191 -183 19.0204,
+                          -11.7568 -162 16.1794,
+                          -16.1795 -183 11.7562,
+                          -16.1809 -162 11.7545,
+                          -19.021 -162 6.17955,
+                          -16.1795 -183 11.7562,
+                          -11.7562 -183 16.1795,
+                          -16.1809 -162 11.7545,
+                          -19.0204 -183 6.18191,
+                          -19.021 -162 6.17955,
+                          -19.9997 -162 -6.32827e-15,
+                          -19.0204 -183 6.18191,
+                          -16.1795 -183 11.7562,
+                          -19.021 -162 6.17955,
+                          -20 -183 -5.08065e-15,
+                          -19.9997 -162 -6.32827e-15,
+                          -19.021 -162 -6.17955,
+                          -20 -183 -5.08065e-15,
+                          -19.0204 -183 6.18191,
+                          -19.9997 -162 -6.32827e-15,
+                          -19.0204 -183 -6.18191,
+                          -19.021 -162 -6.17955,
+                          -16.1809 -162 -11.7545,
+                          -19.0204 -183 -6.18191,
+                          -20 -183 -5.08065e-15,
+                          -19.021 -162 -6.17955,
+                          -16.1795 -183 -11.7562,
+                          -16.1809 -162 -11.7545,
+                          -11.7568 -162 -16.1794,
+                          -16.1795 -183 -11.7562,
+                          -19.0204 -183 -6.18191,
+                          -16.1809 -162 -11.7545,
+                          -11.7562 -183 -16.1795,
+                          -11.7568 -162 -16.1794,
+                          -6.18136 -162 -19.0208,
+                          -11.7562 -183 -16.1795,
+                          -16.1795 -183 -11.7562,
+                          -11.7568 -162 -16.1794,
+                          -6.18191 -183 -19.0204,
+                          -11.7562 -183 -16.1795,
+                          -6.18136 -162 -19.0208,
+                          -1.89813e-15 -183 15.5,
+                          6.12303e-21 -183 20,
+                          -6.18191 -183 19.0204,
+                          5.30131 -183 14.5652,
+                          6.18191 -183 19.0204,
+                          6.12303e-21 -183 20,
+                          -1.89813e-15 -183 15.5,
+                          5.30131 -183 14.5652,
+                          6.12303e-21 -183 20,
+                          -9.96321 -183 11.8737,
+                          -6.18191 -183 19.0204,
+                          -11.7562 -183 16.1795,
+                          -5.30131 -183 14.5652,
+                          -1.89813e-15 -183 15.5,
+                          -6.18191 -183 19.0204,
+                          -9.96321 -183 11.8737,
+                          -5.30131 -183 14.5652,
+                          -6.18191 -183 19.0204,
+                          -13.4234 -183 7.75,
+                          -11.7562 -183 16.1795,
+                          -16.1795 -183 11.7562,
+                          -13.4234 -183 7.75,
+                          -9.96321 -183 11.8737,
+                          -11.7562 -183 16.1795,
+                          -16.1795 -183 -11.7562,
+                          -16.1795 -183 11.7562,
+                          -19.0204 -183 6.18191,
+                          -15.2645 -183 -2.69155,
+                          -16.1795 -183 11.7562,
+                          -16.1795 -183 -11.7562,
+                          -15.2645 -183 2.69155,
+                          -13.4234 -183 7.75,
+                          -16.1795 -183 11.7562,
+                          -15.2645 -183 -2.69155,
+                          -15.2645 -183 2.69155,
+                          -16.1795 -183 11.7562,
+                          -19.0204 -183 -6.18191,
+                          -19.0204 -183 6.18191,
+                          -20 -183 -5.08065e-15,
+                          -16.1795 -183 -11.7562,
+                          -19.0204 -183 6.18191,
+                          -19.0204 -183 -6.18191,
+                          -15.2645 -183 -2.69155,
+                          -16.1795 -183 -11.7562,
+                          -11.7562 -183 -16.1795,
+                          -9.96321 -183 -11.8737,
+                          -11.7562 -183 -16.1795,
+                          -6.18191 -183 -19.0204,
+                          -13.4234 -183 -7.75,
+                          -15.2645 -183 -2.69155,
+                          -11.7562 -183 -16.1795,
+                          -9.96321 -183 -11.8737,
+                          -13.4234 -183 -7.75,
+                          -11.7562 -183 -16.1795,
+                          -5.30131 -183 -14.5652,
+                          -6.18191 -183 -19.0204,
+                          6.12303e-21 -183 -20,
+                          -5.30131 -183 -14.5652,
+                          -9.96321 -183 -11.8737,
+                          -6.18191 -183 -19.0204,
+                          1.89815e-15 -183 -15.5,
+                          6.12303e-21 -183 -20,
+                          6.18191 -183 -19.0204,
+                          -5.30131 -183 -14.5652,
+                          6.12303e-21 -183 -20,
+                          1.89815e-15 -183 -15.5,
+                          9.96321 -183 11.8737,
+                          11.7562 -183 16.1795,
+                          6.18191 -183 19.0204,
+                          5.30131 -183 14.5652,
+                          9.96321 -183 11.8737,
+                          6.18191 -183 19.0204,
+                          15.2645 -183 2.69155,
+                          16.1795 -183 11.7562,
+                          11.7562 -183 16.1795,
+                          13.4234 -183 7.75,
+                          15.2645 -183 2.69155,
+                          11.7562 -183 16.1795,
+                          9.96321 -183 11.8737,
+                          13.4234 -183 7.75,
+                          11.7562 -183 16.1795,
+                          19.0204 -183 -6.18191,
+                          19.0204 -183 6.18191,
+                          16.1795 -183 11.7562,
+                          16.1795 -183 -11.7562,
+                          19.0204 -183 -6.18191,
+                          16.1795 -183 11.7562,
+                          15.2645 -183 2.69155,
+                          16.1795 -183 -11.7562,
+                          16.1795 -183 11.7562,
+                          19.0204 -183 -6.18191,
+                          20 -183 -5.08065e-15,
+                          19.0204 -183 6.18191,
+                          13.4234 -183 -7.75,
+                          11.7562 -183 -16.1795,
+                          16.1795 -183 -11.7562,
+                          15.2645 -183 -2.69155,
+                          13.4234 -183 -7.75,
+                          16.1795 -183 -11.7562,
+                          15.2645 -183 2.69155,
+                          15.2645 -183 -2.69155,
+                          16.1795 -183 -11.7562,
+                          9.96321 -183 -11.8737,
+                          6.18191 -183 -19.0204,
+                          11.7562 -183 -16.1795,
+                          13.4234 -183 -7.75,
+                          9.96321 -183 -11.8737,
+                          11.7562 -183 -16.1795,
+                          5.30131 -183 -14.5652,
+                          1.89815e-15 -183 -15.5,
+                          6.18191 -183 -19.0204,
+                          9.96321 -183 -11.8737,
+                          5.30131 -183 -14.5652,
+                          6.18191 -183 -19.0204 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          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,
+                          1 0 0,
+                          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 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 41.5 -157 36.5,
+                          45.5 -157 36.5,
+                          45.5 157 36.5,
+                          45.5 157 -36.5,
+                          45.5 157 36.5,
+                          45.5 -157 36.5,
+                          41.5 157 36.5,
+                          41.5 -157 36.5,
+                          45.5 157 36.5,
+                          45.5 157 -36.5,
+                          41.5 157 36.5,
+                          45.5 157 36.5,
+                          41.5 -157 -36.5,
+                          45.5 -157 36.5,
+                          41.5 -157 36.5,
+                          45.5 -157 -36.5,
+                          45.5 -157 36.5,
+                          41.5 -157 -36.5,
+                          45.5 157 -36.5,
+                          45.5 -157 36.5,
+                          45.5 -157 -36.5,
+                          41.5 -157 -36.5,
+                          41.5 -157 36.5,
+                          41.5 157 36.5,
+                          41.5 157 -36.5,
+                          41.5 -157 -36.5,
+                          41.5 157 36.5,
+                          45.5 157 -36.5,
+                          41.5 157 -36.5,
+                          41.5 157 36.5,
+                          45.5 -157 -36.5,
+                          41.5 -157 -36.5,
+                          41.5 157 -36.5,
+                          45.5 157 -36.5,
+                          45.5 -157 -36.5,
+                          41.5 157 -36.5 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 0 -0.173648 0.984808,
+                          0 -0.173648 0.984808,
+                          0 -0.642788 0.766044,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.642788 0.766044,
+                          0 -0.173648 0.984808,
+                          0 -0.642788 0.766044,
+                          0 -0.939693 0.34202,
+                          0 -0.642788 0.766044,
+                          0 -0.642788 0.766044,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.34202 0.939693,
+                          0 0.34202 0.939693,
+                          0 -0.173648 0.984808,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.173648 0.984808,
+                          0 0.34202 0.939693,
+                          0 -0.173648 0.984808,
+                          0 0.766044 0.642788,
+                          0 0.766044 0.642788,
+                          0 0.34202 0.939693,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.34202 0.939693,
+                          0 0.766044 0.642788,
+                          0 0.34202 0.939693,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.984808 0.173648,
+                          0 0.984808 0.173648,
+                          0 0.766044 0.642788,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.766044 0.642788,
+                          0 0.984808 0.173648,
+                          0 0.766044 0.642788,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.939693 -0.34202,
+                          0 0.939693 -0.34202,
+                          0 0.984808 0.173648,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.984808 0.173648,
+                          0 0.939693 -0.34202,
+                          0 0.984808 0.173648,
+                          0 0.642788 -0.766044,
+                          0 0.642788 -0.766044,
+                          0 0.939693 -0.34202,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.939693 -0.34202,
+                          0 0.642788 -0.766044,
+                          0 0.939693 -0.34202,
+                          0 0.173648 -0.984808,
+                          0 0.642788 -0.766044,
+                          0 0.642788 -0.766044,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.173648 -0.984808,
+                          0 0.173648 -0.984808,
+                          0 0.642788 -0.766044,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.939693 0.34202,
+                          0 -0.642788 0.766044,
+                          0 -0.939693 0.34202,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.300706 0.953717,
+                          0 -0.300706 0.953717,
+                          0 -0.642788 0.766044,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.642788 0.766044,
+                          0 -0.300706 0.953717,
+                          0 -0.642788 0.766044,
+                          0 -0.887011 0.461749,
+                          0 -0.642788 0.766044,
+                          0 -0.642788 0.766044,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.0871557 0.996195,
+                          0 0.0871557 0.996195,
+                          0 -0.300706 0.953717,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.300706 0.953717,
+                          0 0.0871557 0.996195,
+                          0 -0.300706 0.953717,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.461749 0.887011,
+                          0 0.461749 0.887011,
+                          0 0.0871557 0.996195,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.0871557 0.996195,
+                          0 0.461749 0.887011,
+                          0 0.0871557 0.996195,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.766044 0.642788,
+                          0 0.766044 0.642788,
+                          0 0.461749 0.887011,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.461749 0.887011,
+                          0 0.766044 0.642788,
+                          0 0.461749 0.887011,
+                          0 0.953717 0.300706,
+                          0 0.953717 0.300706,
+                          0 0.766044 0.642788,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.766044 0.642788,
+                          0 0.953717 0.300706,
+                          0 0.766044 0.642788,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.996195 -0.0871557,
+                          0 0.996195 -0.0871557,
+                          0 0.953717 0.300706,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.953717 0.300706,
+                          0 0.996195 -0.0871557,
+                          0 0.953717 0.300706,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.887011 -0.461749,
+                          0 0.887011 -0.461749,
+                          0 0.996195 -0.0871557,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.996195 -0.0871557,
+                          0 0.887011 -0.461749,
+                          0 0.996195 -0.0871557,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.642788 -0.766044,
+                          0 0.642788 -0.766044,
+                          0 0.887011 -0.461749,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.887011 -0.461749,
+                          0 0.642788 -0.766044,
+                          0 0.887011 -0.461749,
+                          0 0.300706 -0.953717,
+                          0 0.642788 -0.766044,
+                          0 0.642788 -0.766044,
+                          0 0.300706 -0.953717,
+                          0 0.642788 -0.766044,
+                          0 0.300706 -0.953717,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.887011 0.461749,
+                          0 -0.887011 0.461749,
+                          0 -0.642788 0.766044,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.300706 -0.953717,
+                          0 0.300706 -0.953717,
+                          0 -0.0871557 -0.996195,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.0871557 -0.996195,
+                          0 -0.0871557 -0.996195,
+                          0 -0.461749 -0.887011,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.300706 -0.953717,
+                          0 -0.0871557 -0.996195,
+                          0 -0.0871557 -0.996195,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.461749 -0.887011,
+                          0 -0.461749 -0.887011,
+                          0 -0.766044 -0.642788,
+                          0 -0.0871557 -0.996195,
+                          0 -0.461749 -0.887011,
+                          0 -0.461749 -0.887011,
+                          0 -0.766044 -0.642788,
+                          0 -0.766044 -0.642788,
+                          0 -0.953717 -0.300706,
+                          0 -0.461749 -0.887011,
+                          0 -0.766044 -0.642788,
+                          0 -0.766044 -0.642788,
+                          0 -0.953717 -0.300706,
+                          0 -0.953717 -0.300706,
+                          0 -0.996195 0.0871557,
+                          0 -0.766044 -0.642788,
+                          0 -0.953717 -0.300706,
+                          0 -0.953717 -0.300706,
+                          0 -0.996195 0.0871557,
+                          0 -0.996195 0.0871557,
+                          0 -0.887011 0.461749,
+                          0 -0.953717 -0.300706,
+                          0 -0.996195 0.0871557,
+                          0 -0.996195 0.0871557,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.996195 0.0871557,
+                          0 -0.887011 0.461749,
+                          0 -0.887011 0.461749,
+                          0 -0.939693 0.34202,
+                          0 -0.939693 0.34202,
+                          0 -0.984808 -0.173648,
+                          0 -0.984808 -0.173648,
+                          0 -0.984808 -0.173648,
+                          0 -0.766044 -0.642788,
+                          0 -0.939693 0.34202,
+                          0 -0.984808 -0.173648,
+                          0 -0.984808 -0.173648,
+                          0 -0.766044 -0.642788,
+                          0 -0.766044 -0.642788,
+                          0 -0.34202 -0.939693,
+                          0 -0.984808 -0.173648,
+                          0 -0.766044 -0.642788,
+                          0 -0.766044 -0.642788,
+                          0 -0.34202 -0.939693,
+                          0 -0.34202 -0.939693,
+                          0 0.173648 -0.984808,
+                          0 -0.766044 -0.642788,
+                          0 -0.34202 -0.939693,
+                          0 -0.34202 -0.939693,
+                          0 -0.34202 -0.939693,
+                          0 0.173648 -0.984808,
+                          0 0.173648 -0.984808,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.642788 0.766044,
+                          0 -0.642788 0.766044,
+                          0 -0.173648 0.984808,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.939693 0.34202,
+                          0 -0.939693 0.34202,
+                          0 -0.642788 0.766044,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.939693 0.34202,
+                          0 -0.642788 0.766044,
+                          0 -0.642788 0.766044,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.173648 0.984808,
+                          0 -0.173648 0.984808,
+                          0 0.34202 0.939693,
+                          0 -0.173648 0.984808,
+                          0 -0.642788 0.766044,
+                          0 -0.173648 0.984808,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.34202 0.939693,
+                          0 0.34202 0.939693,
+                          0 0.766044 0.642788,
+                          0 -0.173648 0.984808,
+                          0 0.34202 0.939693,
+                          0 0.34202 0.939693,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.766044 0.642788,
+                          0 0.766044 0.642788,
+                          0 0.984808 0.173648,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.34202 0.939693,
+                          0 0.766044 0.642788,
+                          0 0.766044 0.642788,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.984808 0.173648,
+                          0 0.984808 0.173648,
+                          0 0.939693 -0.34202,
+                          0 0.766044 0.642788,
+                          0 0.984808 0.173648,
+                          0 0.984808 0.173648,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.939693 -0.34202,
+                          0 0.939693 -0.34202,
+                          0 0.642788 -0.766044,
+                          0 0.984808 0.173648,
+                          0 0.939693 -0.34202,
+                          0 0.939693 -0.34202,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.642788 -0.766044,
+                          0 0.642788 -0.766044,
+                          0 0.173648 -0.984808,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.939693 -0.34202,
+                          0 0.642788 -0.766044,
+                          0 0.642788 -0.766044,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.173648 -0.984808,
+                          0 0.173648 -0.984808,
+                          0 -0.34202 -0.939693,
+                          0 0.642788 -0.766044,
+                          0 0.173648 -0.984808,
+                          0 0.173648 -0.984808,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.34202 -0.939693,
+                          0 -0.34202 -0.939693,
+                          0 -0.766044 -0.642788,
+                          0 0.173648 -0.984808,
+                          0 -0.34202 -0.939693,
+                          0 -0.34202 -0.939693,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.766044 -0.642788,
+                          0 -0.766044 -0.642788,
+                          0 -0.984808 -0.173648,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.34202 -0.939693,
+                          0 -0.766044 -0.642788,
+                          0 -0.766044 -0.642788,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.984808 -0.173648,
+                          0 -0.984808 -0.173648,
+                          0 -0.939693 0.34202,
+                          0 -0.766044 -0.642788,
+                          0 -0.984808 -0.173648,
+                          0 -0.984808 -0.173648,
+                          0 -0.984808 -0.173648,
+                          0 -0.939693 0.34202,
+                          0 -0.939693 0.34202,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.642788 0.766044,
+                          0 -0.642788 0.766044,
+                          0 -0.83257 0.55392,
+                          0 -0.400931 0.916108,
+                          0 -0.400931 0.916108,
+                          0 -0.642788 0.766044,
+                          0 -0.642788 0.766044,
+                          0 -0.400931 0.916108,
+                          0 -0.642788 0.766044,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.83257 0.55392,
+                          0 -0.83257 0.55392,
+                          0 -0.954902 0.29692,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.83257 0.55392,
+                          0 -0.642788 0.766044,
+                          0 -0.83257 0.55392,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.954902 0.29692,
+                          0 -0.954902 0.29692,
+                          0 -0.999874 0.015866,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.83257 0.55392,
+                          0 -0.954902 0.29692,
+                          0 -0.954902 0.29692,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.999874 0.015866,
+                          0 -0.999874 0.015866,
+                          0 -0.963842 -0.266474,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.954902 0.29692,
+                          0 -0.999874 0.015866,
+                          0 -0.999874 0.015866,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.963842 -0.266474,
+                          0 -0.963842 -0.266474,
+                          0 -0.849725 -0.527225,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.999874 0.015866,
+                          0 -0.963842 -0.266474,
+                          0 -0.963842 -0.266474,
+                          0 -0.849725 -0.527225,
+                          0 -0.849725 -0.527225,
+                          0 -0.666769 -0.745264,
+                          0 -0.963842 -0.266474,
+                          0 -0.849725 -0.527225,
+                          0 -0.849725 -0.527225,
+                          0 -0.666769 -0.745264,
+                          0 -0.666769 -0.745264,
+                          0 -0.429795 -0.902927,
+                          0 -0.849725 -0.527225,
+                          0 -0.666769 -0.745264,
+                          0 -0.666769 -0.745264,
+                          0 -0.429795 -0.902927,
+                          0 -0.429795 -0.902927,
+                          0 -0.158001 -0.987439,
+                          0 -0.666769 -0.745264,
+                          0 -0.429795 -0.902927,
+                          0 -0.429795 -0.902927,
+                          0 -0.158001 -0.987439,
+                          0 -0.158001 -0.987439,
+                          0 0.126592 -0.991955,
+                          0 -0.429795 -0.902927,
+                          0 -0.158001 -0.987439,
+                          0 -0.158001 -0.987439,
+                          0 0.126592 -0.991955,
+                          0 0.126592 -0.991955,
+                          0 0.400931 -0.916108,
+                          0 -0.158001 -0.987439,
+                          0 0.126592 -0.991955,
+                          0 0.126592 -0.991955,
+                          0 0.400931 -0.916108,
+                          0 0.400931 -0.916108,
+                          0 0.642788 -0.766044,
+                          0 0.126592 -0.991955,
+                          0 0.400931 -0.916108,
+                          0 0.400931 -0.916108,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.642788 -0.766044,
+                          0 0.642788 -0.766044,
+                          0 0.83257 -0.55392,
+                          0 0.400931 -0.916108,
+                          0 0.642788 -0.766044,
+                          0 0.642788 -0.766044,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.83257 -0.55392,
+                          0 0.83257 -0.55392,
+                          0 0.954902 -0.29692,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.83257 -0.55392,
+                          0 0.642788 -0.766044,
+                          0 0.83257 -0.55392,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.954902 -0.29692,
+                          0 0.954902 -0.29692,
+                          0 0.999874 -0.015866,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.954902 -0.29692,
+                          0 0.83257 -0.55392,
+                          0 0.954902 -0.29692,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.999874 -0.015866,
+                          0 0.999874 -0.015866,
+                          0 0.963842 0.266474,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.999874 -0.015866,
+                          0 0.954902 -0.29692,
+                          0 0.999874 -0.015866,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.963842 0.266474,
+                          0 0.963842 0.266474,
+                          0 0.849725 0.527225,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.963842 0.266474,
+                          0 0.999874 -0.015866,
+                          0 0.963842 0.266474,
+                          0 0.849725 0.527225,
+                          0 0.849725 0.527225,
+                          0 0.666769 0.745264,
+                          0 0.849725 0.527225,
+                          0 0.963842 0.266474,
+                          0 0.849725 0.527225,
+                          0 0.666769 0.745264,
+                          0 0.666769 0.745264,
+                          0 0.429795 0.902927,
+                          0 0.666769 0.745264,
+                          0 0.849725 0.527225,
+                          0 0.666769 0.745264,
+                          0 0.429795 0.902927,
+                          0 0.429795 0.902927,
+                          0 0.158001 0.987439,
+                          0 0.429795 0.902927,
+                          0 0.666769 0.745264,
+                          0 0.429795 0.902927,
+                          0 0.158001 0.987439,
+                          0 0.158001 0.987439,
+                          0 -0.126592 0.991955,
+                          0 0.158001 0.987439,
+                          0 0.429795 0.902927,
+                          0 0.158001 0.987439,
+                          0 -0.126592 0.991955,
+                          0 -0.126592 0.991955,
+                          0 -0.400931 0.916108,
+                          0 -0.126592 0.991955,
+                          0 0.158001 0.987439,
+                          0 -0.126592 0.991955,
+                          0 -0.400931 0.916108,
+                          0 -0.126592 0.991955,
+                          0 -0.400931 0.916108,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.642788 0.766044,
+                          0 -0.642788 0.766044,
+                          0 -0.866025 0.5,
+                          0 -0.34202 0.939693,
+                          0 -0.34202 0.939693,
+                          0 -0.642788 0.766044,
+                          0 -0.642788 0.766044,
+                          0 -0.34202 0.939693,
+                          0 -0.642788 0.766044,
+                          0 -0.866025 0.5,
+                          0 -0.866025 0.5,
+                          0 -0.984808 0.173648,
+                          0 -0.866025 0.5,
+                          0 -0.642788 0.766044,
+                          0 -0.866025 0.5,
+                          0 -0.984808 0.173648,
+                          0 -0.984808 0.173648,
+                          0 -0.984808 -0.173648,
+                          0 -0.866025 0.5,
+                          0 -0.984808 0.173648,
+                          0 -0.984808 0.173648,
+                          0 -0.984808 -0.173648,
+                          0 -0.984808 -0.173648,
+                          0 -0.866025 -0.5,
+                          0 -0.984808 0.173648,
+                          0 -0.984808 -0.173648,
+                          0 -0.984808 -0.173648,
+                          0 -0.866025 -0.5,
+                          0 -0.866025 -0.5,
+                          0 -0.642788 -0.766044,
+                          0 -0.984808 -0.173648,
+                          0 -0.866025 -0.5,
+                          0 -0.866025 -0.5,
+                          0 -0.642788 -0.766044,
+                          0 -0.642788 -0.766044,
+                          0 -0.34202 -0.939693,
+                          0 -0.866025 -0.5,
+                          0 -0.642788 -0.766044,
+                          0 -0.642788 -0.766044,
+                          0 -0.34202 -0.939693,
+                          0 -0.34202 -0.939693,
+                          0 -1.11022e-16 -1,
+                          0 -0.642788 -0.766044,
+                          0 -0.34202 -0.939693,
+                          0 -0.34202 -0.939693,
+                          0 -1.11022e-16 -1,
+                          0 -1.11022e-16 -1,
+                          0 0.34202 -0.939693,
+                          0 -0.34202 -0.939693,
+                          0 -1.11022e-16 -1,
+                          0 -1.11022e-16 -1,
+                          0 0.34202 -0.939693,
+                          0 0.34202 -0.939693,
+                          0 0.642788 -0.766044,
+                          0 -1.11022e-16 -1,
+                          0 0.34202 -0.939693,
+                          0 0.34202 -0.939693,
+                          0 0.642788 -0.766044,
+                          0 0.642788 -0.766044,
+                          0 0.866025 -0.5,
+                          0 0.34202 -0.939693,
+                          0 0.642788 -0.766044,
+                          0 0.642788 -0.766044,
+                          0 0.866025 -0.5,
+                          0 0.866025 -0.5,
+                          0 0.984808 -0.173648,
+                          0 0.866025 -0.5,
+                          0 0.642788 -0.766044,
+                          0 0.866025 -0.5,
+                          0 0.984808 -0.173648,
+                          0 0.984808 -0.173648,
+                          0 0.984808 0.173648,
+                          0 0.984808 -0.173648,
+                          0 0.866025 -0.5,
+                          0 0.984808 -0.173648,
+                          0 0.984808 0.173648,
+                          0 0.984808 0.173648,
+                          0 0.866025 0.5,
+                          0 0.984808 0.173648,
+                          0 0.984808 -0.173648,
+                          0 0.984808 0.173648,
+                          0 0.866025 0.5,
+                          0 0.866025 0.5,
+                          0 0.642788 0.766044,
+                          0 0.866025 0.5,
+                          0 0.984808 0.173648,
+                          0 0.866025 0.5,
+                          0 0.642788 0.766044,
+                          0 0.642788 0.766044,
+                          0 0.34202 0.939693,
+                          0 0.642788 0.766044,
+                          0 0.866025 0.5,
+                          0 0.642788 0.766044,
+                          0 0.34202 0.939693,
+                          0 0.34202 0.939693,
+                          0 0 1,
+                          0 0.34202 0.939693,
+                          0 0.642788 0.766044,
+                          0 0.34202 0.939693,
+                          0 0 1,
+                          0 0 1,
+                          0 -0.34202 0.939693,
+                          0 0 1,
+                          0 0.34202 0.939693,
+                          0 0 1,
+                          0 -0.34202 0.939693,
+                          0 0 1,
+                          0 -0.34202 0.939693,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.642788 0.766044,
+                          0 -0.642788 0.766044,
+                          0 -0.887011 0.461749,
+                          0 -0.300706 0.953717,
+                          0 -0.300706 0.953717,
+                          0 -0.642788 0.766044,
+                          0 -0.642788 0.766044,
+                          0 -0.300706 0.953717,
+                          0 -0.642788 0.766044,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.887011 0.461749,
+                          0 -0.887011 0.461749,
+                          0 -0.996195 0.0871557,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.887011 0.461749,
+                          0 -0.642788 0.766044,
+                          0 -0.887011 0.461749,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.996195 0.0871557,
+                          0 -0.996195 0.0871557,
+                          0 -0.953717 -0.300706,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.887011 0.461749,
+                          0 -0.996195 0.0871557,
+                          0 -0.996195 0.0871557,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.953717 -0.300706,
+                          0 -0.953717 -0.300706,
+                          0 -0.766044 -0.642788,
+                          0 -0.996195 0.0871557,
+                          0 -0.953717 -0.300706,
+                          0 -0.953717 -0.300706,
+                          0 -0.766044 -0.642788,
+                          0 -0.766044 -0.642788,
+                          0 -0.461749 -0.887011,
+                          0 -0.953717 -0.300706,
+                          0 -0.766044 -0.642788,
+                          0 -0.766044 -0.642788,
+                          0 -0.461749 -0.887011,
+                          0 -0.461749 -0.887011,
+                          0 -0.0871557 -0.996195,
+                          0 -0.766044 -0.642788,
+                          0 -0.461749 -0.887011,
+                          0 -0.461749 -0.887011,
+                          0 -0.0871557 -0.996195,
+                          0 -0.0871557 -0.996195,
+                          0 0.300706 -0.953717,
+                          0 -0.461749 -0.887011,
+                          0 -0.0871557 -0.996195,
+                          0 -0.0871557 -0.996195,
+                          0 0.300706 -0.953717,
+                          0 0.300706 -0.953717,
+                          0 0.642788 -0.766044,
+                          0 -0.0871557 -0.996195,
+                          0 0.300706 -0.953717,
+                          0 0.300706 -0.953717,
+                          0 0.642788 -0.766044,
+                          0 0.642788 -0.766044,
+                          0 0.887011 -0.461749,
+                          0 0.300706 -0.953717,
+                          0 0.642788 -0.766044,
+                          0 0.642788 -0.766044,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.887011 -0.461749,
+                          0 0.887011 -0.461749,
+                          0 0.996195 -0.0871557,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.887011 -0.461749,
+                          0 0.642788 -0.766044,
+                          0 0.887011 -0.461749,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.996195 -0.0871557,
+                          0 0.996195 -0.0871557,
+                          0 0.953717 0.300706,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.996195 -0.0871557,
+                          0 0.887011 -0.461749,
+                          0 0.996195 -0.0871557,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.953717 0.300706,
+                          0 0.953717 0.300706,
+                          0 0.766044 0.642788,
+                          0 0.953717 0.300706,
+                          0 0.996195 -0.0871557,
+                          0 0.953717 0.300706,
+                          0 0.766044 0.642788,
+                          0 0.766044 0.642788,
+                          0 0.461749 0.887011,
+                          0 0.766044 0.642788,
+                          0 0.953717 0.300706,
+                          0 0.766044 0.642788,
+                          0 0.461749 0.887011,
+                          0 0.461749 0.887011,
+                          0 0.0871557 0.996195,
+                          0 0.461749 0.887011,
+                          0 0.766044 0.642788,
+                          0 0.461749 0.887011,
+                          0 0.0871557 0.996195,
+                          0 0.0871557 0.996195,
+                          0 -0.300706 0.953717,
+                          0 0.0871557 0.996195,
+                          0 0.461749 0.887011,
+                          0 0.0871557 0.996195,
+                          0 -0.300706 0.953717,
+                          0 0.0871557 0.996195,
+                          0 -0.300706 0.953717,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.642788 0.766044,
+                          0 -0.642788 0.766044,
+                          0 -0.911506 0.411287,
+                          0 -0.246757 0.969077,
+                          0 -0.246757 0.969077,
+                          0 -0.642788 0.766044,
+                          0 -0.642788 0.766044,
+                          0 -0.246757 0.969077,
+                          0 -0.642788 0.766044,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.911506 0.411287,
+                          0 -0.911506 0.411287,
+                          0 -0.999689 -0.0249307,
+                          0 -0.911506 0.411287,
+                          0 -0.642788 0.766044,
+                          0 -0.911506 0.411287,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.999689 -0.0249307,
+                          0 -0.999689 -0.0249307,
+                          0 -0.889872 -0.456211,
+                          0 -0.911506 0.411287,
+                          0 -0.999689 -0.0249307,
+                          0 -0.999689 -0.0249307,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.889872 -0.456211,
+                          0 -0.889872 -0.456211,
+                          0 -0.603804 -0.797132,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.999689 -0.0249307,
+                          0 -0.889872 -0.456211,
+                          0 -0.889872 -0.456211,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.603804 -0.797132,
+                          0 -0.603804 -0.797132,
+                          0 -0.198146 -0.980173,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.889872 -0.456211,
+                          0 -0.603804 -0.797132,
+                          0 -0.603804 -0.797132,
+                          0 -0.198146 -0.980173,
+                          0 -0.198146 -0.980173,
+                          0 0.246757 -0.969077,
+                          0 -0.603804 -0.797132,
+                          0 -0.198146 -0.980173,
+                          0 -0.198146 -0.980173,
+                          0 0.246757 -0.969077,
+                          0 0.246757 -0.969077,
+                          0 0.642788 -0.766044,
+                          0 -0.198146 -0.980173,
+                          0 0.246757 -0.969077,
+                          0 0.246757 -0.969077,
+                          0 0.642788 -0.766044,
+                          0 0.642788 -0.766044,
+                          0 0.911506 -0.411287,
+                          0 0.246757 -0.969077,
+                          0 0.642788 -0.766044,
+                          0 0.642788 -0.766044,
+                          0 0.911506 -0.411287,
+                          0 0.911506 -0.411287,
+                          0 0.999689 0.0249307,
+                          0 0.911506 -0.411287,
+                          0 0.642788 -0.766044,
+                          0 0.911506 -0.411287,
+                          0 0.999689 0.0249307,
+                          0 0.999689 0.0249307,
+                          0 0.889872 0.456211,
+                          0 0.999689 0.0249307,
+                          0 0.911506 -0.411287,
+                          0 0.999689 0.0249307,
+                          0 0.889872 0.456211,
+                          0 0.889872 0.456211,
+                          0 0.603804 0.797132,
+                          0 0.889872 0.456211,
+                          0 0.999689 0.0249307,
+                          0 0.889872 0.456211,
+                          0 0.603804 0.797132,
+                          0 0.603804 0.797132,
+                          0 0.198146 0.980173,
+                          0 0.603804 0.797132,
+                          0 0.889872 0.456211,
+                          0 0.603804 0.797132,
+                          0 0.198146 0.980173,
+                          0 0.198146 0.980173,
+                          0 -0.246757 0.969077,
+                          0 0.198146 0.980173,
+                          0 0.603804 0.797132,
+                          0 0.198146 0.980173,
+                          0 -0.246757 0.969077,
+                          0 0.198146 0.980173,
+                          0 -0.246757 0.969077,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 30.75 -0.694593 3.93923,
+                          -29.75 -0.694593 3.93923,
+                          -29.75 -2.57115 3.06418,
+                          -29.75 -8.03485 9.57556,
+                          -29.75 -2.57115 3.06418,
+                          -29.75 -0.694593 3.93923,
+                          30.75 -2.57115 3.06418,
+                          30.75 -0.694593 3.93923,
+                          -29.75 -2.57115 3.06418,
+                          -29.75 -3.75877 1.36808,
+                          30.75 -2.57115 3.06418,
+                          -29.75 -2.57115 3.06418,
+                          -29.75 -11.0876 5.77186,
+                          -29.75 -2.57115 3.06418,
+                          -29.75 -8.03485 9.57556,
+                          -29.75 -3.75877 1.36808,
+                          -29.75 -2.57115 3.06418,
+                          -29.75 -11.0876 5.77186,
+                          30.75 1.36808 3.75877,
+                          -29.75 1.36808 3.75877,
+                          -29.75 -0.694593 3.93923,
+                          -29.75 -8.03485 9.57556,
+                          -29.75 -0.694593 3.93923,
+                          -29.75 1.36808 3.75877,
+                          30.75 -0.694593 3.93923,
+                          30.75 1.36808 3.75877,
+                          -29.75 -0.694593 3.93923,
+                          30.75 3.06418 2.57115,
+                          -29.75 3.06418 2.57115,
+                          -29.75 1.36808 3.75877,
+                          -29.75 -3.75882 11.9215,
+                          -29.75 1.36808 3.75877,
+                          -29.75 3.06418 2.57115,
+                          30.75 1.36808 3.75877,
+                          30.75 3.06418 2.57115,
+                          -29.75 1.36808 3.75877,
+                          -29.75 -8.03485 9.57556,
+                          -29.75 1.36808 3.75877,
+                          -29.75 -3.75882 11.9215,
+                          30.75 3.93923 0.694593,
+                          -29.75 3.93923 0.694593,
+                          -29.75 3.06418 2.57115,
+                          -29.75 11.0876 -5.77186,
+                          -29.75 3.06418 2.57115,
+                          -29.75 3.93923 0.694593,
+                          30.75 3.06418 2.57115,
+                          30.75 3.93923 0.694593,
+                          -29.75 3.06418 2.57115,
+                          -29.75 -3.75882 11.9215,
+                          -29.75 3.06418 2.57115,
+                          -29.75 11.0876 -5.77186,
+                          30.75 3.75877 -1.36808,
+                          -29.75 3.75877 -1.36808,
+                          -29.75 3.93923 0.694593,
+                          -29.75 11.0876 -5.77186,
+                          -29.75 3.93923 0.694593,
+                          -29.75 3.75877 -1.36808,
+                          30.75 3.93923 0.694593,
+                          30.75 3.75877 -1.36808,
+                          -29.75 3.93923 0.694593,
+                          30.75 2.57115 -3.06418,
+                          -29.75 2.57115 -3.06418,
+                          -29.75 3.75877 -1.36808,
+                          -29.75 11.0876 -5.77186,
+                          -29.75 3.75877 -1.36808,
+                          -29.75 2.57115 -3.06418,
+                          30.75 3.75877 -1.36808,
+                          30.75 2.57115 -3.06418,
+                          -29.75 3.75877 -1.36808,
+                          30.75 0.694593 -3.93923,
+                          -29.75 2.57115 -3.06418,
+                          30.75 2.57115 -3.06418,
+                          -29.75 11.0876 -5.77186,
+                          -29.75 2.57115 -3.06418,
+                          -29.75 8.03485 -9.57556,
+                          -29.75 0.694593 -3.93923,
+                          -29.75 8.03485 -9.57556,
+                          -29.75 2.57115 -3.06418,
+                          30.75 0.694593 -3.93923,
+                          -29.75 0.694593 -3.93923,
+                          -29.75 2.57115 -3.06418,
+                          30.75 8.03485 -9.57556,
+                          30.75 2.57115 -3.06418,
+                          30.75 3.75877 -1.36808,
+                          30.75 3.75882 -11.9215,
+                          30.75 0.694593 -3.93923,
+                          30.75 2.57115 -3.06418,
+                          30.75 8.03485 -9.57556,
+                          30.75 3.75882 -11.9215,
+                          30.75 2.57115 -3.06418,
+                          30.75 8.03485 -9.57556,
+                          30.75 3.75877 -1.36808,
+                          30.75 3.93923 0.694593,
+                          30.75 11.0876 -5.77186,
+                          30.75 3.93923 0.694593,
+                          30.75 3.06418 2.57115,
+                          30.75 11.0876 -5.77186,
+                          30.75 8.03485 -9.57556,
+                          30.75 3.93923 0.694593,
+                          30.75 -3.75882 11.9215,
+                          30.75 3.06418 2.57115,
+                          30.75 1.36808 3.75877,
+                          30.75 -3.75882 11.9215,
+                          30.75 11.0876 -5.77186,
+                          30.75 3.06418 2.57115,
+                          30.75 -3.75882 11.9215,
+                          30.75 1.36808 3.75877,
+                          30.75 -0.694593 3.93923,
+                          30.75 -3.75882 11.9215,
+                          30.75 -0.694593 3.93923,
+                          30.75 -2.57115 3.06418,
+                          30.75 -3.75877 1.36808,
+                          30.75 -2.57115 3.06418,
+                          -29.75 -3.75877 1.36808,
+                          30.75 -8.03485 9.57556,
+                          30.75 -2.57115 3.06418,
+                          30.75 -3.75877 1.36808,
+                          30.75 -3.75882 11.9215,
+                          30.75 -2.57115 3.06418,
+                          30.75 -8.03485 9.57556,
+                          -29.75 -3.75882 11.9215,
+                          -44.75 -3.75882 11.9215,
+                          -44.75 -8.03485 9.57556,
+                          -44.75 -11.2488 13.4058,
+                          -44.75 -8.03485 9.57556,
+                          -44.75 -3.75882 11.9215,
+                          -29.75 -8.03485 9.57556,
+                          -29.75 -3.75882 11.9215,
+                          -44.75 -8.03485 9.57556,
+                          -44.75 -11.0876 5.77186,
+                          -29.75 -8.03485 9.57556,
+                          -44.75 -8.03485 9.57556,
+                          -44.75 -15.1561 8.74874,
+                          -44.75 -8.03485 9.57556,
+                          -44.75 -11.2488 13.4058,
+                          -44.75 -11.0876 5.77186,
+                          -44.75 -8.03485 9.57556,
+                          -44.75 -15.1561 8.74874,
+                          -29.75 1.08945 12.4524,
+                          -44.75 1.08945 12.4524,
+                          -44.75 -3.75882 11.9215,
+                          -44.75 -5.984 16.445,
+                          -44.75 -3.75882 11.9215,
+                          -44.75 1.08945 12.4524,
+                          -29.75 -3.75882 11.9215,
+                          -29.75 1.08945 12.4524,
+                          -44.75 -3.75882 11.9215,
+                          -44.75 -11.2488 13.4058,
+                          -44.75 -3.75882 11.9215,
+                          -44.75 -5.984 16.445,
+                          -29.75 5.77186 11.0876,
+                          -44.75 5.77186 11.0876,
+                          -44.75 1.08945 12.4524,
+                          -44.75 0.00177073 17.4998,
+                          -44.75 1.08945 12.4524,
+                          -44.75 5.77186 11.0876,
+                          -29.75 1.08945 12.4524,
+                          -29.75 5.77186 11.0876,
+                          -44.75 1.08945 12.4524,
+                          -44.75 -5.984 16.445,
+                          -44.75 1.08945 12.4524,
+                          -44.75 0.00177073 17.4998,
+                          -29.75 9.57556 8.03485,
+                          -44.75 9.57556 8.03485,
+                          -44.75 5.77186 11.0876,
+                          -44.75 0.00177073 17.4998,
+                          -44.75 5.77186 11.0876,
+                          -44.75 9.57556 8.03485,
+                          -29.75 5.77186 11.0876,
+                          -29.75 9.57556 8.03485,
+                          -44.75 5.77186 11.0876,
+                          -29.75 11.9215 3.75882,
+                          -44.75 11.9215 3.75882,
+                          -44.75 9.57556 8.03485,
+                          -44.75 17.2335 3.04012,
+                          -44.75 9.57556 8.03485,
+                          -44.75 11.9215 3.75882,
+                          -29.75 9.57556 8.03485,
+                          -29.75 11.9215 3.75882,
+                          -44.75 9.57556 8.03485,
+                          -44.75 0.00177073 17.4998,
+                          -44.75 9.57556 8.03485,
+                          -44.75 17.2335 3.04012,
+                          -29.75 12.4524 -1.08945,
+                          -44.75 12.4524 -1.08945,
+                          -44.75 11.9215 3.75882,
+                          -44.75 17.2342 -3.03706,
+                          -44.75 11.9215 3.75882,
+                          -44.75 12.4524 -1.08945,
+                          -29.75 11.9215 3.75882,
+                          -29.75 12.4524 -1.08945,
+                          -44.75 11.9215 3.75882,
+                          -44.75 17.2335 3.04012,
+                          -44.75 11.9215 3.75882,
+                          -44.75 17.2342 -3.03706,
+                          -29.75 11.0876 -5.77186,
+                          -44.75 11.0876 -5.77186,
+                          -44.75 12.4524 -1.08945,
+                          -44.75 15.1561 -8.74874,
+                          -44.75 12.4524 -1.08945,
+                          -44.75 11.0876 -5.77186,
+                          -29.75 12.4524 -1.08945,
+                          -29.75 11.0876 -5.77186,
+                          -44.75 12.4524 -1.08945,
+                          -44.75 17.2342 -3.03706,
+                          -44.75 12.4524 -1.08945,
+                          -44.75 15.1561 -8.74874,
+                          -29.75 8.03485 -9.57556,
+                          -44.75 8.03485 -9.57556,
+                          -44.75 11.0876 -5.77186,
+                          -44.75 15.1561 -8.74874,
+                          -44.75 11.0876 -5.77186,
+                          -44.75 8.03485 -9.57556,
+                          -29.75 11.0876 -5.77186,
+                          -29.75 8.03485 -9.57556,
+                          -44.75 11.0876 -5.77186,
+                          -29.75 3.75882 -11.9215,
+                          -44.75 8.03485 -9.57556,
+                          -29.75 8.03485 -9.57556,
+                          -44.75 3.75882 -11.9215,
+                          -44.75 8.03485 -9.57556,
+                          -29.75 3.75882 -11.9215,
+                          -44.75 15.1561 -8.74874,
+                          -44.75 8.03485 -9.57556,
+                          -44.75 11.2488 -13.4058,
+                          -44.75 3.75882 -11.9215,
+                          -44.75 11.2488 -13.4058,
+                          -44.75 8.03485 -9.57556,
+                          -29.75 -1.36808 -3.75877,
+                          -29.75 3.75882 -11.9215,
+                          -29.75 8.03485 -9.57556,
+                          -29.75 0.694593 -3.93923,
+                          -29.75 -1.36808 -3.75877,
+                          -29.75 8.03485 -9.57556,
+                          -29.75 -3.75882 11.9215,
+                          -29.75 11.0876 -5.77186,
+                          -29.75 12.4524 -1.08945,
+                          -29.75 1.08945 12.4524,
+                          -29.75 12.4524 -1.08945,
+                          -29.75 11.9215 3.75882,
+                          -29.75 -3.75882 11.9215,
+                          -29.75 12.4524 -1.08945,
+                          -29.75 1.08945 12.4524,
+                          -29.75 5.77186 11.0876,
+                          -29.75 11.9215 3.75882,
+                          -29.75 9.57556 8.03485,
+                          -29.75 1.08945 12.4524,
+                          -29.75 11.9215 3.75882,
+                          -29.75 5.77186 11.0876,
+                          -44.75 -11.0876 5.77186,
+                          -29.75 -11.0876 5.77186,
+                          -29.75 -8.03485 9.57556,
+                          -29.75 -12.4524 1.08945,
+                          -29.75 -1.08945 -12.4524,
+                          -29.75 3.75882 -11.9215,
+                          -44.75 3.75882 -11.9215,
+                          -29.75 3.75882 -11.9215,
+                          -29.75 -1.08945 -12.4524,
+                          -29.75 -11.0876 5.77186,
+                          -29.75 -12.4524 1.08945,
+                          -29.75 3.75882 -11.9215,
+                          -29.75 -3.06418 -2.57115,
+                          -29.75 -11.0876 5.77186,
+                          -29.75 3.75882 -11.9215,
+                          -29.75 -1.36808 -3.75877,
+                          -29.75 -3.06418 -2.57115,
+                          -29.75 3.75882 -11.9215,
+                          -29.75 -11.9215 -3.75882,
+                          -29.75 -5.77186 -11.0876,
+                          -29.75 -1.08945 -12.4524,
+                          -44.75 -1.08945 -12.4524,
+                          -29.75 -1.08945 -12.4524,
+                          -29.75 -5.77186 -11.0876,
+                          -29.75 -12.4524 1.08945,
+                          -29.75 -11.9215 -3.75882,
+                          -29.75 -1.08945 -12.4524,
+                          -44.75 3.75882 -11.9215,
+                          -29.75 -1.08945 -12.4524,
+                          -44.75 -1.08945 -12.4524,
+                          -29.75 -11.9215 -3.75882,
+                          -29.75 -9.57556 -8.03485,
+                          -29.75 -5.77186 -11.0876,
+                          -44.75 -5.77186 -11.0876,
+                          -29.75 -5.77186 -11.0876,
+                          -29.75 -9.57556 -8.03485,
+                          -44.75 -1.08945 -12.4524,
+                          -29.75 -5.77186 -11.0876,
+                          -44.75 -5.77186 -11.0876,
+                          -44.75 -9.57556 -8.03485,
+                          -29.75 -9.57556 -8.03485,
+                          -29.75 -11.9215 -3.75882,
+                          -44.75 -5.77186 -11.0876,
+                          -29.75 -9.57556 -8.03485,
+                          -44.75 -9.57556 -8.03485,
+                          -44.75 -11.9215 -3.75882,
+                          -29.75 -11.9215 -3.75882,
+                          -29.75 -12.4524 1.08945,
+                          -44.75 -9.57556 -8.03485,
+                          -29.75 -11.9215 -3.75882,
+                          -44.75 -11.9215 -3.75882,
+                          -44.75 -12.4524 1.08945,
+                          -29.75 -12.4524 1.08945,
+                          -29.75 -11.0876 5.77186,
+                          -44.75 -11.9215 -3.75882,
+                          -29.75 -12.4524 1.08945,
+                          -44.75 -12.4524 1.08945,
+                          -29.75 -3.93923 -0.694593,
+                          -29.75 -3.75877 1.36808,
+                          -29.75 -11.0876 5.77186,
+                          -29.75 -3.06418 -2.57115,
+                          -29.75 -3.93923 -0.694593,
+                          -29.75 -11.0876 5.77186,
+                          -44.75 -12.4524 1.08945,
+                          -29.75 -11.0876 5.77186,
+                          -44.75 -11.0876 5.77186,
+                          30.75 -3.75877 1.36808,
+                          -29.75 -3.75877 1.36808,
+                          -29.75 -3.93923 -0.694593,
+                          30.75 -3.93923 -0.694593,
+                          -29.75 -3.93923 -0.694593,
+                          -29.75 -3.06418 -2.57115,
+                          30.75 -3.75877 1.36808,
+                          -29.75 -3.93923 -0.694593,
+                          30.75 -3.93923 -0.694593,
+                          30.75 -3.06418 -2.57115,
+                          -29.75 -3.06418 -2.57115,
+                          -29.75 -1.36808 -3.75877,
+                          30.75 -3.93923 -0.694593,
+                          -29.75 -3.06418 -2.57115,
+                          30.75 -3.06418 -2.57115,
+                          30.75 -1.36808 -3.75877,
+                          -29.75 -1.36808 -3.75877,
+                          -29.75 0.694593 -3.93923,
+                          30.75 -3.06418 -2.57115,
+                          -29.75 -1.36808 -3.75877,
+                          30.75 -1.36808 -3.75877,
+                          30.75 -1.36808 -3.75877,
+                          -29.75 0.694593 -3.93923,
+                          30.75 0.694593 -3.93923,
+                          -49.5 -10.0216 22.9031,
+                          -49.5 -0.519855 2.95447,
+                          -49.5 -1.92836 2.29813,
+                          -61.5 -1.92836 2.29813,
+                          -49.5 -1.92836 2.29813,
+                          -49.5 -0.519855 2.95447,
+                          -49.5 -16.0697 19.1511,
+                          -49.5 -1.92836 2.29813,
+                          -49.5 -2.81931 1.025,
+                          -61.5 -2.81931 1.025,
+                          -49.5 -2.81931 1.025,
+                          -49.5 -1.92836 2.29813,
+                          -49.5 -10.0216 22.9031,
+                          -49.5 -1.92836 2.29813,
+                          -49.5 -16.0697 19.1511,
+                          -61.5 -2.81931 1.025,
+                          -49.5 -1.92836 2.29813,
+                          -61.5 -1.92836 2.29813,
+                          -49.5 -10.0216 22.9031,
+                          -49.5 1.02675 2.81844,
+                          -49.5 -0.519855 2.95447,
+                          -61.5 -0.519855 2.95447,
+                          -49.5 -0.519855 2.95447,
+                          -49.5 1.02675 2.81844,
+                          -61.5 -0.519855 2.95447,
+                          -61.5 -1.92836 2.29813,
+                          -49.5 -0.519855 2.95447,
+                          -49.5 -10.0216 22.9031,
+                          -49.5 2.29778 1.92806,
+                          -49.5 1.02675 2.81844,
+                          -61.5 1.02675 2.81844,
+                          -49.5 1.02675 2.81844,
+                          -49.5 2.29778 1.92806,
+                          -61.5 -0.519855 2.95447,
+                          -49.5 1.02675 2.81844,
+                          -61.5 1.02675 2.81844,
+                          -49.5 16.0697 -19.1511,
+                          -49.5 2.95391 0.521736,
+                          -49.5 2.29778 1.92806,
+                          -61.5 2.29778 1.92806,
+                          -49.5 2.29778 1.92806,
+                          -49.5 2.95391 0.521736,
+                          -49.5 -10.0216 22.9031,
+                          -49.5 16.0697 -19.1511,
+                          -49.5 2.29778 1.92806,
+                          -61.5 1.02675 2.81844,
+                          -49.5 2.29778 1.92806,
+                          -61.5 2.29778 1.92806,
+                          -49.5 16.0697 -19.1511,
+                          -49.5 2.81931 -1.025,
+                          -49.5 2.95391 0.521736,
+                          -61.5 2.95391 0.521736,
+                          -49.5 2.95391 0.521736,
+                          -49.5 2.81931 -1.025,
+                          -61.5 2.29778 1.92806,
+                          -49.5 2.95391 0.521736,
+                          -61.5 2.95391 0.521736,
+                          -49.5 16.0697 -19.1511,
+                          -49.5 1.92836 -2.29813,
+                          -49.5 2.81931 -1.025,
+                          -61.5 2.81931 -1.025,
+                          -49.5 2.81931 -1.025,
+                          -49.5 1.92836 -2.29813,
+                          -61.5 2.95391 0.521736,
+                          -49.5 2.81931 -1.025,
+                          -61.5 2.81931 -1.025,
+                          -49.5 10.0216 -22.9031,
+                          -49.5 0.519855 -2.95447,
+                          -49.5 1.92836 -2.29813,
+                          -61.5 1.92836 -2.29813,
+                          -49.5 1.92836 -2.29813,
+                          -49.5 0.519855 -2.95447,
+                          -49.5 16.0697 -19.1511,
+                          -49.5 10.0216 -22.9031,
+                          -49.5 1.92836 -2.29813,
+                          -61.5 2.81931 -1.025,
+                          -49.5 1.92836 -2.29813,
+                          -61.5 1.92836 -2.29813,
+                          -49.5 10.0216 -22.9031,
+                          -49.5 -1.02675 -2.81844,
+                          -49.5 0.519855 -2.95447,
+                          -61.5 0.519855 -2.95447,
+                          -49.5 0.519855 -2.95447,
+                          -49.5 -1.02675 -2.81844,
+                          -61.5 1.92836 -2.29813,
+                          -49.5 0.519855 -2.95447,
+                          -61.5 0.519855 -2.95447,
+                          -49.5 10.0216 -22.9031,
+                          -49.5 -2.29778 -1.92806,
+                          -49.5 -1.02675 -2.81844,
+                          -61.5 -1.02675 -2.81844,
+                          -49.5 -1.02675 -2.81844,
+                          -49.5 -2.29778 -1.92806,
+                          -61.5 0.519855 -2.95447,
+                          -49.5 -1.02675 -2.81844,
+                          -61.5 -1.02675 -2.81844,
+                          -49.5 -16.0697 19.1511,
+                          -49.5 -2.95391 -0.521736,
+                          -49.5 -2.29778 -1.92806,
+                          -61.5 -2.29778 -1.92806,
+                          -49.5 -2.29778 -1.92806,
+                          -49.5 -2.95391 -0.521736,
+                          -49.5 10.0216 -22.9031,
+                          -49.5 -16.0697 19.1511,
+                          -49.5 -2.29778 -1.92806,
+                          -61.5 -1.02675 -2.81844,
+                          -49.5 -2.29778 -1.92806,
+                          -61.5 -2.29778 -1.92806,
+                          -49.5 -16.0697 19.1511,
+                          -49.5 -2.81931 1.025,
+                          -49.5 -2.95391 -0.521736,
+                          -61.5 -2.95391 -0.521736,
+                          -49.5 -2.95391 -0.521736,
+                          -49.5 -2.81931 1.025,
+                          -61.5 -2.29778 -1.92806,
+                          -49.5 -2.95391 -0.521736,
+                          -61.5 -2.95391 -0.521736,
+                          -61.5 -2.95391 -0.521736,
+                          -49.5 -2.81931 1.025,
+                          -61.5 -2.81931 1.025,
+                          -49.5 10.0216 -22.9031,
+                          -49.5 -20.815 13.8464,
+                          -49.5 -16.0697 19.1511,
+                          -45.5 -16.0697 19.1511,
+                          -49.5 -16.0697 19.1511,
+                          -49.5 -20.815 13.8464,
+                          -45.5 -10.0216 22.9031,
+                          -49.5 -10.0216 22.9031,
+                          -49.5 -16.0697 19.1511,
+                          -45.5 -16.0697 19.1511,
+                          -45.5 -10.0216 22.9031,
+                          -49.5 -16.0697 19.1511,
+                          -49.5 3.16518 -24.7984,
+                          -49.5 -23.872 7.42329,
+                          -49.5 -20.815 13.8464,
+                          -45.5 -20.815 13.8464,
+                          -49.5 -20.815 13.8464,
+                          -49.5 -23.872 7.42329,
+                          -49.5 10.0216 -22.9031,
+                          -49.5 3.16518 -24.7984,
+                          -49.5 -20.815 13.8464,
+                          -45.5 -20.815 13.8464,
+                          -45.5 -16.0697 19.1511,
+                          -49.5 -20.815 13.8464,
+                          -49.5 -3.94825 -24.6861,
+                          -49.5 -24.9967 0.398431,
+                          -49.5 -23.872 7.42329,
+                          -45.5 -23.872 7.42329,
+                          -49.5 -23.872 7.42329,
+                          -49.5 -24.9967 0.398431,
+                          -49.5 3.16518 -24.7984,
+                          -49.5 -3.94825 -24.6861,
+                          -49.5 -23.872 7.42329,
+                          -45.5 -20.815 13.8464,
+                          -49.5 -23.872 7.42329,
+                          -45.5 -23.872 7.42329,
+                          -49.5 -10.746 -22.5726,
+                          -49.5 -24.0957 -6.66306,
+                          -49.5 -24.9967 0.398431,
+                          -45.5 -24.9967 0.398431,
+                          -49.5 -24.9967 0.398431,
+                          -49.5 -24.0957 -6.66306,
+                          -49.5 -3.94825 -24.6861,
+                          -49.5 -10.746 -22.5726,
+                          -49.5 -24.9967 0.398431,
+                          -45.5 -23.872 7.42329,
+                          -49.5 -24.9967 0.398431,
+                          -45.5 -24.9967 0.398431,
+                          -49.5 -16.6699 -18.6305,
+                          -49.5 -21.2422 -13.1815,
+                          -49.5 -24.0957 -6.66306,
+                          -45.5 -24.0957 -6.66306,
+                          -49.5 -24.0957 -6.66306,
+                          -49.5 -21.2422 -13.1815,
+                          -49.5 -10.746 -22.5726,
+                          -49.5 -16.6699 -18.6305,
+                          -49.5 -24.0957 -6.66306,
+                          -45.5 -24.9967 0.398431,
+                          -49.5 -24.0957 -6.66306,
+                          -45.5 -24.0957 -6.66306,
+                          -45.5 -21.2422 -13.1815,
+                          -49.5 -21.2422 -13.1815,
+                          -49.5 -16.6699 -18.6305,
+                          -45.5 -24.0957 -6.66306,
+                          -49.5 -21.2422 -13.1815,
+                          -45.5 -21.2422 -13.1815,
+                          -45.5 -16.6699 -18.6305,
+                          -49.5 -16.6699 -18.6305,
+                          -49.5 -10.746 -22.5726,
+                          -45.5 -21.2422 -13.1815,
+                          -49.5 -16.6699 -18.6305,
+                          -45.5 -16.6699 -18.6305,
+                          -45.5 -10.746 -22.5726,
+                          -49.5 -10.746 -22.5726,
+                          -49.5 -3.94825 -24.6861,
+                          -45.5 -16.6699 -18.6305,
+                          -49.5 -10.746 -22.5726,
+                          -45.5 -10.746 -22.5726,
+                          -45.5 -3.94825 -24.6861,
+                          -49.5 -3.94825 -24.6861,
+                          -49.5 3.16518 -24.7984,
+                          -45.5 -10.746 -22.5726,
+                          -49.5 -3.94825 -24.6861,
+                          -45.5 -3.94825 -24.6861,
+                          -45.5 3.16518 -24.7984,
+                          -49.5 3.16518 -24.7984,
+                          -49.5 10.0216 -22.9031,
+                          -45.5 -3.94825 -24.6861,
+                          -49.5 3.16518 -24.7984,
+                          -45.5 3.16518 -24.7984,
+                          -45.5 10.0216 -22.9031,
+                          -49.5 10.0216 -22.9031,
+                          -49.5 16.0697 -19.1511,
+                          -45.5 3.16518 -24.7984,
+                          -49.5 10.0216 -22.9031,
+                          -45.5 10.0216 -22.9031,
+                          -49.5 -10.0216 22.9031,
+                          -49.5 20.815 -13.8464,
+                          -49.5 16.0697 -19.1511,
+                          -45.5 16.0697 -19.1511,
+                          -49.5 16.0697 -19.1511,
+                          -49.5 20.815 -13.8464,
+                          -45.5 10.0216 -22.9031,
+                          -49.5 16.0697 -19.1511,
+                          -45.5 16.0697 -19.1511,
+                          -49.5 -3.16518 24.7984,
+                          -49.5 23.872 -7.42329,
+                          -49.5 20.815 -13.8464,
+                          -45.5 20.815 -13.8464,
+                          -49.5 20.815 -13.8464,
+                          -49.5 23.872 -7.42329,
+                          -49.5 -10.0216 22.9031,
+                          -49.5 -3.16518 24.7984,
+                          -49.5 20.815 -13.8464,
+                          -45.5 20.815 -13.8464,
+                          -45.5 16.0697 -19.1511,
+                          -49.5 20.815 -13.8464,
+                          -49.5 3.94825 24.6861,
+                          -49.5 24.9967 -0.398431,
+                          -49.5 23.872 -7.42329,
+                          -45.5 23.872 -7.42329,
+                          -49.5 23.872 -7.42329,
+                          -49.5 24.9967 -0.398431,
+                          -49.5 -3.16518 24.7984,
+                          -49.5 3.94825 24.6861,
+                          -49.5 23.872 -7.42329,
+                          -45.5 23.872 -7.42329,
+                          -45.5 20.815 -13.8464,
+                          -49.5 23.872 -7.42329,
+                          -49.5 10.746 22.5726,
+                          -49.5 24.0957 6.66306,
+                          -49.5 24.9967 -0.398431,
+                          -45.5 24.9967 -0.398431,
+                          -49.5 24.9967 -0.398431,
+                          -49.5 24.0957 6.66306,
+                          -49.5 3.94825 24.6861,
+                          -49.5 10.746 22.5726,
+                          -49.5 24.9967 -0.398431,
+                          -45.5 24.9967 -0.398431,
+                          -45.5 23.872 -7.42329,
+                          -49.5 24.9967 -0.398431,
+                          -49.5 16.6699 18.6305,
+                          -49.5 21.2422 13.1815,
+                          -49.5 24.0957 6.66306,
+                          -45.5 24.0957 6.66306,
+                          -49.5 24.0957 6.66306,
+                          -49.5 21.2422 13.1815,
+                          -49.5 10.746 22.5726,
+                          -49.5 16.6699 18.6305,
+                          -49.5 24.0957 6.66306,
+                          -45.5 24.0957 6.66306,
+                          -45.5 24.9967 -0.398431,
+                          -49.5 24.0957 6.66306,
+                          -45.5 21.2422 13.1815,
+                          -49.5 21.2422 13.1815,
+                          -49.5 16.6699 18.6305,
+                          -45.5 21.2422 13.1815,
+                          -45.5 24.0957 6.66306,
+                          -49.5 21.2422 13.1815,
+                          -45.5 16.6699 18.6305,
+                          -49.5 16.6699 18.6305,
+                          -49.5 10.746 22.5726,
+                          -45.5 16.6699 18.6305,
+                          -45.5 21.2422 13.1815,
+                          -49.5 16.6699 18.6305,
+                          -45.5 10.746 22.5726,
+                          -49.5 10.746 22.5726,
+                          -49.5 3.94825 24.6861,
+                          -45.5 10.746 22.5726,
+                          -45.5 16.6699 18.6305,
+                          -49.5 10.746 22.5726,
+                          -45.5 3.94825 24.6861,
+                          -49.5 3.94825 24.6861,
+                          -49.5 -3.16518 24.7984,
+                          -45.5 3.94825 24.6861,
+                          -45.5 10.746 22.5726,
+                          -49.5 3.94825 24.6861,
+                          -45.5 -3.16518 24.7984,
+                          -49.5 -3.16518 24.7984,
+                          -49.5 -10.0216 22.9031,
+                          -45.5 -3.16518 24.7984,
+                          -45.5 3.94825 24.6861,
+                          -49.5 -3.16518 24.7984,
+                          -45.5 -10.0216 22.9031,
+                          -45.5 -3.16518 24.7984,
+                          -49.5 -10.0216 22.9031,
+                          -45.5 11.2488 -13.4058,
+                          -45.5 16.0697 -19.1511,
+                          -45.5 20.815 -13.8464,
+                          -45.5 5.984 -16.445,
+                          -45.5 10.0216 -22.9031,
+                          -45.5 16.0697 -19.1511,
+                          -45.5 11.2488 -13.4058,
+                          -45.5 5.984 -16.445,
+                          -45.5 16.0697 -19.1511,
+                          -45.5 17.2342 -3.03706,
+                          -45.5 20.815 -13.8464,
+                          -45.5 23.872 -7.42329,
+                          -45.5 15.1561 -8.74874,
+                          -45.5 11.2488 -13.4058,
+                          -45.5 20.815 -13.8464,
+                          -45.5 17.2342 -3.03706,
+                          -45.5 15.1561 -8.74874,
+                          -45.5 20.815 -13.8464,
+                          -45.5 17.2335 3.04012,
+                          -45.5 23.872 -7.42329,
+                          -45.5 24.9967 -0.398431,
+                          -45.5 17.2335 3.04012,
+                          -45.5 17.2342 -3.03706,
+                          -45.5 23.872 -7.42329,
+                          -45.5 3.94825 24.6861,
+                          -45.5 24.9967 -0.398431,
+                          -45.5 24.0957 6.66306,
+                          -45.5 11.2489 13.4051,
+                          -45.5 24.9967 -0.398431,
+                          -45.5 3.94825 24.6861,
+                          -45.5 15.1548 8.75021,
+                          -45.5 17.2335 3.04012,
+                          -45.5 24.9967 -0.398431,
+                          -45.5 11.2489 13.4051,
+                          -45.5 15.1548 8.75021,
+                          -45.5 24.9967 -0.398431,
+                          -45.5 10.746 22.5726,
+                          -45.5 24.0957 6.66306,
+                          -45.5 21.2422 13.1815,
+                          -45.5 3.94825 24.6861,
+                          -45.5 24.0957 6.66306,
+                          -45.5 10.746 22.5726,
+                          -45.5 10.746 22.5726,
+                          -45.5 21.2422 13.1815,
+                          -45.5 16.6699 18.6305,
+                          -45.5 11.2489 13.4051,
+                          -45.5 3.94825 24.6861,
+                          -45.5 -3.16518 24.7984,
+                          -45.5 0.00177073 17.4998,
+                          -45.5 -3.16518 24.7984,
+                          -45.5 -10.0216 22.9031,
+                          -45.5 5.98651 16.4438,
+                          -45.5 11.2489 13.4051,
+                          -45.5 -3.16518 24.7984,
+                          -45.5 0.00177073 17.4998,
+                          -45.5 5.98651 16.4438,
+                          -45.5 -3.16518 24.7984,
+                          -45.5 -5.984 16.445,
+                          -45.5 -10.0216 22.9031,
+                          -45.5 -16.0697 19.1511,
+                          -45.5 -5.984 16.445,
+                          -45.5 0.00177073 17.4998,
+                          -45.5 -10.0216 22.9031,
+                          -45.5 -11.2488 13.4058,
+                          -45.5 -16.0697 19.1511,
+                          -45.5 -20.815 13.8464,
+                          -45.5 -5.984 16.445,
+                          -45.5 -16.0697 19.1511,
+                          -45.5 -11.2488 13.4058,
+                          -45.5 -0.00177073 -17.4998,
+                          -45.5 3.16518 -24.7984,
+                          -45.5 10.0216 -22.9031,
+                          -45.5 5.984 -16.445,
+                          -45.5 -0.00177073 -17.4998,
+                          -45.5 10.0216 -22.9031,
+                          -45.5 -11.2489 -13.4051,
+                          -45.5 -3.94825 -24.6861,
+                          -45.5 3.16518 -24.7984,
+                          -45.5 -5.98651 -16.4438,
+                          -45.5 -11.2489 -13.4051,
+                          -45.5 3.16518 -24.7984,
+                          -45.5 -0.00177073 -17.4998,
+                          -45.5 -5.98651 -16.4438,
+                          -45.5 3.16518 -24.7984,
+                          -45.5 -24.0957 -6.66306,
+                          -45.5 -10.746 -22.5726,
+                          -45.5 -3.94825 -24.6861,
+                          -45.5 -24.9967 0.398431,
+                          -45.5 -24.0957 -6.66306,
+                          -45.5 -3.94825 -24.6861,
+                          -45.5 -11.2489 -13.4051,
+                          -45.5 -24.9967 0.398431,
+                          -45.5 -3.94825 -24.6861,
+                          -45.5 -21.2422 -13.1815,
+                          -45.5 -16.6699 -18.6305,
+                          -45.5 -10.746 -22.5726,
+                          -45.5 -24.0957 -6.66306,
+                          -45.5 -21.2422 -13.1815,
+                          -45.5 -10.746 -22.5726,
+                          -45.5 -17.2335 -3.04012,
+                          -45.5 -23.872 7.42329,
+                          -45.5 -24.9967 0.398431,
+                          -45.5 -15.1548 -8.75021,
+                          -45.5 -17.2335 -3.04012,
+                          -45.5 -24.9967 0.398431,
+                          -45.5 -11.2489 -13.4051,
+                          -45.5 -15.1548 -8.75021,
+                          -45.5 -24.9967 0.398431,
+                          -45.5 -17.2342 3.03706,
+                          -45.5 -20.815 13.8464,
+                          -45.5 -23.872 7.42329,
+                          -45.5 -17.2335 -3.04012,
+                          -45.5 -17.2342 3.03706,
+                          -45.5 -23.872 7.42329,
+                          -45.5 -15.1561 8.74874,
+                          -45.5 -11.2488 13.4058,
+                          -45.5 -20.815 13.8464,
+                          -45.5 -17.2342 3.03706,
+                          -45.5 -15.1561 8.74874,
+                          -45.5 -20.815 13.8464,
+                          -44.75 -11.2488 13.4058,
+                          -45.5 -11.2488 13.4058,
+                          -45.5 -15.1561 8.74874,
+                          -44.75 -5.984 16.445,
+                          -45.5 -5.984 16.445,
+                          -45.5 -11.2488 13.4058,
+                          -44.75 -11.2488 13.4058,
+                          -44.75 -5.984 16.445,
+                          -45.5 -11.2488 13.4058,
+                          -44.75 -15.1561 8.74874,
+                          -45.5 -15.1561 8.74874,
+                          -45.5 -17.2342 3.03706,
+                          -44.75 -15.1561 8.74874,
+                          -44.75 -11.2488 13.4058,
+                          -45.5 -15.1561 8.74874,
+                          -44.75 -17.2342 3.03706,
+                          -45.5 -17.2342 3.03706,
+                          -45.5 -17.2335 -3.04012,
+                          -44.75 -15.1561 8.74874,
+                          -45.5 -17.2342 3.03706,
+                          -44.75 -17.2342 3.03706,
+                          -44.75 -17.2335 -3.04012,
+                          -45.5 -17.2335 -3.04012,
+                          -45.5 -15.1548 -8.75021,
+                          -44.75 -17.2342 3.03706,
+                          -45.5 -17.2335 -3.04012,
+                          -44.75 -17.2335 -3.04012,
+                          -44.75 -15.1548 -8.75021,
+                          -45.5 -15.1548 -8.75021,
+                          -45.5 -11.2489 -13.4051,
+                          -44.75 -17.2335 -3.04012,
+                          -45.5 -15.1548 -8.75021,
+                          -44.75 -15.1548 -8.75021,
+                          -44.75 -11.2489 -13.4051,
+                          -45.5 -11.2489 -13.4051,
+                          -45.5 -5.98651 -16.4438,
+                          -44.75 -15.1548 -8.75021,
+                          -45.5 -11.2489 -13.4051,
+                          -44.75 -11.2489 -13.4051,
+                          -44.75 -5.98651 -16.4438,
+                          -45.5 -5.98651 -16.4438,
+                          -45.5 -0.00177073 -17.4998,
+                          -44.75 -11.2489 -13.4051,
+                          -45.5 -5.98651 -16.4438,
+                          -44.75 -5.98651 -16.4438,
+                          -44.75 -0.00177073 -17.4998,
+                          -45.5 -0.00177073 -17.4998,
+                          -45.5 5.984 -16.445,
+                          -44.75 -5.98651 -16.4438,
+                          -45.5 -0.00177073 -17.4998,
+                          -44.75 -0.00177073 -17.4998,
+                          -44.75 5.984 -16.445,
+                          -45.5 5.984 -16.445,
+                          -45.5 11.2488 -13.4058,
+                          -44.75 -0.00177073 -17.4998,
+                          -45.5 5.984 -16.445,
+                          -44.75 5.984 -16.445,
+                          -44.75 11.2488 -13.4058,
+                          -45.5 11.2488 -13.4058,
+                          -45.5 15.1561 -8.74874,
+                          -44.75 5.984 -16.445,
+                          -45.5 11.2488 -13.4058,
+                          -44.75 11.2488 -13.4058,
+                          -44.75 15.1561 -8.74874,
+                          -45.5 15.1561 -8.74874,
+                          -45.5 17.2342 -3.03706,
+                          -44.75 15.1561 -8.74874,
+                          -44.75 11.2488 -13.4058,
+                          -45.5 15.1561 -8.74874,
+                          -44.75 17.2342 -3.03706,
+                          -45.5 17.2342 -3.03706,
+                          -45.5 17.2335 3.04012,
+                          -44.75 17.2342 -3.03706,
+                          -44.75 15.1561 -8.74874,
+                          -45.5 17.2342 -3.03706,
+                          -44.75 17.2335 3.04012,
+                          -45.5 17.2335 3.04012,
+                          -45.5 15.1548 8.75021,
+                          -44.75 17.2335 3.04012,
+                          -44.75 17.2342 -3.03706,
+                          -45.5 17.2335 3.04012,
+                          -44.75 15.1548 8.75021,
+                          -45.5 15.1548 8.75021,
+                          -45.5 11.2489 13.4051,
+                          -44.75 15.1548 8.75021,
+                          -44.75 17.2335 3.04012,
+                          -45.5 15.1548 8.75021,
+                          -44.75 11.2489 13.4051,
+                          -45.5 11.2489 13.4051,
+                          -45.5 5.98651 16.4438,
+                          -44.75 11.2489 13.4051,
+                          -44.75 15.1548 8.75021,
+                          -45.5 11.2489 13.4051,
+                          -44.75 5.98651 16.4438,
+                          -45.5 5.98651 16.4438,
+                          -45.5 0.00177073 17.4998,
+                          -44.75 5.98651 16.4438,
+                          -44.75 11.2489 13.4051,
+                          -45.5 5.98651 16.4438,
+                          -44.75 0.00177073 17.4998,
+                          -45.5 0.00177073 17.4998,
+                          -45.5 -5.984 16.445,
+                          -44.75 0.00177073 17.4998,
+                          -44.75 5.98651 16.4438,
+                          -45.5 0.00177073 17.4998,
+                          -44.75 -5.984 16.445,
+                          -44.75 0.00177073 17.4998,
+                          -45.5 -5.984 16.445,
+                          -44.75 3.75882 -11.9215,
+                          -44.75 5.984 -16.445,
+                          -44.75 11.2488 -13.4058,
+                          -44.75 5.98651 16.4438,
+                          -44.75 17.2335 3.04012,
+                          -44.75 15.1548 8.75021,
+                          -44.75 0.00177073 17.4998,
+                          -44.75 17.2335 3.04012,
+                          -44.75 5.98651 16.4438,
+                          -44.75 5.98651 16.4438,
+                          -44.75 15.1548 8.75021,
+                          -44.75 11.2489 13.4051,
+                          -44.75 -1.08945 -12.4524,
+                          -44.75 -0.00177073 -17.4998,
+                          -44.75 5.984 -16.445,
+                          -44.75 3.75882 -11.9215,
+                          -44.75 -1.08945 -12.4524,
+                          -44.75 5.984 -16.445,
+                          -44.75 -17.2335 -3.04012,
+                          -44.75 -5.98651 -16.4438,
+                          -44.75 -0.00177073 -17.4998,
+                          -44.75 -9.57556 -8.03485,
+                          -44.75 -17.2335 -3.04012,
+                          -44.75 -0.00177073 -17.4998,
+                          -44.75 -5.77186 -11.0876,
+                          -44.75 -9.57556 -8.03485,
+                          -44.75 -0.00177073 -17.4998,
+                          -44.75 -1.08945 -12.4524,
+                          -44.75 -5.77186 -11.0876,
+                          -44.75 -0.00177073 -17.4998,
+                          -44.75 -15.1548 -8.75021,
+                          -44.75 -11.2489 -13.4051,
+                          -44.75 -5.98651 -16.4438,
+                          -44.75 -17.2335 -3.04012,
+                          -44.75 -15.1548 -8.75021,
+                          -44.75 -5.98651 -16.4438,
+                          -44.75 -11.9215 -3.75882,
+                          -44.75 -17.2342 3.03706,
+                          -44.75 -17.2335 -3.04012,
+                          -44.75 -9.57556 -8.03485,
+                          -44.75 -11.9215 -3.75882,
+                          -44.75 -17.2335 -3.04012,
+                          -44.75 -12.4524 1.08945,
+                          -44.75 -15.1561 8.74874,
+                          -44.75 -17.2342 3.03706,
+                          -44.75 -11.9215 -3.75882,
+                          -44.75 -12.4524 1.08945,
+                          -44.75 -17.2342 3.03706,
+                          -44.75 -12.4524 1.08945,
+                          -44.75 -11.0876 5.77186,
+                          -44.75 -15.1561 8.74874,
+                          -61.5 0.519855 -2.95447,
+                          -61.5 -2.81931 1.025,
+                          -61.5 -1.92836 2.29813,
+                          -61.5 1.92836 -2.29813,
+                          -61.5 0.519855 -2.95447,
+                          -61.5 -1.92836 2.29813,
+                          -61.5 -0.519855 2.95447,
+                          -61.5 1.92836 -2.29813,
+                          -61.5 -1.92836 2.29813,
+                          -61.5 -1.02675 -2.81844,
+                          -61.5 -2.95391 -0.521736,
+                          -61.5 -2.81931 1.025,
+                          -61.5 0.519855 -2.95447,
+                          -61.5 -1.02675 -2.81844,
+                          -61.5 -2.81931 1.025,
+                          -61.5 -1.02675 -2.81844,
+                          -61.5 -2.29778 -1.92806,
+                          -61.5 -2.95391 -0.521736,
+                          -61.5 -0.519855 2.95447,
+                          -61.5 2.81931 -1.025,
+                          -61.5 1.92836 -2.29813,
+                          -61.5 1.02675 2.81844,
+                          -61.5 2.95391 0.521736,
+                          -61.5 2.81931 -1.025,
+                          -61.5 -0.519855 2.95447,
+                          -61.5 1.02675 2.81844,
+                          -61.5 2.81931 -1.025,
+                          -61.5 1.02675 2.81844,
+                          -61.5 2.29778 1.92806,
+                          -61.5 2.95391 0.521736,
+                          30.75 3.75882 -11.9215,
+                          30.75 -1.36808 -3.75877,
+                          30.75 0.694593 -3.93923,
+                          30.75 3.75882 -11.9215,
+                          30.75 -3.06418 -2.57115,
+                          30.75 -1.36808 -3.75877,
+                          30.75 -11.0876 5.77186,
+                          30.75 -3.93923 -0.694593,
+                          30.75 -3.06418 -2.57115,
+                          30.75 3.75882 -11.9215,
+                          30.75 -11.0876 5.77186,
+                          30.75 -3.06418 -2.57115,
+                          30.75 -8.03485 9.57556,
+                          30.75 -3.75877 1.36808,
+                          30.75 -3.93923 -0.694593,
+                          30.75 -11.0876 5.77186,
+                          30.75 -8.03485 9.57556,
+                          30.75 -3.93923 -0.694593,
+                          46.75 -8.03485 9.57556,
+                          30.75 -8.03485 9.57556,
+                          30.75 -11.0876 5.77186,
+                          46.75 -3.75882 11.9215,
+                          30.75 -3.75882 11.9215,
+                          30.75 -8.03485 9.57556,
+                          46.75 -8.03485 9.57556,
+                          46.75 -3.75882 11.9215,
+                          30.75 -8.03485 9.57556,
+                          30.75 -1.08945 -12.4524,
+                          30.75 -12.4524 1.08945,
+                          30.75 -11.0876 5.77186,
+                          46.75 -11.0876 5.77186,
+                          30.75 -11.0876 5.77186,
+                          30.75 -12.4524 1.08945,
+                          30.75 3.75882 -11.9215,
+                          30.75 -1.08945 -12.4524,
+                          30.75 -11.0876 5.77186,
+                          46.75 -11.0876 5.77186,
+                          46.75 -8.03485 9.57556,
+                          30.75 -11.0876 5.77186,
+                          30.75 -5.77186 -11.0876,
+                          30.75 -11.9215 -3.75882,
+                          30.75 -12.4524 1.08945,
+                          46.75 -12.4524 1.08945,
+                          30.75 -12.4524 1.08945,
+                          30.75 -11.9215 -3.75882,
+                          30.75 -1.08945 -12.4524,
+                          30.75 -5.77186 -11.0876,
+                          30.75 -12.4524 1.08945,
+                          46.75 -11.0876 5.77186,
+                          30.75 -12.4524 1.08945,
+                          46.75 -12.4524 1.08945,
+                          30.75 -5.77186 -11.0876,
+                          30.75 -9.57556 -8.03485,
+                          30.75 -11.9215 -3.75882,
+                          46.75 -11.9215 -3.75882,
+                          30.75 -11.9215 -3.75882,
+                          30.75 -9.57556 -8.03485,
+                          46.75 -12.4524 1.08945,
+                          30.75 -11.9215 -3.75882,
+                          46.75 -11.9215 -3.75882,
+                          46.75 -9.57556 -8.03485,
+                          30.75 -9.57556 -8.03485,
+                          30.75 -5.77186 -11.0876,
+                          46.75 -11.9215 -3.75882,
+                          30.75 -9.57556 -8.03485,
+                          46.75 -9.57556 -8.03485,
+                          46.75 -5.77186 -11.0876,
+                          30.75 -5.77186 -11.0876,
+                          30.75 -1.08945 -12.4524,
+                          46.75 -9.57556 -8.03485,
+                          30.75 -5.77186 -11.0876,
+                          46.75 -5.77186 -11.0876,
+                          46.75 -1.08945 -12.4524,
+                          30.75 -1.08945 -12.4524,
+                          30.75 3.75882 -11.9215,
+                          46.75 -5.77186 -11.0876,
+                          30.75 -1.08945 -12.4524,
+                          46.75 -1.08945 -12.4524,
+                          46.75 3.75882 -11.9215,
+                          30.75 3.75882 -11.9215,
+                          30.75 8.03485 -9.57556,
+                          46.75 -1.08945 -12.4524,
+                          30.75 3.75882 -11.9215,
+                          46.75 3.75882 -11.9215,
+                          46.75 8.03485 -9.57556,
+                          30.75 8.03485 -9.57556,
+                          30.75 11.0876 -5.77186,
+                          46.75 3.75882 -11.9215,
+                          30.75 8.03485 -9.57556,
+                          46.75 8.03485 -9.57556,
+                          30.75 1.08945 12.4524,
+                          30.75 12.4524 -1.08945,
+                          30.75 11.0876 -5.77186,
+                          46.75 11.0876 -5.77186,
+                          30.75 11.0876 -5.77186,
+                          30.75 12.4524 -1.08945,
+                          30.75 -3.75882 11.9215,
+                          30.75 1.08945 12.4524,
+                          30.75 11.0876 -5.77186,
+                          46.75 11.0876 -5.77186,
+                          46.75 8.03485 -9.57556,
+                          30.75 11.0876 -5.77186,
+                          30.75 5.77186 11.0876,
+                          30.75 11.9215 3.75882,
+                          30.75 12.4524 -1.08945,
+                          46.75 12.4524 -1.08945,
+                          30.75 12.4524 -1.08945,
+                          30.75 11.9215 3.75882,
+                          30.75 1.08945 12.4524,
+                          30.75 5.77186 11.0876,
+                          30.75 12.4524 -1.08945,
+                          46.75 12.4524 -1.08945,
+                          46.75 11.0876 -5.77186,
+                          30.75 12.4524 -1.08945,
+                          30.75 5.77186 11.0876,
+                          30.75 9.57556 8.03485,
+                          30.75 11.9215 3.75882,
+                          46.75 11.9215 3.75882,
+                          30.75 11.9215 3.75882,
+                          30.75 9.57556 8.03485,
+                          46.75 11.9215 3.75882,
+                          46.75 12.4524 -1.08945,
+                          30.75 11.9215 3.75882,
+                          46.75 9.57556 8.03485,
+                          30.75 9.57556 8.03485,
+                          30.75 5.77186 11.0876,
+                          46.75 9.57556 8.03485,
+                          46.75 11.9215 3.75882,
+                          30.75 9.57556 8.03485,
+                          46.75 5.77186 11.0876,
+                          30.75 5.77186 11.0876,
+                          30.75 1.08945 12.4524,
+                          46.75 5.77186 11.0876,
+                          46.75 9.57556 8.03485,
+                          30.75 5.77186 11.0876,
+                          46.75 1.08945 12.4524,
+                          30.75 1.08945 12.4524,
+                          30.75 -3.75882 11.9215,
+                          46.75 1.08945 12.4524,
+                          46.75 5.77186 11.0876,
+                          30.75 1.08945 12.4524,
+                          46.75 -3.75882 11.9215,
+                          46.75 1.08945 12.4524,
+                          30.75 -3.75882 11.9215,
+                          46.75 3.21394 -3.83022,
+                          46.75 8.03485 -9.57556,
+                          46.75 11.0876 -5.77186,
+                          46.75 1.23242 -4.84536,
+                          46.75 -0.990111 -4.90045,
+                          46.75 8.03485 -9.57556,
+                          46.75 3.75882 -11.9215,
+                          46.75 8.03485 -9.57556,
+                          46.75 -0.990111 -4.90045,
+                          46.75 3.21394 -3.83022,
+                          46.75 1.23242 -4.84536,
+                          46.75 8.03485 -9.57556,
+                          46.75 4.44984 2.27983,
+                          46.75 11.0876 -5.77186,
+                          46.75 12.4524 -1.08945,
+                          46.75 4.55774 -2.05509,
+                          46.75 3.21394 -3.83022,
+                          46.75 11.0876 -5.77186,
+                          46.75 4.99793 0.124114,
+                          46.75 4.55774 -2.05509,
+                          46.75 11.0876 -5.77186,
+                          46.75 4.44984 2.27983,
+                          46.75 4.99793 0.124114,
+                          46.75 11.0876 -5.77186,
+                          46.75 1.08945 12.4524,
+                          46.75 12.4524 -1.08945,
+                          46.75 11.9215 3.75882,
+                          46.75 -3.75882 11.9215,
+                          46.75 12.4524 -1.08945,
+                          46.75 1.08945 12.4524,
+                          46.75 3.0179 3.98635,
+                          46.75 12.4524 -1.08945,
+                          46.75 -3.75882 11.9215,
+                          46.75 3.0179 3.98635,
+                          46.75 4.44984 2.27983,
+                          46.75 12.4524 -1.08945,
+                          46.75 5.77186 11.0876,
+                          46.75 11.9215 3.75882,
+                          46.75 9.57556 8.03485,
+                          46.75 1.08945 12.4524,
+                          46.75 11.9215 3.75882,
+                          46.75 5.77186 11.0876,
+                          46.75 0.990111 4.90045,
+                          46.75 -3.75882 11.9215,
+                          46.75 -8.03485 9.57556,
+                          46.75 0.990111 4.90045,
+                          46.75 3.0179 3.98635,
+                          46.75 -3.75882 11.9215,
+                          46.75 -1.23242 4.84536,
+                          46.75 -8.03485 9.57556,
+                          46.75 -3.21394 3.83022,
+                          46.75 -11.0876 5.77186,
+                          46.75 -3.21394 3.83022,
+                          46.75 -8.03485 9.57556,
+                          46.75 -1.23242 4.84536,
+                          46.75 0.990111 4.90045,
+                          46.75 -8.03485 9.57556,
+                          46.75 -11.0876 5.77186,
+                          46.75 -4.55774 2.05509,
+                          46.75 -3.21394 3.83022,
+                          62.75 -3.21394 3.83022,
+                          46.75 -3.21394 3.83022,
+                          46.75 -4.55774 2.05509,
+                          62.75 -1.23242 4.84536,
+                          46.75 -1.23242 4.84536,
+                          46.75 -3.21394 3.83022,
+                          62.75 -3.21394 3.83022,
+                          62.75 -1.23242 4.84536,
+                          46.75 -3.21394 3.83022,
+                          46.75 -11.0876 5.77186,
+                          46.75 -4.99793 -0.124114,
+                          46.75 -4.55774 2.05509,
+                          62.75 -4.55774 2.05509,
+                          46.75 -4.55774 2.05509,
+                          46.75 -4.99793 -0.124114,
+                          62.75 -4.55774 2.05509,
+                          62.75 -3.21394 3.83022,
+                          46.75 -4.55774 2.05509,
+                          46.75 -11.0876 5.77186,
+                          46.75 -4.44984 -2.27983,
+                          46.75 -4.99793 -0.124114,
+                          62.75 -4.99793 -0.124114,
+                          46.75 -4.99793 -0.124114,
+                          46.75 -4.44984 -2.27983,
+                          62.75 -4.55774 2.05509,
+                          46.75 -4.99793 -0.124114,
+                          62.75 -4.99793 -0.124114,
+                          46.75 -12.4524 1.08945,
+                          46.75 -3.0179 -3.98635,
+                          46.75 -4.44984 -2.27983,
+                          62.75 -4.44984 -2.27983,
+                          46.75 -4.44984 -2.27983,
+                          46.75 -3.0179 -3.98635,
+                          46.75 -11.0876 5.77186,
+                          46.75 -12.4524 1.08945,
+                          46.75 -4.44984 -2.27983,
+                          62.75 -4.99793 -0.124114,
+                          46.75 -4.44984 -2.27983,
+                          62.75 -4.44984 -2.27983,
+                          46.75 3.75882 -11.9215,
+                          46.75 -0.990111 -4.90045,
+                          46.75 -3.0179 -3.98635,
+                          62.75 -3.0179 -3.98635,
+                          46.75 -3.0179 -3.98635,
+                          46.75 -0.990111 -4.90045,
+                          46.75 -12.4524 1.08945,
+                          46.75 3.75882 -11.9215,
+                          46.75 -3.0179 -3.98635,
+                          62.75 -4.44984 -2.27983,
+                          46.75 -3.0179 -3.98635,
+                          62.75 -3.0179 -3.98635,
+                          62.75 -0.990111 -4.90045,
+                          46.75 -0.990111 -4.90045,
+                          46.75 1.23242 -4.84536,
+                          62.75 -3.0179 -3.98635,
+                          46.75 -0.990111 -4.90045,
+                          62.75 -0.990111 -4.90045,
+                          62.75 1.23242 -4.84536,
+                          46.75 1.23242 -4.84536,
+                          46.75 3.21394 -3.83022,
+                          62.75 -0.990111 -4.90045,
+                          46.75 1.23242 -4.84536,
+                          62.75 1.23242 -4.84536,
+                          62.75 3.21394 -3.83022,
+                          46.75 3.21394 -3.83022,
+                          46.75 4.55774 -2.05509,
+                          62.75 1.23242 -4.84536,
+                          46.75 3.21394 -3.83022,
+                          62.75 3.21394 -3.83022,
+                          62.75 4.55774 -2.05509,
+                          46.75 4.55774 -2.05509,
+                          46.75 4.99793 0.124114,
+                          62.75 4.55774 -2.05509,
+                          62.75 3.21394 -3.83022,
+                          46.75 4.55774 -2.05509,
+                          62.75 4.99793 0.124114,
+                          46.75 4.99793 0.124114,
+                          46.75 4.44984 2.27983,
+                          62.75 4.99793 0.124114,
+                          62.75 4.55774 -2.05509,
+                          46.75 4.99793 0.124114,
+                          62.75 4.44984 2.27983,
+                          46.75 4.44984 2.27983,
+                          46.75 3.0179 3.98635,
+                          62.75 4.44984 2.27983,
+                          62.75 4.99793 0.124114,
+                          46.75 4.44984 2.27983,
+                          62.75 3.0179 3.98635,
+                          46.75 3.0179 3.98635,
+                          46.75 0.990111 4.90045,
+                          62.75 3.0179 3.98635,
+                          62.75 4.44984 2.27983,
+                          46.75 3.0179 3.98635,
+                          62.75 0.990111 4.90045,
+                          46.75 0.990111 4.90045,
+                          46.75 -1.23242 4.84536,
+                          62.75 0.990111 4.90045,
+                          62.75 3.0179 3.98635,
+                          46.75 0.990111 4.90045,
+                          62.75 -1.23242 4.84536,
+                          62.75 0.990111 4.90045,
+                          46.75 -1.23242 4.84536,
+                          46.75 -12.4524 1.08945,
+                          46.75 -1.08945 -12.4524,
+                          46.75 3.75882 -11.9215,
+                          46.75 -11.9215 -3.75882,
+                          46.75 -5.77186 -11.0876,
+                          46.75 -1.08945 -12.4524,
+                          46.75 -12.4524 1.08945,
+                          46.75 -11.9215 -3.75882,
+                          46.75 -1.08945 -12.4524,
+                          46.75 -11.9215 -3.75882,
+                          46.75 -9.57556 -8.03485,
+                          46.75 -5.77186 -11.0876,
+                          62.75 -3.21394 3.83022,
+                          62.75 3.21394 -3.83022,
+                          62.75 4.55774 -2.05509,
+                          62.75 -4.55774 2.05509,
+                          62.75 3.21394 -3.83022,
+                          62.75 -3.21394 3.83022,
+                          62.75 -4.55774 2.05509,
+                          62.75 1.23242 -4.84536,
+                          62.75 3.21394 -3.83022,
+                          62.75 -1.23242 4.84536,
+                          62.75 4.55774 -2.05509,
+                          62.75 4.99793 0.124114,
+                          62.75 -3.21394 3.83022,
+                          62.75 4.55774 -2.05509,
+                          62.75 -1.23242 4.84536,
+                          62.75 0.990111 4.90045,
+                          62.75 4.99793 0.124114,
+                          62.75 4.44984 2.27983,
+                          62.75 -1.23242 4.84536,
+                          62.75 4.99793 0.124114,
+                          62.75 0.990111 4.90045,
+                          62.75 0.990111 4.90045,
+                          62.75 4.44984 2.27983,
+                          62.75 3.0179 3.98635,
+                          62.75 -4.99793 -0.124114,
+                          62.75 -0.990111 -4.90045,
+                          62.75 1.23242 -4.84536,
+                          62.75 -4.55774 2.05509,
+                          62.75 -4.99793 -0.124114,
+                          62.75 1.23242 -4.84536,
+                          62.75 -4.44984 -2.27983,
+                          62.75 -3.0179 -3.98635,
+                          62.75 -0.990111 -4.90045,
+                          62.75 -4.99793 -0.124114,
+                          62.75 -4.44984 -2.27983,
+                          62.75 -0.990111 -4.90045 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          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,
+                          -1 0 0,
+                          -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 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -41.5 -157 -36.5,
+                          -45.5 -157 -36.5,
+                          -45.5 157 -36.5,
+                          -45.5 157 36.5,
+                          -45.5 157 -36.5,
+                          -45.5 -157 -36.5,
+                          -41.5 157 -36.5,
+                          -41.5 -157 -36.5,
+                          -45.5 157 -36.5,
+                          -45.5 157 36.5,
+                          -41.5 157 -36.5,
+                          -45.5 157 -36.5,
+                          -41.5 -157 36.5,
+                          -45.5 -157 -36.5,
+                          -41.5 -157 -36.5,
+                          -45.5 -157 36.5,
+                          -45.5 -157 -36.5,
+                          -41.5 -157 36.5,
+                          -45.5 157 36.5,
+                          -45.5 -157 -36.5,
+                          -45.5 -157 36.5,
+                          -41.5 -157 36.5,
+                          -41.5 -157 -36.5,
+                          -41.5 157 -36.5,
+                          -41.5 157 36.5,
+                          -41.5 -157 36.5,
+                          -41.5 157 -36.5,
+                          -45.5 157 36.5,
+                          -41.5 157 36.5,
+                          -41.5 157 -36.5,
+                          -45.5 -157 36.5,
+                          -41.5 -157 36.5,
+                          -41.5 157 36.5,
+                          -45.5 157 36.5,
+                          -45.5 -157 36.5,
+                          -41.5 157 36.5 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -1 0 1.22461e-16,
+                          -1 0 1.22461e-16,
+                          -0.965926 0 -0.258819,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.965926 0 0.258819,
+                          -0.965926 0 0.258819,
+                          -1 0 1.22461e-16,
+                          -1 0 1.22461e-16,
+                          -0.965926 0 0.258819,
+                          -1 0 1.22461e-16,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.965926 0 -0.258819,
+                          -0.965926 0 -0.258819,
+                          -0.866025 0 -0.5,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.965926 0 -0.258819,
+                          -1 0 1.22461e-16,
+                          -0.965926 0 -0.258819,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.866025 0 -0.5,
+                          -0.866025 0 -0.5,
+                          -0.707107 0 -0.707107,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.965926 0 -0.258819,
+                          -0.866025 0 -0.5,
+                          -0.866025 0 -0.5,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.707107 0 -0.707107,
+                          -0.707107 0 -0.707107,
+                          -0.5 0 -0.866025,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.866025 0 -0.5,
+                          -0.707107 0 -0.707107,
+                          -0.707107 0 -0.707107,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.5 0 -0.866025,
+                          -0.5 0 -0.866025,
+                          -0.258819 0 -0.965926,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.707107 0 -0.707107,
+                          -0.5 0 -0.866025,
+                          -0.5 0 -0.866025,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.258819 0 -0.965926,
+                          -0.258819 0 -0.965926,
+                          -1.83691e-16 0 -1,
+                          -0.5 0 -0.866025,
+                          -0.258819 0 -0.965926,
+                          -0.258819 0 -0.965926,
+                          -1.83691e-16 0 -1,
+                          -1.83691e-16 0 -1,
+                          0.258819 0 -0.965926,
+                          -0.258819 0 -0.965926,
+                          -1.83691e-16 0 -1,
+                          -1.83691e-16 0 -1,
+                          0.258819 0 -0.965926,
+                          0.258819 0 -0.965926,
+                          0.5 0 -0.866025,
+                          -1.83691e-16 0 -1,
+                          0.258819 0 -0.965926,
+                          0.258819 0 -0.965926,
+                          0.5 0 -0.866025,
+                          0.5 0 -0.866025,
+                          0.707107 0 -0.707107,
+                          0.258819 0 -0.965926,
+                          0.5 0 -0.866025,
+                          0.5 0 -0.866025,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          0.866025 0 -0.5,
+                          0.5 0 -0.866025,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          0.866025 0 -0.5,
+                          0.866025 0 -0.5,
+                          0.965926 0 -0.258819,
+                          0.707107 0 -0.707107,
+                          0.866025 0 -0.5,
+                          0.866025 0 -0.5,
+                          0.965926 0 -0.258819,
+                          0.965926 0 -0.258819,
+                          1 0 -2.44921e-16,
+                          0.866025 0 -0.5,
+                          0.965926 0 -0.258819,
+                          0.965926 0 -0.258819,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          1 0 0,
+                          1 0 0,
+                          0.965926 0 0.258819,
+                          0.965926 0 -0.258819,
+                          1 0 -2.44921e-16,
+                          1 0 -2.44921e-16,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.965926 0 0.258819,
+                          0.965926 0 0.258819,
+                          0.866025 0 0.5,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.965926 0 0.258819,
+                          1 0 0,
+                          0.965926 0 0.258819,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.866025 0 0.5,
+                          0.866025 0 0.5,
+                          0.707107 0 0.707107,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.866025 0 0.5,
+                          0.965926 0 0.258819,
+                          0.866025 0 0.5,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          0.5 0 0.866025,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.707107 0 0.707107,
+                          0.866025 0 0.5,
+                          0.707107 0 0.707107,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.5 0 0.866025,
+                          0.5 0 0.866025,
+                          0.258819 0 0.965926,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.5 0 0.866025,
+                          0.707107 0 0.707107,
+                          0.5 0 0.866025,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.258819 0 0.965926,
+                          0.258819 0 0.965926,
+                          6.12303e-17 0 1,
+                          0.258819 0 0.965926,
+                          0.5 0 0.866025,
+                          0.258819 0 0.965926,
+                          6.12303e-17 0 1,
+                          6.12303e-17 0 1,
+                          -0.258819 0 0.965926,
+                          6.12303e-17 0 1,
+                          0.258819 0 0.965926,
+                          6.12303e-17 0 1,
+                          -0.258819 0 0.965926,
+                          -0.258819 0 0.965926,
+                          -0.5 0 0.866025,
+                          -0.258819 0 0.965926,
+                          6.12303e-17 0 1,
+                          -0.258819 0 0.965926,
+                          -0.5 0 0.866025,
+                          -0.5 0 0.866025,
+                          -0.707107 0 0.707107,
+                          -0.5 0 0.866025,
+                          -0.258819 0 0.965926,
+                          -0.5 0 0.866025,
+                          -0.707107 0 0.707107,
+                          -0.707107 0 0.707107,
+                          -0.866025 0 0.5,
+                          -0.707107 0 0.707107,
+                          -0.5 0 0.866025,
+                          -0.707107 0 0.707107,
+                          -0.866025 0 0.5,
+                          -0.866025 0 0.5,
+                          -0.965926 0 0.258819,
+                          -0.866025 0 0.5,
+                          -0.707107 0 0.707107,
+                          -0.866025 0 0.5,
+                          -0.965926 0 0.258819,
+                          -0.866025 0 0.5,
+                          -0.965926 0 0.258819,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          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.22461e-16,
+                          -1 0 1.22461e-16,
+                          -0.974928 0 -0.222521,
+                          -0.974928 0 0.222521,
+                          -0.974928 0 0.222521,
+                          -1 0 1.22461e-16,
+                          -1 0 1.22461e-16,
+                          -0.974928 0 0.222521,
+                          -1 0 1.22461e-16,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.974928 0 -0.222521,
+                          -0.974928 0 -0.222521,
+                          -0.900969 0 -0.433884,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.974928 0 -0.222521,
+                          -1 0 1.22461e-16,
+                          -0.974928 0 -0.222521,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.900969 0 -0.433884,
+                          -0.900969 0 -0.433884,
+                          -0.781832 0 -0.62349,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.974928 0 -0.222521,
+                          -0.900969 0 -0.433884,
+                          -0.900969 0 -0.433884,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.781832 0 -0.62349,
+                          -0.781832 0 -0.62349,
+                          -0.62349 0 -0.781832,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.900969 0 -0.433884,
+                          -0.781832 0 -0.62349,
+                          -0.781832 0 -0.62349,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.62349 0 -0.781832,
+                          -0.62349 0 -0.781832,
+                          -0.433884 0 -0.900969,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.781832 0 -0.62349,
+                          -0.62349 0 -0.781832,
+                          -0.62349 0 -0.781832,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.433884 0 -0.900969,
+                          -0.433884 0 -0.900969,
+                          -0.222521 0 -0.974928,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.62349 0 -0.781832,
+                          -0.433884 0 -0.900969,
+                          -0.433884 0 -0.900969,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.222521 0 -0.974928,
+                          -0.222521 0 -0.974928,
+                          -1.83691e-16 0 -1,
+                          -0.433884 0 -0.900969,
+                          -0.222521 0 -0.974928,
+                          -0.222521 0 -0.974928,
+                          -1.83691e-16 0 -1,
+                          -1.83691e-16 0 -1,
+                          0.222521 0 -0.974928,
+                          -0.222521 0 -0.974928,
+                          -1.83691e-16 0 -1,
+                          -1.83691e-16 0 -1,
+                          0.222521 0 -0.974928,
+                          0.222521 0 -0.974928,
+                          0.433884 0 -0.900969,
+                          -1.83691e-16 0 -1,
+                          0.222521 0 -0.974928,
+                          0.222521 0 -0.974928,
+                          0.433884 0 -0.900969,
+                          0.433884 0 -0.900969,
+                          0.62349 0 -0.781832,
+                          0.222521 0 -0.974928,
+                          0.433884 0 -0.900969,
+                          0.433884 0 -0.900969,
+                          0.62349 0 -0.781832,
+                          0.62349 0 -0.781832,
+                          0.781832 0 -0.62349,
+                          0.433884 0 -0.900969,
+                          0.62349 0 -0.781832,
+                          0.62349 0 -0.781832,
+                          0.781832 0 -0.62349,
+                          0.781832 0 -0.62349,
+                          0.900969 0 -0.433884,
+                          0.62349 0 -0.781832,
+                          0.781832 0 -0.62349,
+                          0.781832 0 -0.62349,
+                          0.900969 0 -0.433884,
+                          0.900969 0 -0.433884,
+                          0.974928 0 -0.222521,
+                          0.781832 0 -0.62349,
+                          0.900969 0 -0.433884,
+                          0.900969 0 -0.433884,
+                          0.974928 0 -0.222521,
+                          0.974928 0 -0.222521,
+                          1 0 -2.44921e-16,
+                          0.900969 0 -0.433884,
+                          0.974928 0 -0.222521,
+                          0.974928 0 -0.222521,
+                          1 0 0,
+                          1 0 0,
+                          0.974928 0 0.222521,
+                          0.974928 0 -0.222521,
+                          1 0 -2.44921e-16,
+                          1 0 -2.44921e-16,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.974928 0 0.222521,
+                          0.974928 0 0.222521,
+                          0.900969 0 0.433884,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.974928 0 0.222521,
+                          1 0 0,
+                          0.974928 0 0.222521,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.900969 0 0.433884,
+                          0.900969 0 0.433884,
+                          0.781832 0 0.62349,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.900969 0 0.433884,
+                          0.974928 0 0.222521,
+                          0.900969 0 0.433884,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.781832 0 0.62349,
+                          0.781832 0 0.62349,
+                          0.62349 0 0.781832,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.781832 0 0.62349,
+                          0.900969 0 0.433884,
+                          0.781832 0 0.62349,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.62349 0 0.781832,
+                          0.62349 0 0.781832,
+                          0.433884 0 0.900969,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.62349 0 0.781832,
+                          0.781832 0 0.62349,
+                          0.62349 0 0.781832,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.433884 0 0.900969,
+                          0.433884 0 0.900969,
+                          0.222521 0 0.974928,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.433884 0 0.900969,
+                          0.62349 0 0.781832,
+                          0.433884 0 0.900969,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.222521 0 0.974928,
+                          0.222521 0 0.974928,
+                          6.12303e-17 0 1,
+                          0.222521 0 0.974928,
+                          0.433884 0 0.900969,
+                          0.222521 0 0.974928,
+                          6.12303e-17 0 1,
+                          6.12303e-17 0 1,
+                          -0.222521 0 0.974928,
+                          6.12303e-17 0 1,
+                          0.222521 0 0.974928,
+                          6.12303e-17 0 1,
+                          -0.222521 0 0.974928,
+                          -0.222521 0 0.974928,
+                          -0.433884 0 0.900969,
+                          -0.222521 0 0.974928,
+                          6.12303e-17 0 1,
+                          -0.222521 0 0.974928,
+                          -0.433884 0 0.900969,
+                          -0.433884 0 0.900969,
+                          -0.62349 0 0.781832,
+                          -0.433884 0 0.900969,
+                          -0.222521 0 0.974928,
+                          -0.433884 0 0.900969,
+                          -0.62349 0 0.781832,
+                          -0.62349 0 0.781832,
+                          -0.781832 0 0.62349,
+                          -0.62349 0 0.781832,
+                          -0.433884 0 0.900969,
+                          -0.62349 0 0.781832,
+                          -0.781832 0 0.62349,
+                          -0.781832 0 0.62349,
+                          -0.900969 0 0.433884,
+                          -0.781832 0 0.62349,
+                          -0.62349 0 0.781832,
+                          -0.781832 0 0.62349,
+                          -0.900969 0 0.433884,
+                          -0.900969 0 0.433884,
+                          -0.974928 0 0.222521,
+                          -0.900969 0 0.433884,
+                          -0.781832 0 0.62349,
+                          -0.900969 0 0.433884,
+                          -0.974928 0 0.222521,
+                          -0.900969 0 0.433884,
+                          -0.974928 0 0.222521,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 4.82956 -178 -1.29386,
+                          -4.82956 -178 -1.29386,
+                          -5 -178 0,
+                          -5 -181 0,
+                          -5 -178 0,
+                          -4.82956 -178 -1.29386,
+                          5 -178 0,
+                          4.82956 -178 -1.29386,
+                          -5 -178 0,
+                          -4.82956 -178 1.29386,
+                          5 -178 0,
+                          -5 -178 0,
+                          -4.82956 -181 1.29386,
+                          -4.82956 -178 1.29386,
+                          -5 -178 0,
+                          -5 -181 0,
+                          -4.82956 -181 1.29386,
+                          -5 -178 0,
+                          4.32985 -178 -2.5004,
+                          -4.32985 -178 -2.5004,
+                          -4.82956 -178 -1.29386,
+                          -4.82956 -181 -1.29386,
+                          -4.82956 -178 -1.29386,
+                          -4.32985 -178 -2.5004,
+                          4.82956 -178 -1.29386,
+                          4.32985 -178 -2.5004,
+                          -4.82956 -178 -1.29386,
+                          -4.82956 -181 -1.29386,
+                          -5 -181 0,
+                          -4.82956 -178 -1.29386,
+                          3.53583 -178 -3.53513,
+                          -3.53583 -178 -3.53513,
+                          -4.32985 -178 -2.5004,
+                          -4.32985 -181 -2.5004,
+                          -4.32985 -178 -2.5004,
+                          -3.53583 -178 -3.53513,
+                          4.32985 -178 -2.5004,
+                          3.53583 -178 -3.53513,
+                          -4.32985 -178 -2.5004,
+                          -4.82956 -181 -1.29386,
+                          -4.32985 -178 -2.5004,
+                          -4.32985 -181 -2.5004,
+                          2.49961 -178 -4.33023,
+                          -2.49961 -178 -4.33023,
+                          -3.53583 -178 -3.53513,
+                          -3.53583 -181 -3.53513,
+                          -3.53583 -178 -3.53513,
+                          -2.49961 -178 -4.33023,
+                          3.53583 -178 -3.53513,
+                          2.49961 -178 -4.33023,
+                          -3.53583 -178 -3.53513,
+                          -4.32985 -181 -2.5004,
+                          -3.53583 -178 -3.53513,
+                          -3.53583 -181 -3.53513,
+                          1.29442 -178 -4.82953,
+                          -1.29442 -178 -4.82953,
+                          -2.49961 -178 -4.33023,
+                          -2.49961 -181 -4.33023,
+                          -2.49961 -178 -4.33023,
+                          -1.29442 -178 -4.82953,
+                          2.49961 -178 -4.33023,
+                          1.29442 -178 -4.82953,
+                          -2.49961 -178 -4.33023,
+                          -3.53583 -181 -3.53513,
+                          -2.49961 -178 -4.33023,
+                          -2.49961 -181 -4.33023,
+                          1.29442 -178 -4.82953,
+                          -3.05305e-16 -178 -4.99986,
+                          -1.29442 -178 -4.82953,
+                          -1.29442 -181 -4.82953,
+                          -1.29442 -178 -4.82953,
+                          -3.05305e-16 -178 -4.99986,
+                          -2.49961 -181 -4.33023,
+                          -1.29442 -178 -4.82953,
+                          -1.29442 -181 -4.82953,
+                          -3.05305e-16 -181 -4.99986,
+                          -3.05305e-16 -178 -4.99986,
+                          1.29442 -178 -4.82953,
+                          -1.29442 -181 -4.82953,
+                          -3.05305e-16 -178 -4.99986,
+                          -3.05305e-16 -181 -4.99986,
+                          1.29442 -181 -4.82953,
+                          1.29442 -178 -4.82953,
+                          2.49961 -178 -4.33023,
+                          -3.05305e-16 -181 -4.99986,
+                          1.29442 -178 -4.82953,
+                          1.29442 -181 -4.82953,
+                          2.49961 -181 -4.33023,
+                          2.49961 -178 -4.33023,
+                          3.53583 -178 -3.53513,
+                          1.29442 -181 -4.82953,
+                          2.49961 -178 -4.33023,
+                          2.49961 -181 -4.33023,
+                          3.53583 -181 -3.53513,
+                          3.53583 -178 -3.53513,
+                          4.32985 -178 -2.5004,
+                          2.49961 -181 -4.33023,
+                          3.53583 -178 -3.53513,
+                          3.53583 -181 -3.53513,
+                          4.32985 -181 -2.5004,
+                          4.32985 -178 -2.5004,
+                          4.82956 -178 -1.29386,
+                          3.53583 -181 -3.53513,
+                          4.32985 -178 -2.5004,
+                          4.32985 -181 -2.5004,
+                          4.82956 -181 -1.29386,
+                          4.82956 -178 -1.29386,
+                          5 -178 0,
+                          4.32985 -181 -2.5004,
+                          4.82956 -178 -1.29386,
+                          4.82956 -181 -1.29386,
+                          -4.82956 -178 1.29386,
+                          4.82956 -178 1.29386,
+                          5 -178 0,
+                          5 -181 0,
+                          5 -178 0,
+                          4.82956 -178 1.29386,
+                          4.82956 -181 -1.29386,
+                          5 -178 0,
+                          5 -181 0,
+                          -4.32985 -178 2.5004,
+                          4.32985 -178 2.5004,
+                          4.82956 -178 1.29386,
+                          4.82956 -181 1.29386,
+                          4.82956 -178 1.29386,
+                          4.32985 -178 2.5004,
+                          -4.82956 -178 1.29386,
+                          -4.32985 -178 2.5004,
+                          4.82956 -178 1.29386,
+                          4.82956 -181 1.29386,
+                          5 -181 0,
+                          4.82956 -178 1.29386,
+                          -3.53583 -178 3.53513,
+                          3.53583 -178 3.53513,
+                          4.32985 -178 2.5004,
+                          4.32985 -181 2.5004,
+                          4.32985 -178 2.5004,
+                          3.53583 -178 3.53513,
+                          -4.32985 -178 2.5004,
+                          -3.53583 -178 3.53513,
+                          4.32985 -178 2.5004,
+                          4.32985 -181 2.5004,
+                          4.82956 -181 1.29386,
+                          4.32985 -178 2.5004,
+                          -2.49961 -178 4.33023,
+                          2.49961 -178 4.33023,
+                          3.53583 -178 3.53513,
+                          3.53583 -181 3.53513,
+                          3.53583 -178 3.53513,
+                          2.49961 -178 4.33023,
+                          -3.53583 -178 3.53513,
+                          -2.49961 -178 4.33023,
+                          3.53583 -178 3.53513,
+                          3.53583 -181 3.53513,
+                          4.32985 -181 2.5004,
+                          3.53583 -178 3.53513,
+                          -1.29442 -178 4.82953,
+                          1.29442 -178 4.82953,
+                          2.49961 -178 4.33023,
+                          2.49961 -181 4.33023,
+                          2.49961 -178 4.33023,
+                          1.29442 -178 4.82953,
+                          -2.49961 -178 4.33023,
+                          -1.29442 -178 4.82953,
+                          2.49961 -178 4.33023,
+                          2.49961 -181 4.33023,
+                          3.53583 -181 3.53513,
+                          2.49961 -178 4.33023,
+                          -1.29442 -178 4.82953,
+                          -3.05305e-16 -178 4.99986,
+                          1.29442 -178 4.82953,
+                          1.29442 -181 4.82953,
+                          1.29442 -178 4.82953,
+                          -3.05305e-16 -178 4.99986,
+                          1.29442 -181 4.82953,
+                          2.49961 -181 4.33023,
+                          1.29442 -178 4.82953,
+                          -3.05305e-16 -181 4.99986,
+                          -3.05305e-16 -178 4.99986,
+                          -1.29442 -178 4.82953,
+                          -3.05305e-16 -181 4.99986,
+                          1.29442 -181 4.82953,
+                          -3.05305e-16 -178 4.99986,
+                          -1.29442 -181 4.82953,
+                          -1.29442 -178 4.82953,
+                          -2.49961 -178 4.33023,
+                          -1.29442 -181 4.82953,
+                          -3.05305e-16 -181 4.99986,
+                          -1.29442 -178 4.82953,
+                          -2.49961 -181 4.33023,
+                          -2.49961 -178 4.33023,
+                          -3.53583 -178 3.53513,
+                          -2.49961 -181 4.33023,
+                          -1.29442 -181 4.82953,
+                          -2.49961 -178 4.33023,
+                          -3.53583 -181 3.53513,
+                          -3.53583 -178 3.53513,
+                          -4.32985 -178 2.5004,
+                          -3.53583 -181 3.53513,
+                          -2.49961 -181 4.33023,
+                          -3.53583 -178 3.53513,
+                          -4.32985 -181 2.5004,
+                          -4.32985 -178 2.5004,
+                          -4.82956 -178 1.29386,
+                          -4.32985 -181 2.5004,
+                          -3.53583 -181 3.53513,
+                          -4.32985 -178 2.5004,
+                          -4.82956 -181 1.29386,
+                          -4.32985 -181 2.5004,
+                          -4.82956 -178 1.29386,
+                          43 -181 0,
+                          5 -181 0,
+                          4.82956 -181 1.29386,
+                          41.9218 -181 -9.56839,
+                          4.82956 -181 -1.29386,
+                          5 -181 0,
+                          43 -181 0,
+                          41.9218 -181 -9.56839,
+                          5 -181 0,
+                          43 -181 0,
+                          4.82956 -181 1.29386,
+                          4.32985 -181 2.5004,
+                          43 -181 0,
+                          4.32985 -181 2.5004,
+                          3.53583 -181 3.53513,
+                          43 -181 0,
+                          3.53583 -181 3.53513,
+                          2.49961 -181 4.33023,
+                          43 -181 0,
+                          2.49961 -181 4.33023,
+                          1.29442 -181 4.82953,
+                          43 -181 0,
+                          1.29442 -181 4.82953,
+                          -3.05305e-16 -181 4.99986,
+                          -41.9218 -181 9.56839,
+                          -3.05305e-16 -181 4.99986,
+                          -1.29442 -181 4.82953,
+                          41.9218 -181 9.56839,
+                          43 -181 0,
+                          -3.05305e-16 -181 4.99986,
+                          -41.9218 -181 9.56839,
+                          41.9218 -181 9.56839,
+                          -3.05305e-16 -181 4.99986,
+                          -41.9218 -181 9.56839,
+                          -1.29442 -181 4.82953,
+                          -2.49961 -181 4.33023,
+                          -41.9218 -181 9.56839,
+                          -2.49961 -181 4.33023,
+                          -3.53583 -181 3.53513,
+                          -41.9218 -181 9.56839,
+                          -3.53583 -181 3.53513,
+                          -4.32985 -181 2.5004,
+                          -41.9218 -181 9.56839,
+                          -4.32985 -181 2.5004,
+                          -4.82956 -181 1.29386,
+                          -41.9218 -181 9.56839,
+                          -4.82956 -181 1.29386,
+                          -5 -181 0,
+                          -43 -181 0,
+                          -5 -181 0,
+                          -4.82956 -181 -1.29386,
+                          -41.9218 -181 9.56839,
+                          -5 -181 0,
+                          -43 -181 0,
+                          41.9218 -181 -9.56839,
+                          4.32985 -181 -2.5004,
+                          4.82956 -181 -1.29386,
+                          41.9218 -181 -9.56839,
+                          3.53583 -181 -3.53513,
+                          4.32985 -181 -2.5004,
+                          41.9218 -181 -9.56839,
+                          2.49961 -181 -4.33023,
+                          3.53583 -181 -3.53513,
+                          41.9218 -181 -9.56839,
+                          1.29442 -181 -4.82953,
+                          2.49961 -181 -4.33023,
+                          41.9218 -181 -9.56839,
+                          -3.05305e-16 -181 -4.99986,
+                          1.29442 -181 -4.82953,
+                          -43 -181 0,
+                          -1.29442 -181 -4.82953,
+                          -3.05305e-16 -181 -4.99986,
+                          -41.9218 -181 -9.56839,
+                          -43 -181 0,
+                          -3.05305e-16 -181 -4.99986,
+                          41.9218 -181 -9.56839,
+                          -41.9218 -181 -9.56839,
+                          -3.05305e-16 -181 -4.99986,
+                          -43 -181 0,
+                          -2.49961 -181 -4.33023,
+                          -1.29442 -181 -4.82953,
+                          -43 -181 0,
+                          -3.53583 -181 -3.53513,
+                          -2.49961 -181 -4.33023,
+                          -43 -181 0,
+                          -4.32985 -181 -2.5004,
+                          -3.53583 -181 -3.53513,
+                          -43 -181 0,
+                          -4.82956 -181 -1.29386,
+                          -4.32985 -181 -2.5004,
+                          -43 -187 0,
+                          -43 -181 0,
+                          -41.9218 -181 -9.56839,
+                          -41.9218 -187 9.56839,
+                          -41.9218 -181 9.56839,
+                          -43 -181 0,
+                          -43 -187 0,
+                          -41.9218 -187 9.56839,
+                          -43 -181 0,
+                          38.7417 -181 -18.657,
+                          -38.7417 -181 -18.657,
+                          -41.9218 -181 -9.56839,
+                          -41.9218 -187 -9.56839,
+                          -41.9218 -181 -9.56839,
+                          -38.7417 -181 -18.657,
+                          41.9218 -181 -9.56839,
+                          38.7417 -181 -18.657,
+                          -41.9218 -181 -9.56839,
+                          -41.9218 -187 -9.56839,
+                          -43 -187 0,
+                          -41.9218 -181 -9.56839,
+                          33.6187 -181 -26.81,
+                          -33.6187 -181 -26.81,
+                          -38.7417 -181 -18.657,
+                          -38.7417 -187 -18.657,
+                          -38.7417 -181 -18.657,
+                          -33.6187 -181 -26.81,
+                          38.7417 -181 -18.657,
+                          33.6187 -181 -26.81,
+                          -38.7417 -181 -18.657,
+                          -41.9218 -187 -9.56839,
+                          -38.7417 -181 -18.657,
+                          -38.7417 -187 -18.657,
+                          26.8101 -181 -33.6188,
+                          -26.8101 -181 -33.6188,
+                          -33.6187 -181 -26.81,
+                          -33.6187 -187 -26.81,
+                          -33.6187 -181 -26.81,
+                          -26.8101 -181 -33.6188,
+                          33.6187 -181 -26.81,
+                          26.8101 -181 -33.6188,
+                          -33.6187 -181 -26.81,
+                          -38.7417 -187 -18.657,
+                          -33.6187 -181 -26.81,
+                          -33.6187 -187 -26.81,
+                          18.657 -181 -38.7416,
+                          -18.657 -181 -38.7416,
+                          -26.8101 -181 -33.6188,
+                          -26.8101 -187 -33.6188,
+                          -26.8101 -181 -33.6188,
+                          -18.657 -181 -38.7416,
+                          26.8101 -181 -33.6188,
+                          18.657 -181 -38.7416,
+                          -26.8101 -181 -33.6188,
+                          -33.6187 -187 -26.81,
+                          -26.8101 -181 -33.6188,
+                          -26.8101 -187 -33.6188,
+                          9.5684 -181 -41.9219,
+                          -9.5684 -181 -41.9219,
+                          -18.657 -181 -38.7416,
+                          -18.657 -187 -38.7416,
+                          -18.657 -181 -38.7416,
+                          -9.5684 -181 -41.9219,
+                          18.657 -181 -38.7416,
+                          9.5684 -181 -41.9219,
+                          -18.657 -181 -38.7416,
+                          -26.8101 -187 -33.6188,
+                          -18.657 -181 -38.7416,
+                          -18.657 -187 -38.7416,
+                          9.5684 -181 -41.9219,
+                          -7.43849e-15 -181 -42.9999,
+                          -9.5684 -181 -41.9219,
+                          -9.5684 -187 -41.9219,
+                          -9.5684 -181 -41.9219,
+                          -7.43849e-15 -181 -42.9999,
+                          -18.657 -187 -38.7416,
+                          -9.5684 -181 -41.9219,
+                          -9.5684 -187 -41.9219,
+                          -7.43849e-15 -187 -42.9999,
+                          -7.43849e-15 -181 -42.9999,
+                          9.5684 -181 -41.9219,
+                          -9.5684 -187 -41.9219,
+                          -7.43849e-15 -181 -42.9999,
+                          -7.43849e-15 -187 -42.9999,
+                          9.5684 -187 -41.9219,
+                          9.5684 -181 -41.9219,
+                          18.657 -181 -38.7416,
+                          -7.43849e-15 -187 -42.9999,
+                          9.5684 -181 -41.9219,
+                          9.5684 -187 -41.9219,
+                          18.657 -187 -38.7416,
+                          18.657 -181 -38.7416,
+                          26.8101 -181 -33.6188,
+                          9.5684 -187 -41.9219,
+                          18.657 -181 -38.7416,
+                          18.657 -187 -38.7416,
+                          26.8101 -187 -33.6188,
+                          26.8101 -181 -33.6188,
+                          33.6187 -181 -26.81,
+                          18.657 -187 -38.7416,
+                          26.8101 -181 -33.6188,
+                          26.8101 -187 -33.6188,
+                          33.6187 -187 -26.81,
+                          33.6187 -181 -26.81,
+                          38.7417 -181 -18.657,
+                          26.8101 -187 -33.6188,
+                          33.6187 -181 -26.81,
+                          33.6187 -187 -26.81,
+                          38.7417 -187 -18.657,
+                          38.7417 -181 -18.657,
+                          41.9218 -181 -9.56839,
+                          33.6187 -187 -26.81,
+                          38.7417 -181 -18.657,
+                          38.7417 -187 -18.657,
+                          41.9218 -187 -9.56839,
+                          41.9218 -181 -9.56839,
+                          43 -181 0,
+                          38.7417 -187 -18.657,
+                          41.9218 -181 -9.56839,
+                          41.9218 -187 -9.56839,
+                          43 -187 0,
+                          43 -181 0,
+                          41.9218 -181 9.56839,
+                          41.9218 -187 -9.56839,
+                          43 -181 0,
+                          43 -187 0,
+                          -38.7417 -181 18.657,
+                          38.7417 -181 18.657,
+                          41.9218 -181 9.56839,
+                          41.9218 -187 9.56839,
+                          41.9218 -181 9.56839,
+                          38.7417 -181 18.657,
+                          -41.9218 -181 9.56839,
+                          -38.7417 -181 18.657,
+                          41.9218 -181 9.56839,
+                          41.9218 -187 9.56839,
+                          43 -187 0,
+                          41.9218 -181 9.56839,
+                          -33.6187 -181 26.81,
+                          33.6187 -181 26.81,
+                          38.7417 -181 18.657,
+                          38.7417 -187 18.657,
+                          38.7417 -181 18.657,
+                          33.6187 -181 26.81,
+                          -38.7417 -181 18.657,
+                          -33.6187 -181 26.81,
+                          38.7417 -181 18.657,
+                          38.7417 -187 18.657,
+                          41.9218 -187 9.56839,
+                          38.7417 -181 18.657,
+                          -26.8101 -181 33.6188,
+                          26.8101 -181 33.6188,
+                          33.6187 -181 26.81,
+                          33.6187 -187 26.81,
+                          33.6187 -181 26.81,
+                          26.8101 -181 33.6188,
+                          -33.6187 -181 26.81,
+                          -26.8101 -181 33.6188,
+                          33.6187 -181 26.81,
+                          33.6187 -187 26.81,
+                          38.7417 -187 18.657,
+                          33.6187 -181 26.81,
+                          -18.657 -181 38.7416,
+                          18.657 -181 38.7416,
+                          26.8101 -181 33.6188,
+                          26.8101 -187 33.6188,
+                          26.8101 -181 33.6188,
+                          18.657 -181 38.7416,
+                          -26.8101 -181 33.6188,
+                          -18.657 -181 38.7416,
+                          26.8101 -181 33.6188,
+                          26.8101 -187 33.6188,
+                          33.6187 -187 26.81,
+                          26.8101 -181 33.6188,
+                          -9.5684 -181 41.9219,
+                          9.5684 -181 41.9219,
+                          18.657 -181 38.7416,
+                          18.657 -187 38.7416,
+                          18.657 -181 38.7416,
+                          9.5684 -181 41.9219,
+                          -18.657 -181 38.7416,
+                          -9.5684 -181 41.9219,
+                          18.657 -181 38.7416,
+                          18.657 -187 38.7416,
+                          26.8101 -187 33.6188,
+                          18.657 -181 38.7416,
+                          -9.5684 -181 41.9219,
+                          -7.43849e-15 -181 42.9999,
+                          9.5684 -181 41.9219,
+                          9.5684 -187 41.9219,
+                          9.5684 -181 41.9219,
+                          -7.43849e-15 -181 42.9999,
+                          9.5684 -187 41.9219,
+                          18.657 -187 38.7416,
+                          9.5684 -181 41.9219,
+                          -7.43849e-15 -187 42.9999,
+                          -7.43849e-15 -181 42.9999,
+                          -9.5684 -181 41.9219,
+                          -7.43849e-15 -187 42.9999,
+                          9.5684 -187 41.9219,
+                          -7.43849e-15 -181 42.9999,
+                          -9.5684 -187 41.9219,
+                          -9.5684 -181 41.9219,
+                          -18.657 -181 38.7416,
+                          -9.5684 -187 41.9219,
+                          -7.43849e-15 -187 42.9999,
+                          -9.5684 -181 41.9219,
+                          -18.657 -187 38.7416,
+                          -18.657 -181 38.7416,
+                          -26.8101 -181 33.6188,
+                          -18.657 -187 38.7416,
+                          -9.5684 -187 41.9219,
+                          -18.657 -181 38.7416,
+                          -26.8101 -187 33.6188,
+                          -26.8101 -181 33.6188,
+                          -33.6187 -181 26.81,
+                          -26.8101 -187 33.6188,
+                          -18.657 -187 38.7416,
+                          -26.8101 -181 33.6188,
+                          -33.6187 -187 26.81,
+                          -33.6187 -181 26.81,
+                          -38.7417 -181 18.657,
+                          -33.6187 -187 26.81,
+                          -26.8101 -187 33.6188,
+                          -33.6187 -181 26.81,
+                          -38.7417 -187 18.657,
+                          -38.7417 -181 18.657,
+                          -41.9218 -181 9.56839,
+                          -38.7417 -187 18.657,
+                          -33.6187 -187 26.81,
+                          -38.7417 -181 18.657,
+                          -41.9218 -187 9.56839,
+                          -38.7417 -187 18.657,
+                          -41.9218 -181 9.56839,
+                          -43 -187 0,
+                          43 -187 0,
+                          41.9218 -187 9.56839,
+                          -41.9218 -187 -9.56839,
+                          43 -187 0,
+                          -43 -187 0,
+                          -41.9218 -187 -9.56839,
+                          41.9218 -187 -9.56839,
+                          43 -187 0,
+                          -41.9218 -187 9.56839,
+                          41.9218 -187 9.56839,
+                          38.7417 -187 18.657,
+                          -43 -187 0,
+                          41.9218 -187 9.56839,
+                          -41.9218 -187 9.56839,
+                          -38.7417 -187 18.657,
+                          38.7417 -187 18.657,
+                          33.6187 -187 26.81,
+                          -41.9218 -187 9.56839,
+                          38.7417 -187 18.657,
+                          -38.7417 -187 18.657,
+                          -33.6187 -187 26.81,
+                          33.6187 -187 26.81,
+                          26.8101 -187 33.6188,
+                          -38.7417 -187 18.657,
+                          33.6187 -187 26.81,
+                          -33.6187 -187 26.81,
+                          -26.8101 -187 33.6188,
+                          26.8101 -187 33.6188,
+                          18.657 -187 38.7416,
+                          -33.6187 -187 26.81,
+                          26.8101 -187 33.6188,
+                          -26.8101 -187 33.6188,
+                          -18.657 -187 38.7416,
+                          18.657 -187 38.7416,
+                          9.5684 -187 41.9219,
+                          -26.8101 -187 33.6188,
+                          18.657 -187 38.7416,
+                          -18.657 -187 38.7416,
+                          -9.5684 -187 41.9219,
+                          9.5684 -187 41.9219,
+                          -7.43849e-15 -187 42.9999,
+                          -18.657 -187 38.7416,
+                          9.5684 -187 41.9219,
+                          -9.5684 -187 41.9219,
+                          -38.7417 -187 -18.657,
+                          38.7417 -187 -18.657,
+                          41.9218 -187 -9.56839,
+                          -41.9218 -187 -9.56839,
+                          -38.7417 -187 -18.657,
+                          41.9218 -187 -9.56839,
+                          -33.6187 -187 -26.81,
+                          33.6187 -187 -26.81,
+                          38.7417 -187 -18.657,
+                          -38.7417 -187 -18.657,
+                          -33.6187 -187 -26.81,
+                          38.7417 -187 -18.657,
+                          -26.8101 -187 -33.6188,
+                          26.8101 -187 -33.6188,
+                          33.6187 -187 -26.81,
+                          -33.6187 -187 -26.81,
+                          -26.8101 -187 -33.6188,
+                          33.6187 -187 -26.81,
+                          -18.657 -187 -38.7416,
+                          18.657 -187 -38.7416,
+                          26.8101 -187 -33.6188,
+                          -26.8101 -187 -33.6188,
+                          -18.657 -187 -38.7416,
+                          26.8101 -187 -33.6188,
+                          -9.5684 -187 -41.9219,
+                          9.5684 -187 -41.9219,
+                          18.657 -187 -38.7416,
+                          -18.657 -187 -38.7416,
+                          -9.5684 -187 -41.9219,
+                          18.657 -187 -38.7416,
+                          -9.5684 -187 -41.9219,
+                          -7.43849e-15 -187 -42.9999,
+                          9.5684 -187 -41.9219 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.65 0.65 0.65
+    }
+    Separator {
+        Normal {
+            vector      [ 0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          -1.22461e-16 1.22461e-16 -1,
+                          -1.22461e-16 1.22461e-16 -1,
+                          0.5 1.06054e-16 -0.866025,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          -0.5 1.06054e-16 -0.866025,
+                          -0.5 1.06054e-16 -0.866025,
+                          -1.22461e-16 1.22461e-16 -1,
+                          -1.22461e-16 1.22461e-16 -1,
+                          -0.5 1.06054e-16 -0.866025,
+                          -1.22461e-16 1.22461e-16 -1,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0.5 1.06054e-16 -0.866025,
+                          0.5 1.06054e-16 -0.866025,
+                          0.866025 6.12303e-17 -0.5,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0.5 1.06054e-16 -0.866025,
+                          -1.22461e-16 1.22461e-16 -1,
+                          0.5 1.06054e-16 -0.866025,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0.866025 6.12303e-17 -0.5,
+                          0.866025 6.12303e-17 -0.5,
+                          1 0 -1.83691e-16,
+                          0.866025 6.12303e-17 -0.5,
+                          0.5 1.06054e-16 -0.866025,
+                          0.866025 6.12303e-17 -0.5,
+                          1 0 -1.83691e-16,
+                          1 0 -1.83691e-16,
+                          0.866025 -6.12303e-17 0.5,
+                          1 0 -1.83691e-16,
+                          0.866025 6.12303e-17 -0.5,
+                          1 0 -1.83691e-16,
+                          0.866025 -6.12303e-17 0.5,
+                          0.866025 -6.12303e-17 0.5,
+                          0.5 -1.06054e-16 0.866025,
+                          0.866025 -6.12303e-17 0.5,
+                          1 0 -1.83691e-16,
+                          0.866025 -6.12303e-17 0.5,
+                          0.5 -1.06054e-16 0.866025,
+                          0.5 -1.06054e-16 0.866025,
+                          2.44921e-16 -1.22461e-16 1,
+                          0.5 -1.06054e-16 0.866025,
+                          0.866025 -6.12303e-17 0.5,
+                          0.5 -1.06054e-16 0.866025,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 -1.22461e-16 1,
+                          0 -1.22461e-16 1,
+                          -0.5 -1.06054e-16 0.866025,
+                          0.5 -1.06054e-16 0.866025,
+                          2.44921e-16 -1.22461e-16 1,
+                          2.44921e-16 -1.22461e-16 1,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          -0.5 -1.06054e-16 0.866025,
+                          -0.5 -1.06054e-16 0.866025,
+                          -0.866025 -6.12303e-17 0.5,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          -0.5 -1.06054e-16 0.866025,
+                          0 -1.22461e-16 1,
+                          -0.5 -1.06054e-16 0.866025,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          -0.866025 -6.12303e-17 0.5,
+                          -0.866025 -6.12303e-17 0.5,
+                          -1 0 6.12303e-17,
+                          -0.866025 -6.12303e-17 0.5,
+                          -0.5 -1.06054e-16 0.866025,
+                          -0.866025 -6.12303e-17 0.5,
+                          -1 0 6.12303e-17,
+                          -1 0 6.12303e-17,
+                          -0.866025 6.12303e-17 -0.5,
+                          -1 0 6.12303e-17,
+                          -0.866025 -6.12303e-17 0.5,
+                          -1 0 6.12303e-17,
+                          -0.866025 6.12303e-17 -0.5,
+                          -0.866025 6.12303e-17 -0.5,
+                          -0.5 1.06054e-16 -0.866025,
+                          -0.866025 6.12303e-17 -0.5,
+                          -1 0 6.12303e-17,
+                          -0.866025 6.12303e-17 -0.5,
+                          -0.5 1.06054e-16 -0.866025,
+                          -0.866025 6.12303e-17 -0.5,
+                          -0.5 1.06054e-16 -0.866025 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 1.50086 124.3 2.59741,
+                          1.50086 124.3 -2.59741,
+                          0 124.3 -3,
+                          -3.67382e-16 107.55 -3,
+                          0 124.3 -3,
+                          1.50086 124.3 -2.59741,
+                          0 124.3 3,
+                          1.50086 124.3 2.59741,
+                          0 124.3 -3,
+                          -1.50086 124.3 -2.59741,
+                          0 124.3 3,
+                          0 124.3 -3,
+                          -1.5 107.55 -2.59808,
+                          -1.50086 124.3 -2.59741,
+                          0 124.3 -3,
+                          -3.67382e-16 107.55 -3,
+                          -1.5 107.55 -2.59808,
+                          0 124.3 -3,
+                          2.59819 124.3 1.49906,
+                          2.59819 124.3 -1.49906,
+                          1.50086 124.3 -2.59741,
+                          1.5 107.55 -2.59808,
+                          1.50086 124.3 -2.59741,
+                          2.59819 124.3 -1.49906,
+                          1.50086 124.3 2.59741,
+                          2.59819 124.3 1.49906,
+                          1.50086 124.3 -2.59741,
+                          1.5 107.55 -2.59808,
+                          -3.67382e-16 107.55 -3,
+                          1.50086 124.3 -2.59741,
+                          2.59819 124.3 1.49906,
+                          2.99954 124.3 -5.25281e-16,
+                          2.59819 124.3 -1.49906,
+                          2.59808 107.55 -1.5,
+                          2.59819 124.3 -1.49906,
+                          2.99954 124.3 -5.25281e-16,
+                          2.59808 107.55 -1.5,
+                          1.5 107.55 -2.59808,
+                          2.59819 124.3 -1.49906,
+                          3 107.55 -2.60021e-15,
+                          2.99954 124.3 -5.25281e-16,
+                          2.59819 124.3 1.49906,
+                          3 107.55 -2.60021e-15,
+                          2.59808 107.55 -1.5,
+                          2.99954 124.3 -5.25281e-16,
+                          2.59808 107.55 1.5,
+                          2.59819 124.3 1.49906,
+                          1.50086 124.3 2.59741,
+                          2.59808 107.55 1.5,
+                          3 107.55 -2.60021e-15,
+                          2.59819 124.3 1.49906,
+                          1.5 107.55 2.59808,
+                          1.50086 124.3 2.59741,
+                          0 124.3 3,
+                          1.5 107.55 2.59808,
+                          2.59808 107.55 1.5,
+                          1.50086 124.3 2.59741,
+                          -1.50086 124.3 -2.59741,
+                          -1.50086 124.3 2.59741,
+                          0 124.3 3,
+                          0 107.55 3,
+                          0 124.3 3,
+                          -1.50086 124.3 2.59741,
+                          1.5 107.55 2.59808,
+                          0 124.3 3,
+                          0 107.55 3,
+                          -2.59819 124.3 -1.49906,
+                          -2.59819 124.3 1.49906,
+                          -1.50086 124.3 2.59741,
+                          -1.5 107.55 2.59808,
+                          -1.50086 124.3 2.59741,
+                          -2.59819 124.3 1.49906,
+                          -1.50086 124.3 -2.59741,
+                          -2.59819 124.3 -1.49906,
+                          -1.50086 124.3 2.59741,
+                          -1.5 107.55 2.59808,
+                          0 107.55 3,
+                          -1.50086 124.3 2.59741,
+                          -2.59819 124.3 -1.49906,
+                          -2.99954 124.3 -5.25281e-16,
+                          -2.59819 124.3 1.49906,
+                          -2.59808 107.55 1.5,
+                          -2.59819 124.3 1.49906,
+                          -2.99954 124.3 -5.25281e-16,
+                          -2.59808 107.55 1.5,
+                          -1.5 107.55 2.59808,
+                          -2.59819 124.3 1.49906,
+                          -3 107.55 -1.86545e-15,
+                          -2.99954 124.3 -5.25281e-16,
+                          -2.59819 124.3 -1.49906,
+                          -3 107.55 -1.86545e-15,
+                          -2.59808 107.55 1.5,
+                          -2.99954 124.3 -5.25281e-16,
+                          -2.59808 107.55 -1.5,
+                          -2.59819 124.3 -1.49906,
+                          -1.50086 124.3 -2.59741,
+                          -2.59808 107.55 -1.5,
+                          -3 107.55 -1.86545e-15,
+                          -2.59819 124.3 -1.49906,
+                          -1.5 107.55 -2.59808,
+                          -2.59808 107.55 -1.5,
+                          -1.50086 124.3 -2.59741 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.83 0 0
+    }
+    Separator {
+        Normal {
+            vector      [ 0 -1.22461e-16 1,
+                          0 -1.22461e-16 1,
+                          -0.5 -1.06054e-16 0.866025,
+                          0.5 -1.06054e-16 0.866025,
+                          0.5 -1.06054e-16 0.866025,
+                          2.44921e-16 -1.22461e-16 1,
+                          0.5 -1.06054e-16 0.866025,
+                          2.44921e-16 -1.22461e-16 1,
+                          2.44921e-16 -1.22461e-16 1,
+                          -0.5 -1.06054e-16 0.866025,
+                          -0.5 -1.06054e-16 0.866025,
+                          -0.866025 -6.12303e-17 0.5,
+                          -0.5 -1.06054e-16 0.866025,
+                          0 -1.22461e-16 1,
+                          -0.5 -1.06054e-16 0.866025,
+                          -0.866025 -6.12303e-17 0.5,
+                          -0.866025 -6.12303e-17 0.5,
+                          -1 0 6.12303e-17,
+                          -0.866025 -6.12303e-17 0.5,
+                          -0.5 -1.06054e-16 0.866025,
+                          -0.866025 -6.12303e-17 0.5,
+                          -1 0 6.12303e-17,
+                          -1 0 6.12303e-17,
+                          -0.866025 6.12303e-17 -0.5,
+                          -1 0 6.12303e-17,
+                          -0.866025 -6.12303e-17 0.5,
+                          -1 0 6.12303e-17,
+                          -0.866025 6.12303e-17 -0.5,
+                          -0.866025 6.12303e-17 -0.5,
+                          -0.5 1.06054e-16 -0.866025,
+                          -0.866025 6.12303e-17 -0.5,
+                          -1 0 6.12303e-17,
+                          -0.866025 6.12303e-17 -0.5,
+                          -0.5 1.06054e-16 -0.866025,
+                          -0.5 1.06054e-16 -0.866025,
+                          -1.22461e-16 1.22461e-16 -1,
+                          -0.5 1.06054e-16 -0.866025,
+                          -0.866025 6.12303e-17 -0.5,
+                          -0.5 1.06054e-16 -0.866025,
+                          -1.22461e-16 1.22461e-16 -1,
+                          -1.22461e-16 1.22461e-16 -1,
+                          0.5 1.06054e-16 -0.866025,
+                          -1.22461e-16 1.22461e-16 -1,
+                          -0.5 1.06054e-16 -0.866025,
+                          -1.22461e-16 1.22461e-16 -1,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          -1.22461e-16 1.22461e-16 -1,
+                          -1.22461e-16 1.22461e-16 -1,
+                          0.309017 1.16467e-16 -0.951057,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          -0.309017 1.16467e-16 -0.951057,
+                          -0.309017 1.16467e-16 -0.951057,
+                          -1.22461e-16 1.22461e-16 -1,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          -1.22461e-16 1.22461e-16 -1,
+                          -0.309017 1.16467e-16 -0.951057,
+                          -1.22461e-16 1.22461e-16 -1,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0.309017 1.16467e-16 -0.951057,
+                          0.309017 1.16467e-16 -0.951057,
+                          0.587785 9.90727e-17 -0.809017,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0.309017 1.16467e-16 -0.951057,
+                          -1.22461e-16 1.22461e-16 -1,
+                          0.309017 1.16467e-16 -0.951057,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0.587785 9.90727e-17 -0.809017,
+                          0.587785 9.90727e-17 -0.809017,
+                          0.809017 7.19806e-17 -0.587785,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0.587785 9.90727e-17 -0.809017,
+                          0.309017 1.16467e-16 -0.951057,
+                          0.587785 9.90727e-17 -0.809017,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0.809017 7.19806e-17 -0.587785,
+                          0.809017 7.19806e-17 -0.587785,
+                          0.951057 3.78424e-17 -0.309017,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0.809017 7.19806e-17 -0.587785,
+                          0.587785 9.90727e-17 -0.809017,
+                          0.809017 7.19806e-17 -0.587785,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0.951057 3.78424e-17 -0.309017,
+                          0.951057 3.78424e-17 -0.309017,
+                          1 0 -1.83691e-16,
+                          0.951057 3.78424e-17 -0.309017,
+                          0.809017 7.19806e-17 -0.587785,
+                          0.951057 3.78424e-17 -0.309017,
+                          1 0 -1.83691e-16,
+                          1 0 -1.83691e-16,
+                          0.951057 -3.78424e-17 0.309017,
+                          1 0 -1.83691e-16,
+                          0.951057 3.78424e-17 -0.309017,
+                          1 0 -1.83691e-16,
+                          0.951057 -3.78424e-17 0.309017,
+                          0.951057 -3.78424e-17 0.309017,
+                          0.809017 -7.19806e-17 0.587785,
+                          0.951057 -3.78424e-17 0.309017,
+                          1 0 -1.83691e-16,
+                          0.951057 -3.78424e-17 0.309017,
+                          0.809017 -7.19806e-17 0.587785,
+                          0.809017 -7.19806e-17 0.587785,
+                          0.587785 -9.90727e-17 0.809017,
+                          0.809017 -7.19806e-17 0.587785,
+                          0.951057 -3.78424e-17 0.309017,
+                          0.809017 -7.19806e-17 0.587785,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0.587785 -9.90727e-17 0.809017,
+                          0.587785 -9.90727e-17 0.809017,
+                          0.309017 -1.16467e-16 0.951057,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0.587785 -9.90727e-17 0.809017,
+                          0.809017 -7.19806e-17 0.587785,
+                          0.587785 -9.90727e-17 0.809017,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0.309017 -1.16467e-16 0.951057,
+                          0.309017 -1.16467e-16 0.951057,
+                          2.44921e-16 -1.22461e-16 1,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0.309017 -1.16467e-16 0.951057,
+                          0.587785 -9.90727e-17 0.809017,
+                          0.309017 -1.16467e-16 0.951057,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 -1.22461e-16 1,
+                          0 -1.22461e-16 1,
+                          -0.309017 -1.16467e-16 0.951057,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0.309017 -1.16467e-16 0.951057,
+                          2.44921e-16 -1.22461e-16 1,
+                          2.44921e-16 -1.22461e-16 1,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          -0.309017 -1.16467e-16 0.951057,
+                          -0.309017 -1.16467e-16 0.951057,
+                          -0.587785 -9.90727e-17 0.809017,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          -0.309017 -1.16467e-16 0.951057,
+                          0 -1.22461e-16 1,
+                          -0.309017 -1.16467e-16 0.951057,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          -0.587785 -9.90727e-17 0.809017,
+                          -0.587785 -9.90727e-17 0.809017,
+                          -0.809017 -7.19806e-17 0.587785,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          -0.587785 -9.90727e-17 0.809017,
+                          -0.309017 -1.16467e-16 0.951057,
+                          -0.587785 -9.90727e-17 0.809017,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          -0.809017 -7.19806e-17 0.587785,
+                          -0.809017 -7.19806e-17 0.587785,
+                          -0.951057 -3.78424e-17 0.309017,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          -0.809017 -7.19806e-17 0.587785,
+                          -0.587785 -9.90727e-17 0.809017,
+                          -0.809017 -7.19806e-17 0.587785,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          -0.951057 -3.78424e-17 0.309017,
+                          -0.951057 -3.78424e-17 0.309017,
+                          -1 0 6.12303e-17,
+                          -0.951057 -3.78424e-17 0.309017,
+                          -0.809017 -7.19806e-17 0.587785,
+                          -0.951057 -3.78424e-17 0.309017,
+                          -1 0 6.12303e-17,
+                          -1 0 6.12303e-17,
+                          -0.951057 3.78424e-17 -0.309017,
+                          -1 0 6.12303e-17,
+                          -0.951057 -3.78424e-17 0.309017,
+                          -1 0 6.12303e-17,
+                          -0.951057 3.78424e-17 -0.309017,
+                          -0.951057 3.78424e-17 -0.309017,
+                          -0.809017 7.19806e-17 -0.587785,
+                          -0.951057 3.78424e-17 -0.309017,
+                          -1 0 6.12303e-17,
+                          -0.951057 3.78424e-17 -0.309017,
+                          -0.809017 7.19806e-17 -0.587785,
+                          -0.809017 7.19806e-17 -0.587785,
+                          -0.587785 9.90727e-17 -0.809017,
+                          -0.809017 7.19806e-17 -0.587785,
+                          -0.951057 3.78424e-17 -0.309017,
+                          -0.809017 7.19806e-17 -0.587785,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          -0.587785 9.90727e-17 -0.809017,
+                          -0.587785 9.90727e-17 -0.809017,
+                          -0.309017 1.16467e-16 -0.951057,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          -0.587785 9.90727e-17 -0.809017,
+                          -0.809017 7.19806e-17 -0.587785,
+                          -0.587785 9.90727e-17 -0.809017,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          -0.309017 1.16467e-16 -0.951057,
+                          -0.587785 9.90727e-17 -0.809017,
+                          -0.309017 1.16467e-16 -0.951057,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0.5 1.06054e-16 -0.866025,
+                          0.5 1.06054e-16 -0.866025,
+                          0.866025 6.12303e-17 -0.5,
+                          0.5 1.06054e-16 -0.866025,
+                          -1.22461e-16 1.22461e-16 -1,
+                          0.5 1.06054e-16 -0.866025,
+                          0.866025 6.12303e-17 -0.5,
+                          0.866025 6.12303e-17 -0.5,
+                          1 0 -1.83691e-16,
+                          0.5 1.06054e-16 -0.866025,
+                          0.866025 6.12303e-17 -0.5,
+                          0.866025 6.12303e-17 -0.5,
+                          1 0 -1.83691e-16,
+                          1 0 -1.83691e-16,
+                          0.866025 -6.12303e-17 0.5,
+                          0.866025 6.12303e-17 -0.5,
+                          1 0 -1.83691e-16,
+                          1 0 -1.83691e-16,
+                          0.866025 -6.12303e-17 0.5,
+                          0.866025 -6.12303e-17 0.5,
+                          0.5 -1.06054e-16 0.866025,
+                          1 0 -1.83691e-16,
+                          0.866025 -6.12303e-17 0.5,
+                          0.866025 -6.12303e-17 0.5,
+                          0.866025 -6.12303e-17 0.5,
+                          0.5 -1.06054e-16 0.866025,
+                          0.5 -1.06054e-16 0.866025,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 0 104 3,
+                          0 107.55 3,
+                          -1.5 107.55 2.59808,
+                          1.50086 104 2.59741,
+                          1.5 107.55 2.59808,
+                          0 107.55 3,
+                          1.50086 104 2.59741,
+                          0 107.55 3,
+                          0 104 3,
+                          -1.50086 104 2.59741,
+                          -1.5 107.55 2.59808,
+                          -2.59808 107.55 1.5,
+                          -1.50086 104 2.59741,
+                          0 104 3,
+                          -1.5 107.55 2.59808,
+                          -2.59819 104 1.49906,
+                          -2.59808 107.55 1.5,
+                          -3 107.55 -1.86545e-15,
+                          -2.59819 104 1.49906,
+                          -1.50086 104 2.59741,
+                          -2.59808 107.55 1.5,
+                          -2.99954 104 -3.01123e-15,
+                          -3 107.55 -1.86545e-15,
+                          -2.59808 107.55 -1.5,
+                          -2.99954 104 -3.01123e-15,
+                          -2.59819 104 1.49906,
+                          -3 107.55 -1.86545e-15,
+                          -2.59819 104 -1.49906,
+                          -2.59808 107.55 -1.5,
+                          -1.5 107.55 -2.59808,
+                          -2.59819 104 -1.49906,
+                          -2.99954 104 -3.01123e-15,
+                          -2.59808 107.55 -1.5,
+                          -1.50086 104 -2.59741,
+                          -1.5 107.55 -2.59808,
+                          -3.67382e-16 107.55 -3,
+                          -1.50086 104 -2.59741,
+                          -2.59819 104 -1.49906,
+                          -1.5 107.55 -2.59808,
+                          0 104 -3,
+                          -3.67382e-16 107.55 -3,
+                          1.5 107.55 -2.59808,
+                          0 104 -3,
+                          -1.50086 104 -2.59741,
+                          -3.67382e-16 107.55 -3,
+                          3.47007 104 -7.20814,
+                          6.18191 104 -19.0204,
+                          0 104 -20,
+                          0 35.03 -20,
+                          0 104 -20,
+                          6.18191 104 -19.0204,
+                          0 104 -8,
+                          0 104 -20,
+                          -6.18191 104 -19.0204,
+                          -6.18191 35.03 -19.0204,
+                          -6.18191 104 -19.0204,
+                          0 104 -20,
+                          3.47007 104 -7.20814,
+                          0 104 -20,
+                          0 104 -8,
+                          0 35.03 -20,
+                          -6.18191 35.03 -19.0204,
+                          0 104 -20,
+                          11.7562 104 16.1795,
+                          11.7562 104 -16.1795,
+                          6.18191 104 -19.0204,
+                          6.18191 35.03 -19.0204,
+                          6.18191 104 -19.0204,
+                          11.7562 104 -16.1795,
+                          7.79899 104 -1.78051,
+                          11.7562 104 16.1795,
+                          6.18191 104 -19.0204,
+                          6.25379 104 -4.98861,
+                          7.79899 104 -1.78051,
+                          6.18191 104 -19.0204,
+                          3.47007 104 -7.20814,
+                          6.25379 104 -4.98861,
+                          6.18191 104 -19.0204,
+                          6.18191 35.03 -19.0204,
+                          0 35.03 -20,
+                          6.18191 104 -19.0204,
+                          16.1795 104 11.7562,
+                          16.1795 104 -11.7562,
+                          11.7562 104 -16.1795,
+                          11.7562 35.03 -16.1795,
+                          11.7562 104 -16.1795,
+                          16.1795 104 -11.7562,
+                          11.7562 104 16.1795,
+                          16.1795 104 11.7562,
+                          11.7562 104 -16.1795,
+                          11.7562 35.03 -16.1795,
+                          6.18191 35.03 -19.0204,
+                          11.7562 104 -16.1795,
+                          19.0204 104 6.18191,
+                          19.0204 104 -6.18191,
+                          16.1795 104 -11.7562,
+                          16.1795 35.03 -11.7562,
+                          16.1795 104 -11.7562,
+                          19.0204 104 -6.18191,
+                          16.1795 104 11.7562,
+                          19.0204 104 6.18191,
+                          16.1795 104 -11.7562,
+                          16.1795 35.03 -11.7562,
+                          11.7562 35.03 -16.1795,
+                          16.1795 104 -11.7562,
+                          19.0204 104 6.18191,
+                          20 104 -3.70848e-15,
+                          19.0204 104 -6.18191,
+                          19.0204 35.03 -6.18191,
+                          19.0204 104 -6.18191,
+                          20 104 -3.70848e-15,
+                          19.0204 35.03 -6.18191,
+                          16.1795 35.03 -11.7562,
+                          19.0204 104 -6.18191,
+                          20 35.03 -1.21546e-14,
+                          20 104 -3.70848e-15,
+                          19.0204 104 6.18191,
+                          20 35.03 -1.21546e-14,
+                          19.0204 35.03 -6.18191,
+                          20 104 -3.70848e-15,
+                          19.0204 35.03 6.18191,
+                          19.0204 104 6.18191,
+                          16.1795 104 11.7562,
+                          19.0204 35.03 6.18191,
+                          20 35.03 -1.21546e-14,
+                          19.0204 104 6.18191,
+                          16.1795 35.03 11.7562,
+                          16.1795 104 11.7562,
+                          11.7562 104 16.1795,
+                          16.1795 35.03 11.7562,
+                          19.0204 35.03 6.18191,
+                          16.1795 104 11.7562,
+                          6.25379 104 4.98861,
+                          6.18191 104 19.0204,
+                          11.7562 104 16.1795,
+                          11.7562 35.03 16.1795,
+                          11.7562 104 16.1795,
+                          6.18191 104 19.0204,
+                          7.79899 104 1.78051,
+                          6.25379 104 4.98861,
+                          11.7562 104 16.1795,
+                          7.79899 104 -1.78051,
+                          7.79899 104 1.78051,
+                          11.7562 104 16.1795,
+                          11.7562 35.03 16.1795,
+                          16.1795 35.03 11.7562,
+                          11.7562 104 16.1795,
+                          0 104 8,
+                          0 104 20,
+                          6.18191 104 19.0204,
+                          6.18191 35.03 19.0204,
+                          6.18191 104 19.0204,
+                          0 104 20,
+                          3.47007 104 7.20814,
+                          0 104 8,
+                          6.18191 104 19.0204,
+                          6.25379 104 4.98861,
+                          3.47007 104 7.20814,
+                          6.18191 104 19.0204,
+                          6.18191 35.03 19.0204,
+                          11.7562 35.03 16.1795,
+                          6.18191 104 19.0204,
+                          -3.47007 104 7.20814,
+                          -6.18191 104 19.0204,
+                          0 104 20,
+                          0 35.03 20,
+                          0 104 20,
+                          -6.18191 104 19.0204,
+                          0 104 8,
+                          -3.47007 104 7.20814,
+                          0 104 20,
+                          6.18191 35.03 19.0204,
+                          0 104 20,
+                          0 35.03 20,
+                          -11.7562 104 -16.1795,
+                          -11.7562 104 16.1795,
+                          -6.18191 104 19.0204,
+                          -6.18191 35.03 19.0204,
+                          -6.18191 104 19.0204,
+                          -11.7562 104 16.1795,
+                          -7.79899 104 1.78051,
+                          -11.7562 104 -16.1795,
+                          -6.18191 104 19.0204,
+                          -6.25379 104 4.98861,
+                          -7.79899 104 1.78051,
+                          -6.18191 104 19.0204,
+                          -3.47007 104 7.20814,
+                          -6.25379 104 4.98861,
+                          -6.18191 104 19.0204,
+                          -6.18191 35.03 19.0204,
+                          0 35.03 20,
+                          -6.18191 104 19.0204,
+                          -16.1795 104 -11.7562,
+                          -16.1795 104 11.7562,
+                          -11.7562 104 16.1795,
+                          -11.7562 35.03 16.1795,
+                          -11.7562 104 16.1795,
+                          -16.1795 104 11.7562,
+                          -11.7562 104 -16.1795,
+                          -16.1795 104 -11.7562,
+                          -11.7562 104 16.1795,
+                          -11.7562 35.03 16.1795,
+                          -6.18191 35.03 19.0204,
+                          -11.7562 104 16.1795,
+                          -19.0204 104 -6.18191,
+                          -19.0204 104 6.18191,
+                          -16.1795 104 11.7562,
+                          -16.1795 35.03 11.7562,
+                          -16.1795 104 11.7562,
+                          -19.0204 104 6.18191,
+                          -16.1795 104 -11.7562,
+                          -19.0204 104 -6.18191,
+                          -16.1795 104 11.7562,
+                          -16.1795 35.03 11.7562,
+                          -11.7562 35.03 16.1795,
+                          -16.1795 104 11.7562,
+                          -19.0204 104 -6.18191,
+                          -20 104 -3.70848e-15,
+                          -19.0204 104 6.18191,
+                          -19.0204 35.03 6.18191,
+                          -19.0204 104 6.18191,
+                          -20 104 -3.70848e-15,
+                          -19.0204 35.03 6.18191,
+                          -16.1795 35.03 11.7562,
+                          -19.0204 104 6.18191,
+                          -20 35.03 -1.21546e-14,
+                          -20 104 -3.70848e-15,
+                          -19.0204 104 -6.18191,
+                          -20 35.03 -1.21546e-14,
+                          -19.0204 35.03 6.18191,
+                          -20 104 -3.70848e-15,
+                          -19.0204 35.03 -6.18191,
+                          -19.0204 104 -6.18191,
+                          -16.1795 104 -11.7562,
+                          -19.0204 35.03 -6.18191,
+                          -20 35.03 -1.21546e-14,
+                          -19.0204 104 -6.18191,
+                          -16.1795 35.03 -11.7562,
+                          -16.1795 104 -11.7562,
+                          -11.7562 104 -16.1795,
+                          -16.1795 35.03 -11.7562,
+                          -19.0204 35.03 -6.18191,
+                          -16.1795 104 -11.7562,
+                          -6.25379 104 -4.98861,
+                          -6.18191 104 -19.0204,
+                          -11.7562 104 -16.1795,
+                          -11.7562 35.03 -16.1795,
+                          -11.7562 104 -16.1795,
+                          -6.18191 104 -19.0204,
+                          -7.79899 104 -1.78051,
+                          -6.25379 104 -4.98861,
+                          -11.7562 104 -16.1795,
+                          -7.79899 104 1.78051,
+                          -7.79899 104 -1.78051,
+                          -11.7562 104 -16.1795,
+                          -11.7562 35.03 -16.1795,
+                          -16.1795 35.03 -11.7562,
+                          -11.7562 104 -16.1795,
+                          -3.47007 104 -7.20814,
+                          0 104 -8,
+                          -6.18191 104 -19.0204,
+                          -6.25379 104 -4.98861,
+                          -3.47007 104 -7.20814,
+                          -6.18191 104 -19.0204,
+                          -6.18191 35.03 -19.0204,
+                          -11.7562 35.03 -16.1795,
+                          -6.18191 104 -19.0204,
+                          0 104 -3,
+                          0 104 -8,
+                          -3.47007 104 -7.20814,
+                          2.59819 104 -1.49906,
+                          3.47007 104 -7.20814,
+                          0 104 -8,
+                          1.50086 104 -2.59741,
+                          0 104 -8,
+                          0 104 -3,
+                          1.50086 104 -2.59741,
+                          2.59819 104 -1.49906,
+                          0 104 -8,
+                          -3.47007 104 7.20814,
+                          -3.47007 104 -7.20814,
+                          -6.25379 104 -4.98861,
+                          -2.99954 104 -3.01123e-15,
+                          -3.47007 104 -7.20814,
+                          -3.47007 104 7.20814,
+                          -2.59819 104 -1.49906,
+                          -3.47007 104 -7.20814,
+                          -2.99954 104 -3.01123e-15,
+                          -1.50086 104 -2.59741,
+                          -3.47007 104 -7.20814,
+                          -2.59819 104 -1.49906,
+                          0 104 -3,
+                          -3.47007 104 -7.20814,
+                          -1.50086 104 -2.59741,
+                          -6.25379 104 4.98861,
+                          -6.25379 104 -4.98861,
+                          -7.79899 104 -1.78051,
+                          -3.47007 104 7.20814,
+                          -6.25379 104 -4.98861,
+                          -6.25379 104 4.98861,
+                          -6.25379 104 4.98861,
+                          -7.79899 104 -1.78051,
+                          -7.79899 104 1.78051,
+                          -2.59819 104 1.49906,
+                          -3.47007 104 7.20814,
+                          0 104 8,
+                          -2.99954 104 -3.01123e-15,
+                          -3.47007 104 7.20814,
+                          -2.59819 104 1.49906,
+                          0 104 3,
+                          0 104 8,
+                          3.47007 104 7.20814,
+                          -1.50086 104 2.59741,
+                          0 104 8,
+                          0 104 3,
+                          -2.59819 104 1.49906,
+                          0 104 8,
+                          -1.50086 104 2.59741,
+                          3.47007 104 -7.20814,
+                          3.47007 104 7.20814,
+                          6.25379 104 4.98861,
+                          2.99954 104 -3.01123e-15,
+                          3.47007 104 7.20814,
+                          3.47007 104 -7.20814,
+                          1.50086 104 2.59741,
+                          0 104 3,
+                          3.47007 104 7.20814,
+                          2.59819 104 1.49906,
+                          1.50086 104 2.59741,
+                          3.47007 104 7.20814,
+                          2.99954 104 -3.01123e-15,
+                          2.59819 104 1.49906,
+                          3.47007 104 7.20814,
+                          6.25379 104 -4.98861,
+                          6.25379 104 4.98861,
+                          7.79899 104 1.78051,
+                          3.47007 104 -7.20814,
+                          6.25379 104 4.98861,
+                          6.25379 104 -4.98861,
+                          6.25379 104 -4.98861,
+                          7.79899 104 1.78051,
+                          7.79899 104 -1.78051,
+                          2.59819 104 -1.49906,
+                          2.99954 104 -3.01123e-15,
+                          3.47007 104 -7.20814,
+                          0 35.03 15,
+                          0 35.03 20,
+                          -6.18191 35.03 19.0204,
+                          5.13142 35.03 14.0949,
+                          6.18191 35.03 19.0204,
+                          0 35.03 20,
+                          0 35.03 15,
+                          5.13142 35.03 14.0949,
+                          0 35.03 20,
+                          -9.64285 35.03 11.4895,
+                          -6.18191 35.03 19.0204,
+                          -11.7562 35.03 16.1795,
+                          -5.13142 35.03 14.0949,
+                          0 35.03 15,
+                          -6.18191 35.03 19.0204,
+                          -9.64285 35.03 11.4895,
+                          -5.13142 35.03 14.0949,
+                          -6.18191 35.03 19.0204,
+                          -12.9907 35.03 7.49882,
+                          -11.7562 35.03 16.1795,
+                          -16.1795 35.03 11.7562,
+                          -12.9907 35.03 7.49882,
+                          -9.64285 35.03 11.4895,
+                          -11.7562 35.03 16.1795,
+                          -16.1795 35.03 -11.7562,
+                          -16.1795 35.03 11.7562,
+                          -19.0204 35.03 6.18191,
+                          -14.7718 35.03 -2.60423,
+                          -16.1795 35.03 11.7562,
+                          -16.1795 35.03 -11.7562,
+                          -14.7718 35.03 2.60423,
+                          -12.9907 35.03 7.49882,
+                          -16.1795 35.03 11.7562,
+                          -14.7718 35.03 -2.60423,
+                          -14.7718 35.03 2.60423,
+                          -16.1795 35.03 11.7562,
+                          -19.0204 35.03 -6.18191,
+                          -19.0204 35.03 6.18191,
+                          -20 35.03 -1.21546e-14,
+                          -16.1795 35.03 -11.7562,
+                          -19.0204 35.03 6.18191,
+                          -19.0204 35.03 -6.18191,
+                          -14.7718 35.03 -2.60423,
+                          -16.1795 35.03 -11.7562,
+                          -11.7562 35.03 -16.1795,
+                          -9.64285 35.03 -11.4895,
+                          -11.7562 35.03 -16.1795,
+                          -6.18191 35.03 -19.0204,
+                          -12.9907 35.03 -7.49882,
+                          -14.7718 35.03 -2.60423,
+                          -11.7562 35.03 -16.1795,
+                          -9.64285 35.03 -11.4895,
+                          -12.9907 35.03 -7.49882,
+                          -11.7562 35.03 -16.1795,
+                          -5.13142 35.03 -14.0949,
+                          -6.18191 35.03 -19.0204,
+                          0 35.03 -20,
+                          -5.13142 35.03 -14.0949,
+                          -9.64285 35.03 -11.4895,
+                          -6.18191 35.03 -19.0204,
+                          0 35.03 -15,
+                          0 35.03 -20,
+                          6.18191 35.03 -19.0204,
+                          -5.13142 35.03 -14.0949,
+                          0 35.03 -20,
+                          0 35.03 -15,
+                          1.50086 104 -2.59741,
+                          1.5 107.55 -2.59808,
+                          2.59808 107.55 -1.5,
+                          1.50086 104 -2.59741,
+                          0 104 -3,
+                          1.5 107.55 -2.59808,
+                          2.59819 104 -1.49906,
+                          2.59808 107.55 -1.5,
+                          3 107.55 -2.60021e-15,
+                          1.50086 104 -2.59741,
+                          2.59808 107.55 -1.5,
+                          2.59819 104 -1.49906,
+                          2.99954 104 -3.01123e-15,
+                          3 107.55 -2.60021e-15,
+                          2.59808 107.55 1.5,
+                          2.59819 104 -1.49906,
+                          3 107.55 -2.60021e-15,
+                          2.99954 104 -3.01123e-15,
+                          2.59819 104 1.49906,
+                          2.59808 107.55 1.5,
+                          1.5 107.55 2.59808,
+                          2.99954 104 -3.01123e-15,
+                          2.59808 107.55 1.5,
+                          2.59819 104 1.49906,
+                          2.59819 104 1.49906,
+                          1.5 107.55 2.59808,
+                          1.50086 104 2.59741,
+                          9.64285 35.03 -11.4895,
+                          6.18191 35.03 -19.0204,
+                          11.7562 35.03 -16.1795,
+                          5.13142 35.03 -14.0949,
+                          0 35.03 -15,
+                          6.18191 35.03 -19.0204,
+                          9.64285 35.03 -11.4895,
+                          5.13142 35.03 -14.0949,
+                          6.18191 35.03 -19.0204,
+                          12.9907 35.03 -7.49882,
+                          11.7562 35.03 -16.1795,
+                          16.1795 35.03 -11.7562,
+                          12.9907 35.03 -7.49882,
+                          9.64285 35.03 -11.4895,
+                          11.7562 35.03 -16.1795,
+                          16.1795 35.03 11.7562,
+                          16.1795 35.03 -11.7562,
+                          19.0204 35.03 -6.18191,
+                          14.7718 35.03 2.60423,
+                          16.1795 35.03 -11.7562,
+                          16.1795 35.03 11.7562,
+                          14.7718 35.03 -2.60423,
+                          12.9907 35.03 -7.49882,
+                          16.1795 35.03 -11.7562,
+                          14.7718 35.03 2.60423,
+                          14.7718 35.03 -2.60423,
+                          16.1795 35.03 -11.7562,
+                          19.0204 35.03 6.18191,
+                          19.0204 35.03 -6.18191,
+                          20 35.03 -1.21546e-14,
+                          16.1795 35.03 11.7562,
+                          19.0204 35.03 -6.18191,
+                          19.0204 35.03 6.18191,
+                          14.7718 35.03 2.60423,
+                          16.1795 35.03 11.7562,
+                          11.7562 35.03 16.1795,
+                          9.64285 35.03 11.4895,
+                          11.7562 35.03 16.1795,
+                          6.18191 35.03 19.0204,
+                          12.9907 35.03 7.49882,
+                          14.7718 35.03 2.60423,
+                          11.7562 35.03 16.1795,
+                          9.64285 35.03 11.4895,
+                          12.9907 35.03 7.49882,
+                          11.7562 35.03 16.1795,
+                          5.13142 35.03 14.0949,
+                          9.64285 35.03 11.4895,
+                          6.18191 35.03 19.0204 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.25 0.25 0.25
+    }
+    Separator {
+        Normal {
+            vector      [ -1.22461e-16 1.22461e-16 -1,
+                          -1.22461e-16 1.22461e-16 -1,
+                          0.34202 1.15075e-16 -0.939693,
+                          -0.309017 1.16467e-16 -0.951057,
+                          -0.34202 1.15075e-16 -0.939693,
+                          -1.22461e-16 1.22461e-16 -1,
+                          -1.22461e-16 1.22461e-16 -1,
+                          -0.309017 1.16467e-16 -0.951057,
+                          -1.22461e-16 1.22461e-16 -1,
+                          0.587785 9.90727e-17 -0.809017,
+                          0.34202 1.15075e-16 -0.939693,
+                          0.642788 9.38103e-17 -0.766044,
+                          0.309017 1.16467e-16 -0.951057,
+                          -1.22461e-16 1.22461e-16 -1,
+                          0.34202 1.15075e-16 -0.939693,
+                          0.587785 9.90727e-17 -0.809017,
+                          0.309017 1.16467e-16 -0.951057,
+                          0.34202 1.15075e-16 -0.939693,
+                          0.809017 7.19806e-17 -0.587785,
+                          0.642788 9.38103e-17 -0.766044,
+                          0.866025 6.12303e-17 -0.5,
+                          0.809017 7.19806e-17 -0.587785,
+                          0.587785 9.90727e-17 -0.809017,
+                          0.642788 9.38103e-17 -0.766044,
+                          0.951057 3.78424e-17 -0.309017,
+                          0.866025 6.12303e-17 -0.5,
+                          0.984808 2.12651e-17 -0.173648,
+                          0.951057 3.78424e-17 -0.309017,
+                          0.809017 7.19806e-17 -0.587785,
+                          0.866025 6.12303e-17 -0.5,
+                          1 0 -1.83691e-16,
+                          0.984808 2.12651e-17 -0.173648,
+                          0.984808 -2.12651e-17 0.173648,
+                          0.951057 3.78424e-17 -0.309017,
+                          0.984808 2.12651e-17 -0.173648,
+                          1 0 -1.83691e-16,
+                          0.951057 -3.78424e-17 0.309017,
+                          0.984808 -2.12651e-17 0.173648,
+                          0.866025 -6.12303e-17 0.5,
+                          1 0 -1.83691e-16,
+                          0.984808 -2.12651e-17 0.173648,
+                          0.951057 -3.78424e-17 0.309017,
+                          0.809017 -7.19806e-17 0.587785,
+                          0.866025 -6.12303e-17 0.5,
+                          0.642788 -9.38103e-17 0.766044,
+                          0.951057 -3.78424e-17 0.309017,
+                          0.866025 -6.12303e-17 0.5,
+                          0.809017 -7.19806e-17 0.587785,
+                          0.587785 -9.90727e-17 0.809017,
+                          0.642788 -9.38103e-17 0.766044,
+                          0.34202 -1.15075e-16 0.939693,
+                          0.809017 -7.19806e-17 0.587785,
+                          0.642788 -9.38103e-17 0.766044,
+                          0.587785 -9.90727e-17 0.809017,
+                          0.309017 -1.16467e-16 0.951057,
+                          0.34202 -1.15075e-16 0.939693,
+                          2.44921e-16 -1.22461e-16 1,
+                          0.587785 -9.90727e-17 0.809017,
+                          0.34202 -1.15075e-16 0.939693,
+                          0.309017 -1.16467e-16 0.951057,
+                          0 -1.22461e-16 1,
+                          0 -1.22461e-16 1,
+                          -0.34202 -1.15075e-16 0.939693,
+                          0.309017 -1.16467e-16 0.951057,
+                          2.44921e-16 -1.22461e-16 1,
+                          2.44921e-16 -1.22461e-16 1,
+                          -0.5 -1.06054e-16 0.866025,
+                          -0.34202 -1.15075e-16 0.939693,
+                          -0.642788 -9.38103e-17 0.766044,
+                          -0.173648 -1.206e-16 0.984808,
+                          0 -1.22461e-16 1,
+                          -0.34202 -1.15075e-16 0.939693,
+                          -0.5 -1.06054e-16 0.866025,
+                          -0.173648 -1.206e-16 0.984808,
+                          -0.34202 -1.15075e-16 0.939693,
+                          -0.766044 -7.87162e-17 0.642788,
+                          -0.642788 -9.38103e-17 0.766044,
+                          -0.866025 -6.12303e-17 0.5,
+                          -0.766044 -7.87162e-17 0.642788,
+                          -0.5 -1.06054e-16 0.866025,
+                          -0.642788 -9.38103e-17 0.766044,
+                          -0.939693 -4.1884e-17 0.34202,
+                          -0.866025 -6.12303e-17 0.5,
+                          -0.984808 -2.12651e-17 0.173648,
+                          -0.939693 -4.1884e-17 0.34202,
+                          -0.766044 -7.87162e-17 0.642788,
+                          -0.866025 -6.12303e-17 0.5,
+                          -1 0 6.12303e-17,
+                          -0.984808 -2.12651e-17 0.173648,
+                          -0.984808 2.12651e-17 -0.173648,
+                          -1 0 6.12303e-17,
+                          -0.939693 -4.1884e-17 0.34202,
+                          -0.984808 -2.12651e-17 0.173648,
+                          -0.951057 3.78424e-17 -0.309017,
+                          -0.984808 2.12651e-17 -0.173648,
+                          -0.866025 6.12303e-17 -0.5,
+                          -0.951057 3.78424e-17 -0.309017,
+                          -1 0 6.12303e-17,
+                          -0.984808 2.12651e-17 -0.173648,
+                          -0.809017 7.19806e-17 -0.587785,
+                          -0.866025 6.12303e-17 -0.5,
+                          -0.642788 9.38103e-17 -0.766044,
+                          -0.809017 7.19806e-17 -0.587785,
+                          -0.951057 3.78424e-17 -0.309017,
+                          -0.866025 6.12303e-17 -0.5,
+                          -0.587785 9.90727e-17 -0.809017,
+                          -0.642788 9.38103e-17 -0.766044,
+                          -0.34202 1.15075e-16 -0.939693,
+                          -0.587785 9.90727e-17 -0.809017,
+                          -0.809017 7.19806e-17 -0.587785,
+                          -0.642788 9.38103e-17 -0.766044,
+                          -0.309017 1.16467e-16 -0.951057,
+                          -0.587785 9.90727e-17 -0.809017,
+                          -0.34202 1.15075e-16 -0.939693,
+                          0.173648 -1.206e-16 0.984808,
+                          0.309017 -1.16467e-16 0.951057,
+                          0 -1.22461e-16 1,
+                          -0.173648 -1.206e-16 0.984808,
+                          0.173648 -1.206e-16 0.984808,
+                          0 -1.22461e-16 1,
+                          0.5 -1.06054e-16 0.866025,
+                          0.587785 -9.90727e-17 0.809017,
+                          0.309017 -1.16467e-16 0.951057,
+                          0.173648 -1.206e-16 0.984808,
+                          0.5 -1.06054e-16 0.866025,
+                          0.309017 -1.16467e-16 0.951057,
+                          0.766044 -7.87162e-17 0.642788,
+                          0.809017 -7.19806e-17 0.587785,
+                          0.587785 -9.90727e-17 0.809017,
+                          0.5 -1.06054e-16 0.866025,
+                          0.766044 -7.87162e-17 0.642788,
+                          0.587785 -9.90727e-17 0.809017,
+                          0.939693 -4.1884e-17 0.34202,
+                          0.951057 -3.78424e-17 0.309017,
+                          0.809017 -7.19806e-17 0.587785,
+                          0.766044 -7.87162e-17 0.642788,
+                          0.939693 -4.1884e-17 0.34202,
+                          0.809017 -7.19806e-17 0.587785,
+                          1 0 6.12303e-17,
+                          1 0 6.12303e-17,
+                          0.951057 -3.78424e-17 0.309017,
+                          0.939693 -4.1884e-17 0.34202,
+                          1 0 6.12303e-17,
+                          0.951057 -3.78424e-17 0.309017,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          -1 0 6.12303e-17,
+                          -1 0 6.12303e-17,
+                          -0.939693 -4.1884e-17 0.34202,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          0 1 1.22461e-16,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.866025 6.12303e-17 -0.5,
+                          -0.866025 6.12303e-17 -0.5,
+                          -0.866025 6.12303e-17 -0.5,
+                          -0.5 1.06054e-16 -0.866025,
+                          -1 0 0,
+                          -0.866025 6.12303e-17 -0.5,
+                          -0.866025 6.12303e-17 -0.5,
+                          -0.5 1.06054e-16 -0.866025,
+                          -0.5 1.06054e-16 -0.866025,
+                          -6.12303e-17 1.22461e-16 -1,
+                          -0.866025 6.12303e-17 -0.5,
+                          -0.5 1.06054e-16 -0.866025,
+                          -0.5 1.06054e-16 -0.866025,
+                          0 1.22461e-16 -1,
+                          0 1.22461e-16 -1,
+                          0 1.22461e-16 -1,
+                          -0.5 1.06054e-16 -0.866025,
+                          -6.12303e-17 1.22461e-16 -1,
+                          -6.12303e-17 1.22461e-16 -1,
+                          -6.12303e-17 1.22461e-16 -1,
+                          -6.12303e-17 1.22461e-16 -1,
+                          0.5 1.06054e-16 -0.866025,
+                          0 1.22461e-16 -1,
+                          0 1.22461e-16 -1,
+                          0 1.22461e-16 -1,
+                          0.5 1.06054e-16 -0.866025,
+                          0.5 1.06054e-16 -0.866025,
+                          0.866025 6.12303e-17 -0.5,
+                          -6.12303e-17 1.22461e-16 -1,
+                          0.5 1.06054e-16 -0.866025,
+                          0.5 1.06054e-16 -0.866025,
+                          0.866025 6.12303e-17 -0.5,
+                          0.866025 6.12303e-17 -0.5,
+                          1 0 -1.22461e-16,
+                          0.5 1.06054e-16 -0.866025,
+                          0.866025 6.12303e-17 -0.5,
+                          0.866025 6.12303e-17 -0.5,
+                          0.866025 6.12303e-17 -0.5,
+                          1 0 -1.22461e-16,
+                          1 0 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16,
+                          0 -1 -1.22461e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -1.83691e-15 33 -15,
+                          0 35.03 -15,
+                          5.13142 35.03 -14.0949,
+                          -4.63643 33 -14.2653,
+                          -5.13142 35.03 -14.0949,
+                          0 35.03 -15,
+                          -1.83691e-15 33 -15,
+                          -4.63643 33 -14.2653,
+                          0 35.03 -15,
+                          8.81712 33 -12.1346,
+                          5.13142 35.03 -14.0949,
+                          9.64285 35.03 -11.4895,
+                          4.63643 33 -14.2653,
+                          -1.83691e-15 33 -15,
+                          5.13142 35.03 -14.0949,
+                          8.81712 33 -12.1346,
+                          4.63643 33 -14.2653,
+                          5.13142 35.03 -14.0949,
+                          12.1346 33 -8.81712,
+                          9.64285 35.03 -11.4895,
+                          12.9907 35.03 -7.49882,
+                          12.1346 33 -8.81712,
+                          8.81712 33 -12.1346,
+                          9.64285 35.03 -11.4895,
+                          14.2653 33 -4.63643,
+                          12.9907 35.03 -7.49882,
+                          14.7718 35.03 -2.60423,
+                          14.2653 33 -4.63643,
+                          12.1346 33 -8.81712,
+                          12.9907 35.03 -7.49882,
+                          15 33 -1.11786e-14,
+                          14.7718 35.03 -2.60423,
+                          14.7718 35.03 2.60423,
+                          14.2653 33 -4.63643,
+                          14.7718 35.03 -2.60423,
+                          15 33 -1.11786e-14,
+                          14.2658 33 4.63525,
+                          14.7718 35.03 2.60423,
+                          12.9907 35.03 7.49882,
+                          15 33 -1.11786e-14,
+                          14.7718 35.03 2.60423,
+                          14.2658 33 4.63525,
+                          12.1353 33 8.81678,
+                          12.9907 35.03 7.49882,
+                          9.64285 35.03 11.4895,
+                          14.2658 33 4.63525,
+                          12.9907 35.03 7.49882,
+                          12.1353 33 8.81678,
+                          8.81678 33 12.1353,
+                          9.64285 35.03 11.4895,
+                          5.13142 35.03 14.0949,
+                          12.1353 33 8.81678,
+                          9.64285 35.03 11.4895,
+                          8.81678 33 12.1353,
+                          4.63525 33 14.2658,
+                          5.13142 35.03 14.0949,
+                          0 35.03 15,
+                          8.81678 33 12.1353,
+                          5.13142 35.03 14.0949,
+                          4.63525 33 14.2658,
+                          0 33 15,
+                          0 35.03 15,
+                          -5.13142 35.03 14.0949,
+                          4.63525 33 14.2658,
+                          0 35.03 15,
+                          0 33 15,
+                          -7.49882 14.7 12.9907,
+                          -5.13142 35.03 14.0949,
+                          -9.64285 35.03 11.4895,
+                          -2.60423 14.7 14.7718,
+                          0 33 15,
+                          -5.13142 35.03 14.0949,
+                          -7.49882 14.7 12.9907,
+                          -2.60423 14.7 14.7718,
+                          -5.13142 35.03 14.0949,
+                          -11.4895 14.7 9.64285,
+                          -9.64285 35.03 11.4895,
+                          -12.9907 35.03 7.49882,
+                          -11.4895 14.7 9.64285,
+                          -7.49882 14.7 12.9907,
+                          -9.64285 35.03 11.4895,
+                          -14.0949 14.7 5.13142,
+                          -12.9907 35.03 7.49882,
+                          -14.7718 35.03 2.60423,
+                          -14.0949 14.7 5.13142,
+                          -11.4895 14.7 9.64285,
+                          -12.9907 35.03 7.49882,
+                          -15 33 -1.11786e-14,
+                          -14.7718 35.03 2.60423,
+                          -14.7718 35.03 -2.60423,
+                          -15 33 -1.11786e-14,
+                          -14.0949 14.7 5.13142,
+                          -14.7718 35.03 2.60423,
+                          -14.2653 33 -4.63643,
+                          -14.7718 35.03 -2.60423,
+                          -12.9907 35.03 -7.49882,
+                          -14.2653 33 -4.63643,
+                          -15 33 -1.11786e-14,
+                          -14.7718 35.03 -2.60423,
+                          -12.1346 33 -8.81712,
+                          -12.9907 35.03 -7.49882,
+                          -9.64285 35.03 -11.4895,
+                          -12.1346 33 -8.81712,
+                          -14.2653 33 -4.63643,
+                          -12.9907 35.03 -7.49882,
+                          -8.81712 33 -12.1346,
+                          -9.64285 35.03 -11.4895,
+                          -5.13142 35.03 -14.0949,
+                          -8.81712 33 -12.1346,
+                          -12.1346 33 -8.81712,
+                          -9.64285 35.03 -11.4895,
+                          -4.63643 33 -14.2653,
+                          -8.81712 33 -12.1346,
+                          -5.13142 35.03 -14.0949,
+                          2.60423 14.7 14.7718,
+                          4.63525 33 14.2658,
+                          0 33 15,
+                          -2.60423 14.7 14.7718,
+                          2.60423 14.7 14.7718,
+                          0 33 15,
+                          7.49882 14.7 12.9907,
+                          8.81678 33 12.1353,
+                          4.63525 33 14.2658,
+                          2.60423 14.7 14.7718,
+                          7.49882 14.7 12.9907,
+                          4.63525 33 14.2658,
+                          11.4895 14.7 9.64285,
+                          12.1353 33 8.81678,
+                          8.81678 33 12.1353,
+                          7.49882 14.7 12.9907,
+                          11.4895 14.7 9.64285,
+                          8.81678 33 12.1353,
+                          14.0949 14.7 5.13142,
+                          14.2658 33 4.63525,
+                          12.1353 33 8.81678,
+                          11.4895 14.7 9.64285,
+                          14.0949 14.7 5.13142,
+                          12.1353 33 8.81678,
+                          15 14.7 -1.27726e-14,
+                          15 33 -1.11786e-14,
+                          14.2658 33 4.63525,
+                          14.0949 14.7 5.13142,
+                          15 14.7 -1.27726e-14,
+                          14.2658 33 4.63525,
+                          15 14.7 -22.2,
+                          15 33 -1.11786e-14,
+                          15 14.7 -1.27726e-14,
+                          14.4641 33 -24.2,
+                          14.2653 33 -4.63643,
+                          15 33 -1.11786e-14,
+                          15 33 -22.2,
+                          14.4641 33 -24.2,
+                          15 33 -1.11786e-14,
+                          15 14.7 -22.2,
+                          15 33 -22.2,
+                          15 33 -1.11786e-14,
+                          -15 14.7 -7.26192e-15,
+                          15 14.7 -1.27726e-14,
+                          14.0949 14.7 5.13142,
+                          -15 14.7 -22.2,
+                          15 14.7 -1.27726e-14,
+                          -15 14.7 -7.26192e-15,
+                          -15 14.7 -22.2,
+                          15 14.7 -22.2,
+                          15 14.7 -1.27726e-14,
+                          -14.0949 14.7 5.13142,
+                          14.0949 14.7 5.13142,
+                          11.4895 14.7 9.64285,
+                          -15 14.7 -7.26192e-15,
+                          14.0949 14.7 5.13142,
+                          -14.0949 14.7 5.13142,
+                          -11.4895 14.7 9.64285,
+                          11.4895 14.7 9.64285,
+                          7.49882 14.7 12.9907,
+                          -14.0949 14.7 5.13142,
+                          11.4895 14.7 9.64285,
+                          -11.4895 14.7 9.64285,
+                          -7.49882 14.7 12.9907,
+                          7.49882 14.7 12.9907,
+                          2.60423 14.7 14.7718,
+                          -11.4895 14.7 9.64285,
+                          7.49882 14.7 12.9907,
+                          -7.49882 14.7 12.9907,
+                          -7.49882 14.7 12.9907,
+                          2.60423 14.7 14.7718,
+                          -2.60423 14.7 14.7718,
+                          -15 33 -1.11786e-14,
+                          -15 14.7 -7.26192e-15,
+                          -14.0949 14.7 5.13142,
+                          -15 33 -22.2,
+                          -15 14.7 -7.26192e-15,
+                          -15 33 -1.11786e-14,
+                          -15 14.7 -22.2,
+                          -15 14.7 -7.26192e-15,
+                          -15 33 -22.2,
+                          -15 33 -22.2,
+                          -15 33 -1.11786e-14,
+                          -14.2653 33 -4.63643,
+                          -13 33 -25.6641,
+                          -14.2653 33 -4.63643,
+                          -12.1346 33 -8.81712,
+                          -14.4641 33 -24.2,
+                          -15 33 -22.2,
+                          -14.2653 33 -4.63643,
+                          -13 33 -25.6641,
+                          -14.4641 33 -24.2,
+                          -14.2653 33 -4.63643,
+                          -11 33 -26.2,
+                          -12.1346 33 -8.81712,
+                          -8.81712 33 -12.1346,
+                          -11 33 -26.2,
+                          -13 33 -25.6641,
+                          -12.1346 33 -8.81712,
+                          -11 33 -26.2,
+                          -8.81712 33 -12.1346,
+                          -4.63643 33 -14.2653,
+                          -11 33 -26.2,
+                          -4.63643 33 -14.2653,
+                          -1.83691e-15 33 -15,
+                          -11 33 -26.2,
+                          -1.83691e-15 33 -15,
+                          4.63643 33 -14.2653,
+                          -11 33 -26.2,
+                          4.63643 33 -14.2653,
+                          8.81712 33 -12.1346,
+                          11 33 -26.2,
+                          8.81712 33 -12.1346,
+                          12.1346 33 -8.81712,
+                          11 33 -26.2,
+                          -11 33 -26.2,
+                          8.81712 33 -12.1346,
+                          13 33 -25.6641,
+                          12.1346 33 -8.81712,
+                          14.2653 33 -4.63643,
+                          13 33 -25.6641,
+                          11 33 -26.2,
+                          12.1346 33 -8.81712,
+                          14.4641 33 -24.2,
+                          13 33 -25.6641,
+                          14.2653 33 -4.63643,
+                          -15 14.7 -22.2,
+                          -15 33 -22.2,
+                          -14.4641 33 -24.2,
+                          -14.4641 14.7 -24.2,
+                          -14.4641 33 -24.2,
+                          -13 33 -25.6641,
+                          -15 14.7 -22.2,
+                          -14.4641 33 -24.2,
+                          -14.4641 14.7 -24.2,
+                          -13 14.7 -25.6641,
+                          -13 33 -25.6641,
+                          -11 33 -26.2,
+                          -14.4641 14.7 -24.2,
+                          -13 33 -25.6641,
+                          -13 14.7 -25.6641,
+                          -11 14.7 -26.2,
+                          -11 33 -26.2,
+                          11 33 -26.2,
+                          -13 14.7 -25.6641,
+                          -11 33 -26.2,
+                          -11 14.7 -26.2,
+                          11 14.7 -26.2,
+                          11 33 -26.2,
+                          13 33 -25.6641,
+                          -11 14.7 -26.2,
+                          11 33 -26.2,
+                          11 14.7 -26.2,
+                          13 14.7 -25.6641,
+                          13 33 -25.6641,
+                          14.4641 33 -24.2,
+                          11 14.7 -26.2,
+                          13 33 -25.6641,
+                          13 14.7 -25.6641,
+                          14.4641 14.7 -24.2,
+                          14.4641 33 -24.2,
+                          15 33 -22.2,
+                          13 14.7 -25.6641,
+                          14.4641 33 -24.2,
+                          14.4641 14.7 -24.2,
+                          14.4641 14.7 -24.2,
+                          15 33 -22.2,
+                          15 14.7 -22.2,
+                          -14.4641 14.7 -24.2,
+                          14.4641 14.7 -24.2,
+                          15 14.7 -22.2,
+                          -15 14.7 -22.2,
+                          -14.4641 14.7 -24.2,
+                          15 14.7 -22.2,
+                          -13 14.7 -25.6641,
+                          13 14.7 -25.6641,
+                          14.4641 14.7 -24.2,
+                          -14.4641 14.7 -24.2,
+                          -13 14.7 -25.6641,
+                          14.4641 14.7 -24.2,
+                          -11 14.7 -26.2,
+                          11 14.7 -26.2,
+                          13 14.7 -25.6641,
+                          -13 14.7 -25.6641,
+                          -11 14.7 -26.2,
+                          13 14.7 -25.6641 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.95 0.77 0.53
+    }
+    Separator {
+        Normal {
+            vector      [ -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 0.281733 -0.959493,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.281733 -0.959493,
+                          0 -0.281733 -0.959493,
+                          0 -2.28767e-17 -1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.281733 -0.959493,
+                          0 -2.28767e-17 -1,
+                          0 -2.28767e-17 -1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.281733 -0.959493,
+                          0 0.281733 -0.959493,
+                          0 0.540641 -0.841254,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.281733 -0.959493,
+                          0 2.22045e-16 -1,
+                          0 0.281733 -0.959493,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.540641 -0.841254,
+                          0 0.540641 -0.841254,
+                          0 0.75575 -0.654861,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.281733 -0.959493,
+                          0 0.540641 -0.841254,
+                          0 0.540641 -0.841254,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.75575 -0.654861,
+                          0 0.75575 -0.654861,
+                          0 0.909632 -0.415415,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.540641 -0.841254,
+                          0 0.75575 -0.654861,
+                          0 0.75575 -0.654861,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.909632 -0.415415,
+                          0 0.909632 -0.415415,
+                          0 0.989821 -0.142315,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.75575 -0.654861,
+                          0 0.909632 -0.415415,
+                          0 0.909632 -0.415415,
+                          0 0.989821 -0.142315,
+                          0 0.989821 -0.142315,
+                          0 0.989821 0.142315,
+                          0 0.909632 -0.415415,
+                          0 0.989821 -0.142315,
+                          0 0.989821 -0.142315,
+                          0 0.989821 0.142315,
+                          0 0.989821 0.142315,
+                          0 0.909632 0.415415,
+                          0 0.989821 -0.142315,
+                          0 0.989821 0.142315,
+                          0 0.989821 0.142315,
+                          0 0.909632 0.415415,
+                          0 0.909632 0.415415,
+                          0 0.75575 0.654861,
+                          0 0.989821 0.142315,
+                          0 0.909632 0.415415,
+                          0 0.909632 0.415415,
+                          0 0.75575 0.654861,
+                          0 0.75575 0.654861,
+                          0 0.540641 0.841254,
+                          0 0.909632 0.415415,
+                          0 0.75575 0.654861,
+                          0 0.75575 0.654861,
+                          0 0.540641 0.841254,
+                          0 0.540641 0.841254,
+                          0 0.281733 0.959493,
+                          0 0.75575 0.654861,
+                          0 0.540641 0.841254,
+                          0 0.540641 0.841254,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.281733 0.959493,
+                          0 0.281733 0.959493,
+                          0 -9.9584e-17 1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.540641 0.841254,
+                          0 0.281733 0.959493,
+                          0 0.281733 0.959493,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -9.9584e-17 1,
+                          0 -9.9584e-17 1,
+                          0 -0.281733 0.959493,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.281733 0.959493,
+                          0 -9.9584e-17 1,
+                          0 -9.9584e-17 1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.281733 0.959493,
+                          0 -0.281733 0.959493,
+                          0 -0.540641 0.841254,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -9.9584e-17 1,
+                          0 -0.281733 0.959493,
+                          0 -0.281733 0.959493,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.540641 0.841254,
+                          0 -0.540641 0.841254,
+                          0 -0.75575 0.654861,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.281733 0.959493,
+                          0 -0.540641 0.841254,
+                          0 -0.540641 0.841254,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.75575 0.654861,
+                          0 -0.75575 0.654861,
+                          0 -0.909632 0.415415,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.540641 0.841254,
+                          0 -0.75575 0.654861,
+                          0 -0.75575 0.654861,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.909632 0.415415,
+                          0 -0.909632 0.415415,
+                          0 -0.989821 0.142315,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.75575 0.654861,
+                          0 -0.909632 0.415415,
+                          0 -0.909632 0.415415,
+                          0 -0.989821 0.142315,
+                          0 -0.989821 0.142315,
+                          0 -0.989821 -0.142315,
+                          0 -0.909632 0.415415,
+                          0 -0.989821 0.142315,
+                          0 -0.989821 0.142315,
+                          0 -0.989821 -0.142315,
+                          0 -0.989821 -0.142315,
+                          0 -0.909632 -0.415415,
+                          0 -0.989821 0.142315,
+                          0 -0.989821 -0.142315,
+                          0 -0.989821 -0.142315,
+                          0 -0.909632 -0.415415,
+                          0 -0.909632 -0.415415,
+                          0 -0.75575 -0.654861,
+                          0 -0.989821 -0.142315,
+                          0 -0.909632 -0.415415,
+                          0 -0.909632 -0.415415,
+                          0 -0.75575 -0.654861,
+                          0 -0.75575 -0.654861,
+                          0 -0.540641 -0.841254,
+                          0 -0.909632 -0.415415,
+                          0 -0.75575 -0.654861,
+                          0 -0.75575 -0.654861,
+                          0 -0.540641 -0.841254,
+                          0 -0.540641 -0.841254,
+                          0 -0.281733 -0.959493,
+                          0 -0.75575 -0.654861,
+                          0 -0.540641 -0.841254,
+                          0 -0.540641 -0.841254,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.540641 -0.841254,
+                          0 -0.281733 -0.959493,
+                          0 -0.281733 -0.959493,
+                          0 2.28767e-17 1,
+                          0 2.28767e-17 1,
+                          0 0.5 0.866025,
+                          0 -0.5 0.866025,
+                          0 -0.5 0.866025,
+                          0 -2.22045e-16 1,
+                          0 -0.5 0.866025,
+                          0 -2.22045e-16 1,
+                          0 -9.9584e-17 1,
+                          0 0.5 0.866025,
+                          0 0.5 0.866025,
+                          0 0.866025 0.5,
+                          0 0.5 0.866025,
+                          0 2.28767e-17 1,
+                          0 0.5 0.866025,
+                          0 0.866025 0.5,
+                          0 0.866025 0.5,
+                          0 1 3.83537e-17,
+                          0 0.5 0.866025,
+                          0 0.866025 0.5,
+                          0 0.866025 0.5,
+                          0 1 3.83537e-17,
+                          0 1 3.83537e-17,
+                          0 0.866025 -0.5,
+                          0 0.866025 0.5,
+                          0 1 3.83537e-17,
+                          0 1 3.83537e-17,
+                          0 0.866025 -0.5,
+                          0 0.866025 -0.5,
+                          0 0.5 -0.866025,
+                          0 1 3.83537e-17,
+                          0 0.866025 -0.5,
+                          0 0.866025 -0.5,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 9.9584e-17 -1,
+                          0 0.866025 -0.5,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 9.9584e-17 -1,
+                          0 9.9584e-17 -1,
+                          0 -0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 9.9584e-17 -1,
+                          0 9.9584e-17 -1,
+                          0 -0.5 -0.866025,
+                          0 -0.5 -0.866025,
+                          0 -0.866025 -0.5,
+                          0 9.9584e-17 -1,
+                          0 -0.5 -0.866025,
+                          0 -0.5 -0.866025,
+                          0 -0.866025 -0.5,
+                          0 -0.866025 -0.5,
+                          0 -1 -1.60814e-16,
+                          0 -0.5 -0.866025,
+                          0 -0.866025 -0.5,
+                          0 -0.866025 -0.5,
+                          0 -1 -1.60814e-16,
+                          0 -1 -1.60814e-16,
+                          0 -0.866025 0.5,
+                          0 -0.866025 -0.5,
+                          0 -1 -1.60814e-16,
+                          0 -1 -1.60814e-16,
+                          0 -0.866025 0.5,
+                          0 -0.866025 0.5,
+                          0 -0.5 0.866025,
+                          0 -1 -1.60814e-16,
+                          0 -0.866025 0.5,
+                          0 -0.866025 0.5,
+                          0 -0.866025 0.5,
+                          0 -0.5 0.866025,
+                          0 -0.5 0.866025,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          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 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -0.34202 0.939693,
+                          0 0.34202 0.939693,
+                          0 0.34202 0.939693,
+                          0 2.28767e-17 1,
+                          0 0.34202 0.939693,
+                          0 2.28767e-17 1,
+                          0 2.28767e-17 1,
+                          0 -0.34202 0.939693,
+                          0 -0.34202 0.939693,
+                          0 -0.642788 0.766044,
+                          0 -0.34202 0.939693,
+                          0 -2.22045e-16 1,
+                          0 -0.34202 0.939693,
+                          0 -0.642788 0.766044,
+                          0 -0.642788 0.766044,
+                          0 -0.866025 0.5,
+                          0 -0.34202 0.939693,
+                          0 -0.642788 0.766044,
+                          0 -0.642788 0.766044,
+                          0 -0.866025 0.5,
+                          0 -0.866025 0.5,
+                          0 -0.984808 0.173648,
+                          0 -0.642788 0.766044,
+                          0 -0.866025 0.5,
+                          0 -0.866025 0.5,
+                          0 -0.984808 0.173648,
+                          0 -0.984808 0.173648,
+                          0 -0.984808 -0.173648,
+                          0 -0.866025 0.5,
+                          0 -0.984808 0.173648,
+                          0 -0.984808 0.173648,
+                          0 -0.984808 -0.173648,
+                          0 -0.984808 -0.173648,
+                          0 -0.866025 -0.5,
+                          0 -0.984808 0.173648,
+                          0 -0.984808 -0.173648,
+                          0 -0.984808 -0.173648,
+                          0 -0.866025 -0.5,
+                          0 -0.866025 -0.5,
+                          0 -0.642788 -0.766044,
+                          0 -0.984808 -0.173648,
+                          0 -0.866025 -0.5,
+                          0 -0.866025 -0.5,
+                          0 -0.642788 -0.766044,
+                          0 -0.642788 -0.766044,
+                          0 -0.34202 -0.939693,
+                          0 -0.866025 -0.5,
+                          0 -0.642788 -0.766044,
+                          0 -0.642788 -0.766044,
+                          0 -0.34202 -0.939693,
+                          0 -0.34202 -0.939693,
+                          0 9.9584e-17 -1,
+                          0 -0.642788 -0.766044,
+                          0 -0.34202 -0.939693,
+                          0 -0.34202 -0.939693,
+                          0 9.9584e-17 -1,
+                          0 9.9584e-17 -1,
+                          0 0.34202 -0.939693,
+                          0 -0.34202 -0.939693,
+                          0 9.9584e-17 -1,
+                          0 9.9584e-17 -1,
+                          0 0.34202 -0.939693,
+                          0 0.34202 -0.939693,
+                          0 0.642788 -0.766044,
+                          0 9.9584e-17 -1,
+                          0 0.34202 -0.939693,
+                          0 0.34202 -0.939693,
+                          0 0.642788 -0.766044,
+                          0 0.642788 -0.766044,
+                          0 0.866025 -0.5,
+                          0 0.34202 -0.939693,
+                          0 0.642788 -0.766044,
+                          0 0.642788 -0.766044,
+                          0 0.866025 -0.5,
+                          0 0.866025 -0.5,
+                          0 0.984808 -0.173648,
+                          0 0.642788 -0.766044,
+                          0 0.866025 -0.5,
+                          0 0.866025 -0.5,
+                          0 0.984808 -0.173648,
+                          0 0.984808 -0.173648,
+                          0 0.984808 0.173648,
+                          0 0.866025 -0.5,
+                          0 0.984808 -0.173648,
+                          0 0.984808 -0.173648,
+                          0 0.984808 0.173648,
+                          0 0.984808 0.173648,
+                          0 0.866025 0.5,
+                          0 0.984808 -0.173648,
+                          0 0.984808 0.173648,
+                          0 0.984808 0.173648,
+                          0 0.866025 0.5,
+                          0 0.866025 0.5,
+                          0 0.642788 0.766044,
+                          0 0.984808 0.173648,
+                          0 0.866025 0.5,
+                          0 0.866025 0.5,
+                          0 0.642788 0.766044,
+                          0 0.642788 0.766044,
+                          0 0.34202 0.939693,
+                          0 0.866025 0.5,
+                          0 0.642788 0.766044,
+                          0 0.642788 0.766044,
+                          0 0.642788 0.766044,
+                          0 0.34202 0.939693,
+                          0 0.34202 0.939693,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 44.75 5.5 8.84472e-16,
+                          44.75 7.04331 -23.9873,
+                          44.75 2.48959e-15 -25,
+                          49.5 2.48959e-15 -25,
+                          44.75 2.48959e-15 -25,
+                          44.75 7.04331 -23.9873,
+                          44.75 5.47702e-16 -5.5,
+                          44.75 2.48959e-15 -25,
+                          44.75 -7.04331 -23.9873,
+                          49.5 -7.04331 -23.9873,
+                          44.75 -7.04331 -23.9873,
+                          44.75 2.48959e-15 -25,
+                          44.75 2.75037 -4.76275,
+                          44.75 2.48959e-15 -25,
+                          44.75 5.47702e-16 -5.5,
+                          44.75 4.76275 -2.75037,
+                          44.75 5.5 8.84472e-16,
+                          44.75 2.48959e-15 -25,
+                          44.75 2.75037 -4.76275,
+                          44.75 4.76275 -2.75037,
+                          44.75 2.48959e-15 -25,
+                          49.5 -7.04331 -23.9873,
+                          44.75 2.48959e-15 -25,
+                          49.5 2.48959e-15 -25,
+                          44.75 13.516 21.0313,
+                          44.75 13.516 -21.0313,
+                          44.75 7.04331 -23.9873,
+                          49.5 7.04331 -23.9873,
+                          44.75 7.04331 -23.9873,
+                          44.75 13.516 -21.0313,
+                          44.75 7.04331 23.9873,
+                          44.75 13.516 21.0313,
+                          44.75 7.04331 -23.9873,
+                          44.75 5.5 8.84472e-16,
+                          44.75 7.04331 23.9873,
+                          44.75 7.04331 -23.9873,
+                          49.5 7.04331 -23.9873,
+                          49.5 2.48959e-15 -25,
+                          44.75 7.04331 -23.9873,
+                          44.75 18.8937 16.3715,
+                          44.75 18.8937 -16.3715,
+                          44.75 13.516 -21.0313,
+                          49.5 13.516 -21.0313,
+                          44.75 13.516 -21.0313,
+                          44.75 18.8937 -16.3715,
+                          44.75 13.516 21.0313,
+                          44.75 18.8937 16.3715,
+                          44.75 13.516 -21.0313,
+                          49.5 7.04331 -23.9873,
+                          44.75 13.516 -21.0313,
+                          49.5 13.516 -21.0313,
+                          44.75 22.7408 10.3854,
+                          44.75 22.7408 -10.3854,
+                          44.75 18.8937 -16.3715,
+                          49.5 18.8937 -16.3715,
+                          44.75 18.8937 -16.3715,
+                          44.75 22.7408 -10.3854,
+                          44.75 18.8937 16.3715,
+                          44.75 22.7408 10.3854,
+                          44.75 18.8937 -16.3715,
+                          49.5 13.516 -21.0313,
+                          44.75 18.8937 -16.3715,
+                          49.5 18.8937 -16.3715,
+                          44.75 24.7455 3.55787,
+                          44.75 24.7455 -3.55787,
+                          44.75 22.7408 -10.3854,
+                          49.5 22.7408 -10.3854,
+                          44.75 22.7408 -10.3854,
+                          44.75 24.7455 -3.55787,
+                          44.75 22.7408 10.3854,
+                          44.75 24.7455 3.55787,
+                          44.75 22.7408 -10.3854,
+                          49.5 18.8937 -16.3715,
+                          44.75 22.7408 -10.3854,
+                          49.5 22.7408 -10.3854,
+                          49.5 24.7455 -3.55787,
+                          44.75 24.7455 -3.55787,
+                          44.75 24.7455 3.55787,
+                          49.5 22.7408 -10.3854,
+                          44.75 24.7455 -3.55787,
+                          49.5 24.7455 -3.55787,
+                          49.5 24.7455 3.55787,
+                          44.75 24.7455 3.55787,
+                          44.75 22.7408 10.3854,
+                          49.5 24.7455 -3.55787,
+                          44.75 24.7455 3.55787,
+                          49.5 24.7455 3.55787,
+                          49.5 22.7408 10.3854,
+                          44.75 22.7408 10.3854,
+                          44.75 18.8937 16.3715,
+                          49.5 24.7455 3.55787,
+                          44.75 22.7408 10.3854,
+                          49.5 22.7408 10.3854,
+                          49.5 18.8937 16.3715,
+                          44.75 18.8937 16.3715,
+                          44.75 13.516 21.0313,
+                          49.5 22.7408 10.3854,
+                          44.75 18.8937 16.3715,
+                          49.5 18.8937 16.3715,
+                          49.5 13.516 21.0313,
+                          44.75 13.516 21.0313,
+                          44.75 7.04331 23.9873,
+                          49.5 18.8937 16.3715,
+                          44.75 13.516 21.0313,
+                          49.5 13.516 21.0313,
+                          44.75 -5.47722e-16 5.5,
+                          44.75 -2.48961e-15 25,
+                          44.75 7.04331 23.9873,
+                          49.5 7.04331 23.9873,
+                          44.75 7.04331 23.9873,
+                          44.75 -2.48961e-15 25,
+                          44.75 2.75037 4.76275,
+                          44.75 -5.47722e-16 5.5,
+                          44.75 7.04331 23.9873,
+                          44.75 4.76275 2.75037,
+                          44.75 2.75037 4.76275,
+                          44.75 7.04331 23.9873,
+                          44.75 5.5 8.84472e-16,
+                          44.75 4.76275 2.75037,
+                          44.75 7.04331 23.9873,
+                          49.5 13.516 21.0313,
+                          44.75 7.04331 23.9873,
+                          49.5 7.04331 23.9873,
+                          44.75 -5.5 -2.10951e-16,
+                          44.75 -7.04331 23.9873,
+                          44.75 -2.48961e-15 25,
+                          49.5 -2.48961e-15 25,
+                          44.75 -2.48961e-15 25,
+                          44.75 -7.04331 23.9873,
+                          44.75 -4.76275 2.75037,
+                          44.75 -5.5 -2.10951e-16,
+                          44.75 -2.48961e-15 25,
+                          44.75 -2.75037 4.76275,
+                          44.75 -4.76275 2.75037,
+                          44.75 -2.48961e-15 25,
+                          44.75 -5.47722e-16 5.5,
+                          44.75 -2.75037 4.76275,
+                          44.75 -2.48961e-15 25,
+                          49.5 7.04331 23.9873,
+                          44.75 -2.48961e-15 25,
+                          49.5 -2.48961e-15 25,
+                          44.75 -13.516 -21.0313,
+                          44.75 -13.516 21.0313,
+                          44.75 -7.04331 23.9873,
+                          49.5 -7.04331 23.9873,
+                          44.75 -7.04331 23.9873,
+                          44.75 -13.516 21.0313,
+                          44.75 -7.04331 -23.9873,
+                          44.75 -13.516 -21.0313,
+                          44.75 -7.04331 23.9873,
+                          44.75 -5.5 -2.10951e-16,
+                          44.75 -7.04331 -23.9873,
+                          44.75 -7.04331 23.9873,
+                          49.5 -2.48961e-15 25,
+                          44.75 -7.04331 23.9873,
+                          49.5 -7.04331 23.9873,
+                          44.75 -18.8937 -16.3715,
+                          44.75 -18.8937 16.3715,
+                          44.75 -13.516 21.0313,
+                          49.5 -13.516 21.0313,
+                          44.75 -13.516 21.0313,
+                          44.75 -18.8937 16.3715,
+                          44.75 -13.516 -21.0313,
+                          44.75 -18.8937 -16.3715,
+                          44.75 -13.516 21.0313,
+                          49.5 -7.04331 23.9873,
+                          44.75 -13.516 21.0313,
+                          49.5 -13.516 21.0313,
+                          44.75 -22.7408 -10.3854,
+                          44.75 -22.7408 10.3854,
+                          44.75 -18.8937 16.3715,
+                          49.5 -18.8937 16.3715,
+                          44.75 -18.8937 16.3715,
+                          44.75 -22.7408 10.3854,
+                          44.75 -18.8937 -16.3715,
+                          44.75 -22.7408 -10.3854,
+                          44.75 -18.8937 16.3715,
+                          49.5 -13.516 21.0313,
+                          44.75 -18.8937 16.3715,
+                          49.5 -18.8937 16.3715,
+                          44.75 -24.7455 -3.55787,
+                          44.75 -24.7455 3.55787,
+                          44.75 -22.7408 10.3854,
+                          49.5 -22.7408 10.3854,
+                          44.75 -22.7408 10.3854,
+                          44.75 -24.7455 3.55787,
+                          44.75 -22.7408 -10.3854,
+                          44.75 -24.7455 -3.55787,
+                          44.75 -22.7408 10.3854,
+                          49.5 -18.8937 16.3715,
+                          44.75 -22.7408 10.3854,
+                          49.5 -22.7408 10.3854,
+                          49.5 -24.7455 3.55787,
+                          44.75 -24.7455 3.55787,
+                          44.75 -24.7455 -3.55787,
+                          49.5 -22.7408 10.3854,
+                          44.75 -24.7455 3.55787,
+                          49.5 -24.7455 3.55787,
+                          49.5 -24.7455 -3.55787,
+                          44.75 -24.7455 -3.55787,
+                          44.75 -22.7408 -10.3854,
+                          49.5 -24.7455 3.55787,
+                          44.75 -24.7455 -3.55787,
+                          49.5 -24.7455 -3.55787,
+                          49.5 -22.7408 -10.3854,
+                          44.75 -22.7408 -10.3854,
+                          44.75 -18.8937 -16.3715,
+                          49.5 -24.7455 -3.55787,
+                          44.75 -22.7408 -10.3854,
+                          49.5 -22.7408 -10.3854,
+                          49.5 -18.8937 -16.3715,
+                          44.75 -18.8937 -16.3715,
+                          44.75 -13.516 -21.0313,
+                          49.5 -22.7408 -10.3854,
+                          44.75 -18.8937 -16.3715,
+                          49.5 -18.8937 -16.3715,
+                          49.5 -13.516 -21.0313,
+                          44.75 -13.516 -21.0313,
+                          44.75 -7.04331 -23.9873,
+                          49.5 -18.8937 -16.3715,
+                          44.75 -13.516 -21.0313,
+                          49.5 -13.516 -21.0313,
+                          44.75 -2.75037 -4.76275,
+                          44.75 5.47702e-16 -5.5,
+                          44.75 -7.04331 -23.9873,
+                          44.75 -4.76275 -2.75037,
+                          44.75 -2.75037 -4.76275,
+                          44.75 -7.04331 -23.9873,
+                          44.75 -5.5 -2.10951e-16,
+                          44.75 -4.76275 -2.75037,
+                          44.75 -7.04331 -23.9873,
+                          49.5 -13.516 -21.0313,
+                          44.75 -7.04331 -23.9873,
+                          49.5 -7.04331 -23.9873,
+                          53.5 5.47702e-16 -5.5,
+                          44.75 5.47702e-16 -5.5,
+                          44.75 -2.75037 -4.76275,
+                          53.5 2.75037 -4.76275,
+                          44.75 2.75037 -4.76275,
+                          44.75 5.47702e-16 -5.5,
+                          53.5 2.75037 -4.76275,
+                          44.75 5.47702e-16 -5.5,
+                          53.5 5.47702e-16 -5.5,
+                          53.5 -2.75037 -4.76275,
+                          44.75 -2.75037 -4.76275,
+                          44.75 -4.76275 -2.75037,
+                          53.5 -2.75037 -4.76275,
+                          53.5 5.47702e-16 -5.5,
+                          44.75 -2.75037 -4.76275,
+                          53.5 -4.76275 -2.75037,
+                          44.75 -4.76275 -2.75037,
+                          44.75 -5.5 -2.10951e-16,
+                          53.5 -2.75037 -4.76275,
+                          44.75 -4.76275 -2.75037,
+                          53.5 -4.76275 -2.75037,
+                          53.5 -5.5 -2.10951e-16,
+                          44.75 -5.5 -2.10951e-16,
+                          44.75 -4.76275 2.75037,
+                          53.5 -4.76275 -2.75037,
+                          44.75 -5.5 -2.10951e-16,
+                          53.5 -5.5 -2.10951e-16,
+                          53.5 -4.76275 2.75037,
+                          44.75 -4.76275 2.75037,
+                          44.75 -2.75037 4.76275,
+                          53.5 -5.5 -2.10951e-16,
+                          44.75 -4.76275 2.75037,
+                          53.5 -4.76275 2.75037,
+                          53.5 -2.75037 4.76275,
+                          44.75 -2.75037 4.76275,
+                          44.75 -5.47722e-16 5.5,
+                          53.5 -4.76275 2.75037,
+                          44.75 -2.75037 4.76275,
+                          53.5 -2.75037 4.76275,
+                          53.5 -5.47722e-16 5.5,
+                          44.75 -5.47722e-16 5.5,
+                          44.75 2.75037 4.76275,
+                          53.5 -2.75037 4.76275,
+                          44.75 -5.47722e-16 5.5,
+                          53.5 -5.47722e-16 5.5,
+                          53.5 2.75037 4.76275,
+                          44.75 2.75037 4.76275,
+                          44.75 4.76275 2.75037,
+                          53.5 -5.47722e-16 5.5,
+                          44.75 2.75037 4.76275,
+                          53.5 2.75037 4.76275,
+                          53.5 4.76275 2.75037,
+                          44.75 4.76275 2.75037,
+                          44.75 5.5 8.84472e-16,
+                          53.5 2.75037 4.76275,
+                          44.75 4.76275 2.75037,
+                          53.5 4.76275 2.75037,
+                          53.5 5.5 8.84472e-16,
+                          44.75 5.5 8.84472e-16,
+                          44.75 4.76275 -2.75037,
+                          53.5 4.76275 2.75037,
+                          44.75 5.5 8.84472e-16,
+                          53.5 5.5 8.84472e-16,
+                          53.5 4.76275 -2.75037,
+                          44.75 4.76275 -2.75037,
+                          44.75 2.75037 -4.76275,
+                          53.5 5.5 8.84472e-16,
+                          44.75 4.76275 -2.75037,
+                          53.5 4.76275 -2.75037,
+                          53.5 4.76275 -2.75037,
+                          44.75 2.75037 -4.76275,
+                          53.5 2.75037 -4.76275,
+                          49.5 -5.47165 -15.0352,
+                          49.5 -7.04331 -23.9873,
+                          49.5 2.48959e-15 -25,
+                          49.5 1.59333e-15 -16,
+                          49.5 2.48959e-15 -25,
+                          49.5 7.04331 -23.9873,
+                          49.5 1.59333e-15 -16,
+                          49.5 -5.47165 -15.0352,
+                          49.5 2.48959e-15 -25,
+                          49.5 -10.285 -12.2562,
+                          49.5 -13.516 -21.0313,
+                          49.5 -7.04331 -23.9873,
+                          49.5 -5.47165 -15.0352,
+                          49.5 -10.285 -12.2562,
+                          49.5 -7.04331 -23.9873,
+                          49.5 -18.8937 16.3715,
+                          49.5 -18.8937 -16.3715,
+                          49.5 -13.516 -21.0313,
+                          49.5 -15.7567 -2.779,
+                          49.5 -18.8937 16.3715,
+                          49.5 -13.516 -21.0313,
+                          49.5 -13.8564 -8,
+                          49.5 -15.7567 -2.779,
+                          49.5 -13.516 -21.0313,
+                          49.5 -10.285 -12.2562,
+                          49.5 -13.8564 -8,
+                          49.5 -13.516 -21.0313,
+                          49.5 -22.7408 10.3854,
+                          49.5 -22.7408 -10.3854,
+                          49.5 -18.8937 -16.3715,
+                          49.5 -18.8937 16.3715,
+                          49.5 -22.7408 10.3854,
+                          49.5 -18.8937 -16.3715,
+                          49.5 -24.7455 3.55787,
+                          49.5 -24.7455 -3.55787,
+                          49.5 -22.7408 -10.3854,
+                          49.5 -22.7408 10.3854,
+                          49.5 -24.7455 3.55787,
+                          49.5 -22.7408 -10.3854,
+                          49.5 -13.8564 8,
+                          49.5 -13.516 21.0313,
+                          49.5 -18.8937 16.3715,
+                          49.5 -15.7567 2.779,
+                          49.5 -13.8564 8,
+                          49.5 -18.8937 16.3715,
+                          49.5 -15.7567 -2.779,
+                          49.5 -15.7567 2.779,
+                          49.5 -18.8937 16.3715,
+                          49.5 -10.285 12.2562,
+                          49.5 -7.04331 23.9873,
+                          49.5 -13.516 21.0313,
+                          49.5 -13.8564 8,
+                          49.5 -10.285 12.2562,
+                          49.5 -13.516 21.0313,
+                          49.5 -1.59335e-15 16,
+                          49.5 -2.48961e-15 25,
+                          49.5 -7.04331 23.9873,
+                          49.5 -5.47165 15.0352,
+                          49.5 -1.59335e-15 16,
+                          49.5 -7.04331 23.9873,
+                          49.5 -10.285 12.2562,
+                          49.5 -5.47165 15.0352,
+                          49.5 -7.04331 23.9873,
+                          49.5 5.47165 15.0352,
+                          49.5 7.04331 23.9873,
+                          49.5 -2.48961e-15 25,
+                          49.5 5.47165 15.0352,
+                          49.5 -2.48961e-15 25,
+                          49.5 -1.59335e-15 16,
+                          49.5 10.285 12.2562,
+                          49.5 13.516 21.0313,
+                          49.5 7.04331 23.9873,
+                          49.5 5.47165 15.0352,
+                          49.5 10.285 12.2562,
+                          49.5 7.04331 23.9873,
+                          49.5 18.8937 -16.3715,
+                          49.5 18.8937 16.3715,
+                          49.5 13.516 21.0313,
+                          49.5 15.7567 2.779,
+                          49.5 18.8937 -16.3715,
+                          49.5 13.516 21.0313,
+                          49.5 13.8564 8,
+                          49.5 15.7567 2.779,
+                          49.5 13.516 21.0313,
+                          49.5 10.285 12.2562,
+                          49.5 13.8564 8,
+                          49.5 13.516 21.0313,
+                          49.5 22.7408 -10.3854,
+                          49.5 22.7408 10.3854,
+                          49.5 18.8937 16.3715,
+                          49.5 18.8937 -16.3715,
+                          49.5 22.7408 -10.3854,
+                          49.5 18.8937 16.3715,
+                          49.5 24.7455 -3.55787,
+                          49.5 24.7455 3.55787,
+                          49.5 22.7408 10.3854,
+                          49.5 22.7408 -10.3854,
+                          49.5 24.7455 -3.55787,
+                          49.5 22.7408 10.3854,
+                          49.5 13.8564 -8,
+                          49.5 13.516 -21.0313,
+                          49.5 18.8937 -16.3715,
+                          49.5 15.7567 -2.779,
+                          49.5 13.8564 -8,
+                          49.5 18.8937 -16.3715,
+                          49.5 15.7567 2.779,
+                          49.5 15.7567 -2.779,
+                          49.5 18.8937 -16.3715,
+                          49.5 10.285 -12.2562,
+                          49.5 7.04331 -23.9873,
+                          49.5 13.516 -21.0313,
+                          49.5 13.8564 -8,
+                          49.5 10.285 -12.2562,
+                          49.5 13.516 -21.0313,
+                          49.5 5.47165 -15.0352,
+                          49.5 1.59333e-15 -16,
+                          49.5 7.04331 -23.9873,
+                          49.5 10.285 -12.2562,
+                          49.5 5.47165 -15.0352,
+                          49.5 7.04331 -23.9873,
+                          53.5 -1.59335e-15 16,
+                          49.5 -1.59335e-15 16,
+                          49.5 -5.47165 15.0352,
+                          53.5 5.47135 15.0353,
+                          49.5 5.47165 15.0352,
+                          49.5 -1.59335e-15 16,
+                          53.5 5.47135 15.0353,
+                          49.5 -1.59335e-15 16,
+                          53.5 -1.59335e-15 16,
+                          53.5 -5.47135 15.0353,
+                          49.5 -5.47165 15.0352,
+                          49.5 -10.285 12.2562,
+                          53.5 -5.47135 15.0353,
+                          53.5 -1.59335e-15 16,
+                          49.5 -5.47165 15.0352,
+                          53.5 -10.2842 12.2567,
+                          49.5 -10.285 12.2562,
+                          49.5 -13.8564 8,
+                          53.5 -5.47135 15.0353,
+                          49.5 -10.285 12.2562,
+                          53.5 -10.2842 12.2567,
+                          53.5 -13.8566 7.99925,
+                          49.5 -13.8564 8,
+                          49.5 -15.7567 2.779,
+                          53.5 -10.2842 12.2567,
+                          49.5 -13.8564 8,
+                          53.5 -13.8566 7.99925,
+                          53.5 -15.757 2.77758,
+                          49.5 -15.7567 2.779,
+                          49.5 -15.7567 -2.779,
+                          53.5 -13.8566 7.99925,
+                          49.5 -15.7567 2.779,
+                          53.5 -15.757 2.77758,
+                          53.5 -15.757 -2.77758,
+                          49.5 -15.7567 -2.779,
+                          49.5 -13.8564 -8,
+                          53.5 -15.757 2.77758,
+                          49.5 -15.7567 -2.779,
+                          53.5 -15.757 -2.77758,
+                          53.5 -13.8566 -7.99925,
+                          49.5 -13.8564 -8,
+                          49.5 -10.285 -12.2562,
+                          53.5 -15.757 -2.77758,
+                          49.5 -13.8564 -8,
+                          53.5 -13.8566 -7.99925,
+                          53.5 -10.2842 -12.2567,
+                          49.5 -10.285 -12.2562,
+                          49.5 -5.47165 -15.0352,
+                          53.5 -13.8566 -7.99925,
+                          49.5 -10.285 -12.2562,
+                          53.5 -10.2842 -12.2567,
+                          53.5 -5.47135 -15.0353,
+                          49.5 -5.47165 -15.0352,
+                          49.5 1.59333e-15 -16,
+                          53.5 -10.2842 -12.2567,
+                          49.5 -5.47165 -15.0352,
+                          53.5 -5.47135 -15.0353,
+                          53.5 1.59333e-15 -16,
+                          49.5 1.59333e-15 -16,
+                          49.5 5.47165 -15.0352,
+                          53.5 -5.47135 -15.0353,
+                          49.5 1.59333e-15 -16,
+                          53.5 1.59333e-15 -16,
+                          53.5 5.47135 -15.0353,
+                          49.5 5.47165 -15.0352,
+                          49.5 10.285 -12.2562,
+                          53.5 1.59333e-15 -16,
+                          49.5 5.47165 -15.0352,
+                          53.5 5.47135 -15.0353,
+                          53.5 10.2842 -12.2567,
+                          49.5 10.285 -12.2562,
+                          49.5 13.8564 -8,
+                          53.5 5.47135 -15.0353,
+                          49.5 10.285 -12.2562,
+                          53.5 10.2842 -12.2567,
+                          53.5 13.8566 -7.99925,
+                          49.5 13.8564 -8,
+                          49.5 15.7567 -2.779,
+                          53.5 10.2842 -12.2567,
+                          49.5 13.8564 -8,
+                          53.5 13.8566 -7.99925,
+                          53.5 15.757 -2.77758,
+                          49.5 15.7567 -2.779,
+                          49.5 15.7567 2.779,
+                          53.5 13.8566 -7.99925,
+                          49.5 15.7567 -2.779,
+                          53.5 15.757 -2.77758,
+                          53.5 15.757 2.77758,
+                          49.5 15.7567 2.779,
+                          49.5 13.8564 8,
+                          53.5 15.757 -2.77758,
+                          49.5 15.7567 2.779,
+                          53.5 15.757 2.77758,
+                          53.5 13.8566 7.99925,
+                          49.5 13.8564 8,
+                          49.5 10.285 12.2562,
+                          53.5 15.757 2.77758,
+                          49.5 13.8564 8,
+                          53.5 13.8566 7.99925,
+                          53.5 10.2842 12.2567,
+                          49.5 10.285 12.2562,
+                          49.5 5.47165 15.0352,
+                          53.5 13.8566 7.99925,
+                          49.5 10.285 12.2562,
+                          53.5 10.2842 12.2567,
+                          53.5 10.2842 12.2567,
+                          49.5 5.47165 15.0352,
+                          53.5 5.47135 15.0353,
+                          53.5 4.76275 2.75037,
+                          53.5 5.47135 15.0353,
+                          53.5 -1.59335e-15 16,
+                          53.5 -5.47722e-16 5.5,
+                          53.5 -1.59335e-15 16,
+                          53.5 -5.47135 15.0353,
+                          53.5 2.75037 4.76275,
+                          53.5 4.76275 2.75037,
+                          53.5 -1.59335e-15 16,
+                          53.5 -5.47722e-16 5.5,
+                          53.5 2.75037 4.76275,
+                          53.5 -1.59335e-15 16,
+                          53.5 10.2842 -12.2567,
+                          53.5 10.2842 12.2567,
+                          53.5 5.47135 15.0353,
+                          53.5 5.5 8.84472e-16,
+                          53.5 10.2842 -12.2567,
+                          53.5 5.47135 15.0353,
+                          53.5 4.76275 2.75037,
+                          53.5 5.5 8.84472e-16,
+                          53.5 5.47135 15.0353,
+                          53.5 13.8566 -7.99925,
+                          53.5 13.8566 7.99925,
+                          53.5 10.2842 12.2567,
+                          53.5 10.2842 -12.2567,
+                          53.5 13.8566 -7.99925,
+                          53.5 10.2842 12.2567,
+                          53.5 15.757 -2.77758,
+                          53.5 15.757 2.77758,
+                          53.5 13.8566 7.99925,
+                          53.5 13.8566 -7.99925,
+                          53.5 15.757 -2.77758,
+                          53.5 13.8566 7.99925,
+                          53.5 5.5 8.84472e-16,
+                          53.5 5.47135 -15.0353,
+                          53.5 10.2842 -12.2567,
+                          53.5 5.47702e-16 -5.5,
+                          53.5 1.59333e-15 -16,
+                          53.5 5.47135 -15.0353,
+                          53.5 2.75037 -4.76275,
+                          53.5 5.47702e-16 -5.5,
+                          53.5 5.47135 -15.0353,
+                          53.5 4.76275 -2.75037,
+                          53.5 2.75037 -4.76275,
+                          53.5 5.47135 -15.0353,
+                          53.5 5.5 8.84472e-16,
+                          53.5 4.76275 -2.75037,
+                          53.5 5.47135 -15.0353,
+                          53.5 -4.76275 -2.75037,
+                          53.5 -5.47135 -15.0353,
+                          53.5 1.59333e-15 -16,
+                          53.5 -2.75037 -4.76275,
+                          53.5 1.59333e-15 -16,
+                          53.5 5.47702e-16 -5.5,
+                          53.5 -2.75037 -4.76275,
+                          53.5 -4.76275 -2.75037,
+                          53.5 1.59333e-15 -16,
+                          53.5 -10.2842 12.2567,
+                          53.5 -10.2842 -12.2567,
+                          53.5 -5.47135 -15.0353,
+                          53.5 -5.5 -2.10951e-16,
+                          53.5 -10.2842 12.2567,
+                          53.5 -5.47135 -15.0353,
+                          53.5 -4.76275 -2.75037,
+                          53.5 -5.5 -2.10951e-16,
+                          53.5 -5.47135 -15.0353,
+                          53.5 -13.8566 7.99925,
+                          53.5 -13.8566 -7.99925,
+                          53.5 -10.2842 -12.2567,
+                          53.5 -10.2842 12.2567,
+                          53.5 -13.8566 7.99925,
+                          53.5 -10.2842 -12.2567,
+                          53.5 -15.757 2.77758,
+                          53.5 -15.757 -2.77758,
+                          53.5 -13.8566 -7.99925,
+                          53.5 -13.8566 7.99925,
+                          53.5 -15.757 2.77758,
+                          53.5 -13.8566 -7.99925,
+                          53.5 -5.5 -2.10951e-16,
+                          53.5 -5.47135 15.0353,
+                          53.5 -10.2842 12.2567,
+                          53.5 -2.75037 4.76275,
+                          53.5 -5.47722e-16 5.5,
+                          53.5 -5.47135 15.0353,
+                          53.5 -4.76275 2.75037,
+                          53.5 -2.75037 4.76275,
+                          53.5 -5.47135 15.0353,
+                          53.5 -5.5 -2.10951e-16,
+                          53.5 -4.76275 2.75037,
+                          53.5 -5.47135 15.0353 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.129032 0.99164,
+                          0 -0.129032 0.99164,
+                          0 -0.464951 0.885336,
+                          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,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.465129 0.885243,
+                          0 -0.464951 0.885336,
+                          0 -0.743285 0.668974,
+                          0 -0.129032 0.99164,
+                          0 -0.464951 0.885336,
+                          0 -0.465129 0.885243,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.743419 0.668826,
+                          0 -0.743285 0.668974,
+                          0 -0.929242 0.369471,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.465129 0.885243,
+                          0 -0.743285 0.668974,
+                          0 -0.743419 0.668826,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.929316 0.369285,
+                          0 -0.929242 0.369471,
+                          0 -0.999711 0.0240488,
+                          0 -0.743419 0.668826,
+                          0 -0.929242 0.369471,
+                          0 -0.929316 0.369285,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.999716 0.0238494,
+                          0 -0.999711 0.0240488,
+                          0 -0.945933 -0.324362,
+                          0 -0.929316 0.369285,
+                          0 -0.999711 0.0240488,
+                          0 -0.999716 0.0238494,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.945868 -0.324551,
+                          0 -0.945933 -0.324362,
+                          0 -0.774592 -0.632461,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.999716 0.0238494,
+                          0 -0.945933 -0.324362,
+                          0 -0.945868 -0.324551,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.774467 -0.632615,
+                          0 -0.774592 -0.632461,
+                          0 -0.506984 -0.861956,
+                          0 -0.945868 -0.324551,
+                          0 -0.774592 -0.632461,
+                          0 -0.774467 -0.632615,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.506812 -0.862056,
+                          0 -0.506984 -0.861956,
+                          0 -0.176366 -0.984325,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.774467 -0.632615,
+                          0 -0.506984 -0.861956,
+                          0 -0.506812 -0.862056,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.176171 -0.98436,
+                          0 -0.176366 -0.984325,
+                          0 0.176171 -0.98436,
+                          0 -0.506812 -0.862056,
+                          0 -0.176366 -0.984325,
+                          0 -0.176171 -0.98436,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.176366 -0.984325,
+                          0 0.176171 -0.98436,
+                          0 0.506812 -0.862056,
+                          0 -0.176171 -0.98436,
+                          0 0.176171 -0.98436,
+                          0 0.176366 -0.984325,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.506984 -0.861956,
+                          0 0.506812 -0.862056,
+                          0 0.774467 -0.632615,
+                          0 0.176366 -0.984325,
+                          0 0.506812 -0.862056,
+                          0 0.506984 -0.861956,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.774592 -0.632461,
+                          0 0.774467 -0.632615,
+                          0 0.945868 -0.324551,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.506984 -0.861956,
+                          0 0.774467 -0.632615,
+                          0 0.774592 -0.632461,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.945933 -0.324362,
+                          0 0.945868 -0.324551,
+                          0 0.999716 0.0238494,
+                          0 0.774592 -0.632461,
+                          0 0.945868 -0.324551,
+                          0 0.945933 -0.324362,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.999711 0.0240488,
+                          0 0.999716 0.0238494,
+                          0 0.929316 0.369285,
+                          0 0.945933 -0.324362,
+                          0 0.999716 0.0238494,
+                          0 0.999711 0.0240488,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.929242 0.369471,
+                          0 0.929316 0.369285,
+                          0 0.743419 0.668826,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.999711 0.0240488,
+                          0 0.929316 0.369285,
+                          0 0.929242 0.369471,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.743285 0.668974,
+                          0 0.743419 0.668826,
+                          0 0.465129 0.885243,
+                          0 0.929242 0.369471,
+                          0 0.743419 0.668826,
+                          0 0.743285 0.668974,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.464951 0.885336,
+                          0 0.465129 0.885243,
+                          0 0.129032 0.99164,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.743285 0.668974,
+                          0 0.465129 0.885243,
+                          0 0.464951 0.885336,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 0.464951 0.885336,
+                          0 0.129032 0.99164,
+                          0 0.129032 0.99164,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.707107 -0.707107,
+                          0 -0.707107 -0.707107,
+                          0 -0.707107 -0.707107,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.707107 -0.707107,
+                          0 -0.707107 -0.707107,
+                          0 -0.707107 -0.707107,
+                          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 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.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 -0.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.707107 0.707107,
+                          0 0.707107 0.707107,
+                          0 0.707107 0.707107,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.707107 0.707107,
+                          0 0.707107 0.707107,
+                          0 0.707107 0.707107,
+                          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 -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.707107 -0.707107,
+                          0 0.707107 -0.707107,
+                          0 0.707107 -0.707107,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0.707107 -0.707107,
+                          0 0.707107 -0.707107,
+                          0 0.707107 -0.707107,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -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 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -1 0 0,
+                          -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 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 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,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          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 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -59.5 9 -21,
+                          -59.5 7.20674 -13.7227,
+                          -59.5 2 -15.3704,
+                          -64.5 2 -15.3704,
+                          -59.5 2 -15.3704,
+                          -59.5 7.20674 -13.7227,
+                          -59.5 2 -21,
+                          -59.5 9 -21,
+                          -59.5 2 -15.3704,
+                          -64.5 2 -21,
+                          -59.5 2 -21,
+                          -59.5 2 -15.3704,
+                          -64.5 2 -21,
+                          -59.5 2 -15.3704,
+                          -64.5 2 -15.3704,
+                          -59.5 9 -21,
+                          -59.5 11.5209 -10.3691,
+                          -59.5 7.20674 -13.7227,
+                          -64.5 7.2095 -13.7213,
+                          -59.5 7.20674 -13.7227,
+                          -59.5 11.5209 -10.3691,
+                          -64.5 2 -15.3704,
+                          -59.5 7.20674 -13.7227,
+                          -64.5 7.2095 -13.7213,
+                          -59.5 25 -5,
+                          -59.5 14.4033 -5.7268,
+                          -59.5 11.5209 -10.3691,
+                          -64.5 11.523 -10.3668,
+                          -59.5 11.5209 -10.3691,
+                          -59.5 14.4033 -5.7268,
+                          -59.5 9 -21,
+                          -59.5 25 -5,
+                          -59.5 11.5209 -10.3691,
+                          -64.5 7.2095 -13.7213,
+                          -59.5 11.5209 -10.3691,
+                          -64.5 11.523 -10.3668,
+                          -59.5 25 -5,
+                          -59.5 15.4955 -0.372756,
+                          -59.5 14.4033 -5.7268,
+                          -64.5 14.4044 -5.72392,
+                          -59.5 14.4033 -5.7268,
+                          -59.5 15.4955 -0.372756,
+                          -64.5 11.523 -10.3668,
+                          -59.5 14.4033 -5.7268,
+                          -64.5 14.4044 -5.72392,
+                          -59.5 25 -5,
+                          -59.5 14.662 5.02762,
+                          -59.5 15.4955 -0.372756,
+                          -64.5 15.4956 -0.369665,
+                          -59.5 15.4955 -0.372756,
+                          -59.5 14.662 5.02762,
+                          -64.5 14.4044 -5.72392,
+                          -59.5 15.4955 -0.372756,
+                          -64.5 15.4956 -0.369665,
+                          -59.5 9 21,
+                          -59.5 12.0062 9.80314,
+                          -59.5 14.662 5.02762,
+                          -64.5 14.661 5.03053,
+                          -59.5 14.662 5.02762,
+                          -59.5 12.0062 9.80314,
+                          -59.5 25 -5,
+                          -59.5 9 21,
+                          -59.5 14.662 5.02762,
+                          -64.5 15.4956 -0.369665,
+                          -59.5 14.662 5.02762,
+                          -64.5 14.661 5.03053,
+                          -59.5 9 21,
+                          -59.5 7.85825 13.3603,
+                          -59.5 12.0062 9.80314,
+                          -64.5 12.0042 9.80553,
+                          -59.5 12.0062 9.80314,
+                          -59.5 7.85825 13.3603,
+                          -64.5 14.661 5.03053,
+                          -59.5 12.0062 9.80314,
+                          -64.5 12.0042 9.80553,
+                          -59.5 -9 21,
+                          -59.5 2.73368 15.257,
+                          -59.5 7.85825 13.3603,
+                          -64.5 7.85559 13.3619,
+                          -59.5 7.85825 13.3603,
+                          -59.5 2.73368 15.257,
+                          -59.5 9 21,
+                          -59.5 -9 21,
+                          -59.5 7.85825 13.3603,
+                          -64.5 12.0042 9.80553,
+                          -59.5 7.85825 13.3603,
+                          -64.5 7.85559 13.3619,
+                          -59.5 -9 21,
+                          -59.5 -2.73064 15.2576,
+                          -59.5 2.73368 15.257,
+                          -64.5 2.73064 15.2576,
+                          -59.5 2.73368 15.257,
+                          -59.5 -2.73064 15.2576,
+                          -64.5 7.85559 13.3619,
+                          -59.5 2.73368 15.257,
+                          -64.5 2.73064 15.2576,
+                          -59.5 -9 21,
+                          -59.5 -7.85559 13.3619,
+                          -59.5 -2.73064 15.2576,
+                          -64.5 -2.73368 15.257,
+                          -59.5 -2.73064 15.2576,
+                          -59.5 -7.85559 13.3619,
+                          -64.5 2.73064 15.2576,
+                          -59.5 -2.73064 15.2576,
+                          -64.5 -2.73368 15.257,
+                          -59.5 -9 21,
+                          -59.5 -12.0042 9.80553,
+                          -59.5 -7.85559 13.3619,
+                          -64.5 -7.85825 13.3603,
+                          -59.5 -7.85559 13.3619,
+                          -59.5 -12.0042 9.80553,
+                          -64.5 -2.73368 15.257,
+                          -59.5 -7.85559 13.3619,
+                          -64.5 -7.85825 13.3603,
+                          -59.5 -25 5,
+                          -59.5 -14.661 5.03053,
+                          -59.5 -12.0042 9.80553,
+                          -64.5 -12.0062 9.80314,
+                          -59.5 -12.0042 9.80553,
+                          -59.5 -14.661 5.03053,
+                          -59.5 -9 21,
+                          -59.5 -25 5,
+                          -59.5 -12.0042 9.80553,
+                          -64.5 -7.85825 13.3603,
+                          -59.5 -12.0042 9.80553,
+                          -64.5 -12.0062 9.80314,
+                          -59.5 -25 5,
+                          -59.5 -15.4956 -0.369665,
+                          -59.5 -14.661 5.03053,
+                          -64.5 -14.662 5.02762,
+                          -59.5 -14.661 5.03053,
+                          -59.5 -15.4956 -0.369665,
+                          -64.5 -12.0062 9.80314,
+                          -59.5 -14.661 5.03053,
+                          -64.5 -14.662 5.02762,
+                          -59.5 -25 5,
+                          -59.5 -14.4044 -5.72392,
+                          -59.5 -15.4956 -0.369665,
+                          -64.5 -15.4955 -0.372756,
+                          -59.5 -15.4956 -0.369665,
+                          -59.5 -14.4044 -5.72392,
+                          -64.5 -14.662 5.02762,
+                          -59.5 -15.4956 -0.369665,
+                          -64.5 -15.4955 -0.372756,
+                          -59.5 -9 -21,
+                          -59.5 -11.523 -10.3668,
+                          -59.5 -14.4044 -5.72392,
+                          -64.5 -14.4033 -5.7268,
+                          -59.5 -14.4044 -5.72392,
+                          -59.5 -11.523 -10.3668,
+                          -59.5 -25 5,
+                          -59.5 -9 -21,
+                          -59.5 -14.4044 -5.72392,
+                          -64.5 -15.4955 -0.372756,
+                          -59.5 -14.4044 -5.72392,
+                          -64.5 -14.4033 -5.7268,
+                          -59.5 -9 -21,
+                          -59.5 -7.2095 -13.7213,
+                          -59.5 -11.523 -10.3668,
+                          -64.5 -11.5209 -10.3691,
+                          -59.5 -11.523 -10.3668,
+                          -59.5 -7.2095 -13.7213,
+                          -64.5 -14.4033 -5.7268,
+                          -59.5 -11.523 -10.3668,
+                          -64.5 -11.5209 -10.3691,
+                          -59.5 -2 -21,
+                          -59.5 -2 -15.3704,
+                          -59.5 -7.2095 -13.7213,
+                          -64.5 -7.20674 -13.7227,
+                          -59.5 -7.2095 -13.7213,
+                          -59.5 -2 -15.3704,
+                          -59.5 -9 -21,
+                          -59.5 -2 -21,
+                          -59.5 -7.2095 -13.7213,
+                          -64.5 -11.5209 -10.3691,
+                          -59.5 -7.2095 -13.7213,
+                          -64.5 -7.20674 -13.7227,
+                          -64.5 -2 -15.3704,
+                          -59.5 -2 -15.3704,
+                          -59.5 -2 -21,
+                          -64.5 -7.20674 -13.7227,
+                          -59.5 -2 -15.3704,
+                          -64.5 -2 -15.3704,
+                          -64.5 -2 -21,
+                          -59.5 -2 -21,
+                          -59.5 -9 -21,
+                          -64.5 -2 -15.3704,
+                          -59.5 -2 -21,
+                          -64.5 -2 -21,
+                          -59.5 -25 5,
+                          -59.5 -25 -5,
+                          -59.5 -9 -21,
+                          -64.5 -9 -21,
+                          -59.5 -9 -21,
+                          -59.5 -25 -5,
+                          -64.5 -2 -21,
+                          -59.5 -9 -21,
+                          -64.5 -9 -21,
+                          -59.5 -45 5,
+                          -59.5 -45 -5,
+                          -59.5 -25 -5,
+                          -64.5 -25 -5,
+                          -59.5 -25 -5,
+                          -59.5 -45 -5,
+                          -59.5 -25 5,
+                          -59.5 -45 5,
+                          -59.5 -25 -5,
+                          -64.5 -25 -5,
+                          -64.5 -9 -21,
+                          -59.5 -25 -5,
+                          -45.5 -45 5,
+                          -59.5 -45 -5,
+                          -59.5 -45 5,
+                          -64.5 -25 -5,
+                          -59.5 -45 -5,
+                          -64.5 -50 -5,
+                          -48.5 -50 -5,
+                          -64.5 -50 -5,
+                          -59.5 -45 -5,
+                          -45.5 -45 -5,
+                          -59.5 -45 -5,
+                          -45.5 -45 5,
+                          -48.5 -50 -5,
+                          -59.5 -45 -5,
+                          -45.5 -45 -5,
+                          -64.5 -50 5,
+                          -59.5 -45 5,
+                          -59.5 -25 5,
+                          -45.5 -45 5,
+                          -59.5 -45 5,
+                          -64.5 -50 5,
+                          -64.5 -25 5,
+                          -59.5 -25 5,
+                          -59.5 -9 21,
+                          -64.5 -50 5,
+                          -59.5 -25 5,
+                          -64.5 -25 5,
+                          -64.5 -9 21,
+                          -59.5 -9 21,
+                          -59.5 9 21,
+                          -64.5 -25 5,
+                          -59.5 -9 21,
+                          -64.5 -9 21,
+                          -59.5 25 -5,
+                          -59.5 25 5,
+                          -59.5 9 21,
+                          -64.5 9 21,
+                          -59.5 9 21,
+                          -59.5 25 5,
+                          -64.5 -9 21,
+                          -59.5 9 21,
+                          -64.5 9 21,
+                          -59.5 45 -5,
+                          -59.5 45 5,
+                          -59.5 25 5,
+                          -64.5 25 5,
+                          -59.5 25 5,
+                          -59.5 45 5,
+                          -59.5 25 -5,
+                          -59.5 45 -5,
+                          -59.5 25 5,
+                          -64.5 9 21,
+                          -59.5 25 5,
+                          -64.5 25 5,
+                          -45.5 45 -5,
+                          -59.5 45 5,
+                          -59.5 45 -5,
+                          -64.5 25 5,
+                          -59.5 45 5,
+                          -64.5 50 5,
+                          -48.5 50 5,
+                          -64.5 50 5,
+                          -59.5 45 5,
+                          -45.5 45 5,
+                          -48.5 50 5,
+                          -59.5 45 5,
+                          -45.5 45 -5,
+                          -45.5 45 5,
+                          -59.5 45 5,
+                          -64.5 50 -5,
+                          -59.5 45 -5,
+                          -59.5 25 -5,
+                          -45.5 45 -5,
+                          -59.5 45 -5,
+                          -64.5 50 -5,
+                          -64.5 25 -5,
+                          -59.5 25 -5,
+                          -59.5 9 -21,
+                          -64.5 50 -5,
+                          -59.5 25 -5,
+                          -64.5 25 -5,
+                          -64.5 9 -21,
+                          -59.5 9 -21,
+                          -59.5 2 -21,
+                          -64.5 25 -5,
+                          -59.5 9 -21,
+                          -64.5 9 -21,
+                          -64.5 9 -21,
+                          -59.5 2 -21,
+                          -64.5 2 -21,
+                          -64.5 -2 -15.3704,
+                          -64.5 -2 -21,
+                          -64.5 -9 -21,
+                          -64.5 -7.20674 -13.7227,
+                          -64.5 -2 -15.3704,
+                          -64.5 -9 -21,
+                          -64.5 -11.5209 -10.3691,
+                          -64.5 -7.20674 -13.7227,
+                          -64.5 -9 -21,
+                          -64.5 -25 -5,
+                          -64.5 -11.5209 -10.3691,
+                          -64.5 -9 -21,
+                          -64.5 -25 -5,
+                          -64.5 -14.4033 -5.7268,
+                          -64.5 -11.5209 -10.3691,
+                          -64.5 -25 -5,
+                          -64.5 -15.4955 -0.372756,
+                          -64.5 -14.4033 -5.7268,
+                          -64.5 -25 -5,
+                          -64.5 -14.662 5.02762,
+                          -64.5 -15.4955 -0.372756,
+                          -64.5 -9 21,
+                          -64.5 -12.0062 9.80314,
+                          -64.5 -14.662 5.02762,
+                          -64.5 -25 -5,
+                          -64.5 -9 21,
+                          -64.5 -14.662 5.02762,
+                          -64.5 -9 21,
+                          -64.5 -7.85825 13.3603,
+                          -64.5 -12.0062 9.80314,
+                          -64.5 9 21,
+                          -64.5 -2.73368 15.257,
+                          -64.5 -7.85825 13.3603,
+                          -64.5 -9 21,
+                          -64.5 9 21,
+                          -64.5 -7.85825 13.3603,
+                          -64.5 9 21,
+                          -64.5 2.73064 15.2576,
+                          -64.5 -2.73368 15.257,
+                          -64.5 9 21,
+                          -64.5 7.85559 13.3619,
+                          -64.5 2.73064 15.2576,
+                          -64.5 9 21,
+                          -64.5 12.0042 9.80553,
+                          -64.5 7.85559 13.3619,
+                          -64.5 25 5,
+                          -64.5 14.661 5.03053,
+                          -64.5 12.0042 9.80553,
+                          -64.5 9 21,
+                          -64.5 25 5,
+                          -64.5 12.0042 9.80553,
+                          -64.5 25 5,
+                          -64.5 15.4956 -0.369665,
+                          -64.5 14.661 5.03053,
+                          -64.5 25 5,
+                          -64.5 14.4044 -5.72392,
+                          -64.5 15.4956 -0.369665,
+                          -64.5 9 -21,
+                          -64.5 11.523 -10.3668,
+                          -64.5 14.4044 -5.72392,
+                          -64.5 25 5,
+                          -64.5 9 -21,
+                          -64.5 14.4044 -5.72392,
+                          -64.5 9 -21,
+                          -64.5 7.2095 -13.7213,
+                          -64.5 11.523 -10.3668,
+                          -64.5 2 -21,
+                          -64.5 2 -15.3704,
+                          -64.5 7.2095 -13.7213,
+                          -64.5 9 -21,
+                          -64.5 2 -21,
+                          -64.5 7.2095 -13.7213,
+                          -64.5 25 5,
+                          -64.5 25 -5,
+                          -64.5 9 -21,
+                          -64.5 50 5,
+                          -64.5 50 -5,
+                          -64.5 25 -5,
+                          -64.5 25 5,
+                          -64.5 50 5,
+                          -64.5 25 -5,
+                          -48.5 50 5,
+                          -64.5 50 -5,
+                          -64.5 50 5,
+                          -48.5 50 5,
+                          -48.5 50 -5,
+                          -64.5 50 -5,
+                          -45.5 45 -5,
+                          -64.5 50 -5,
+                          -48.5 50 -5,
+                          -64.5 -25 -5,
+                          -64.5 -25 5,
+                          -64.5 -9 21,
+                          -64.5 -50 -5,
+                          -64.5 -50 5,
+                          -64.5 -25 5,
+                          -64.5 -25 -5,
+                          -64.5 -50 -5,
+                          -64.5 -25 5,
+                          -48.5 -50 -5,
+                          -64.5 -50 5,
+                          -64.5 -50 -5,
+                          -48.5 -50 5,
+                          -45.5 -45 5,
+                          -64.5 -50 5,
+                          -48.5 -50 5,
+                          -64.5 -50 5,
+                          -48.5 -50 -5,
+                          -48.5 56 5,
+                          -48.5 50 -5,
+                          -48.5 50 5,
+                          -48.5 56 -5,
+                          -45.5 45 -5,
+                          -48.5 50 -5,
+                          -48.5 56 -5,
+                          -48.5 50 -5,
+                          -48.5 56 5,
+                          -45.5 56 5,
+                          -48.5 50 5,
+                          -45.5 45 5,
+                          -48.5 56 5,
+                          -48.5 50 5,
+                          -45.5 56 5,
+                          -45.5 56 -5,
+                          -45.5 45 5,
+                          -45.5 45 -5,
+                          -45.5 56 5,
+                          -45.5 45 5,
+                          -45.5 56 -5,
+                          -48.5 56 -5,
+                          -45.5 56 -5,
+                          -45.5 45 -5,
+                          -48.5 56 5,
+                          -45.5 56 5,
+                          -45.5 56 -5,
+                          -48.5 56 -5,
+                          -48.5 56 5,
+                          -45.5 56 -5,
+                          -45.5 -45 -5,
+                          -45.5 -45 5,
+                          -45.5 -56 5,
+                          -48.5 -56 5,
+                          -45.5 -56 5,
+                          -45.5 -45 5,
+                          -45.5 -56 -5,
+                          -45.5 -45 -5,
+                          -45.5 -56 5,
+                          -48.5 -56 -5,
+                          -45.5 -56 -5,
+                          -45.5 -56 5,
+                          -48.5 -56 -5,
+                          -45.5 -56 5,
+                          -48.5 -56 5,
+                          -48.5 -50 5,
+                          -48.5 -56 5,
+                          -45.5 -45 5,
+                          -48.5 -50 -5,
+                          -45.5 -45 -5,
+                          -45.5 -56 -5,
+                          -48.5 -50 -5,
+                          -45.5 -56 -5,
+                          -48.5 -56 -5,
+                          -48.5 -50 5,
+                          -48.5 -56 -5,
+                          -48.5 -56 5,
+                          -48.5 -50 5,
+                          -48.5 -50 -5,
+                          -48.5 -56 -5 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 1 -2.44921e-16,
+                          0 1 -2.44921e-16,
+                          0 0.939693 -0.34202,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.939693 0.34202,
+                          0 0.939693 0.34202,
+                          0 1 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.939693 0.34202,
+                          0 1 0,
+                          0 1 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.939693 -0.34202,
+                          0 0.939693 -0.34202,
+                          0 0.766044 -0.642788,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.939693 -0.34202,
+                          0 1 -2.44921e-16,
+                          0 0.939693 -0.34202,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.766044 -0.642788,
+                          0 0.766044 -0.642788,
+                          0 0.5 -0.866025,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.939693 -0.34202,
+                          0 0.766044 -0.642788,
+                          0 0.766044 -0.642788,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 0.173648 -0.984808,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.766044 -0.642788,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 0.173648 -0.984808,
+                          0 0.173648 -0.984808,
+                          0 -0.173648 -0.984808,
+                          0 0.5 -0.866025,
+                          0 0.173648 -0.984808,
+                          0 0.173648 -0.984808,
+                          0 -0.173648 -0.984808,
+                          0 -0.173648 -0.984808,
+                          0 -0.5 -0.866025,
+                          0 0.173648 -0.984808,
+                          0 -0.173648 -0.984808,
+                          0 -0.173648 -0.984808,
+                          0 -0.5 -0.866025,
+                          0 -0.5 -0.866025,
+                          0 -0.766044 -0.642788,
+                          0 -0.173648 -0.984808,
+                          0 -0.5 -0.866025,
+                          0 -0.5 -0.866025,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.766044 -0.642788,
+                          0 -0.766044 -0.642788,
+                          0 -0.939693 -0.34202,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.5 -0.866025,
+                          0 -0.766044 -0.642788,
+                          0 -0.766044 -0.642788,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.939693 -0.34202,
+                          0 -0.939693 -0.34202,
+                          0 -1 1.22461e-16,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.766044 -0.642788,
+                          0 -0.939693 -0.34202,
+                          0 -0.939693 -0.34202,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -1 1.22461e-16,
+                          0 -1 1.22461e-16,
+                          0 -0.939693 0.34202,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.939693 -0.34202,
+                          0 -1 1.22461e-16,
+                          0 -1 1.22461e-16,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.939693 0.34202,
+                          0 -0.939693 0.34202,
+                          0 -0.766044 0.642788,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.939693 0.34202,
+                          0 -1 1.22461e-16,
+                          0 -0.939693 0.34202,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.766044 0.642788,
+                          0 -0.766044 0.642788,
+                          0 -0.5 0.866025,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.766044 0.642788,
+                          0 -0.939693 0.34202,
+                          0 -0.766044 0.642788,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.5 0.866025,
+                          0 -0.5 0.866025,
+                          0 -0.173648 0.984808,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.5 0.866025,
+                          0 -0.766044 0.642788,
+                          0 -0.5 0.866025,
+                          0 -0.173648 0.984808,
+                          0 -0.173648 0.984808,
+                          0 0.173648 0.984808,
+                          0 -0.173648 0.984808,
+                          0 -0.5 0.866025,
+                          0 -0.173648 0.984808,
+                          0 0.173648 0.984808,
+                          0 0.173648 0.984808,
+                          0 0.5 0.866025,
+                          0 0.173648 0.984808,
+                          0 -0.173648 0.984808,
+                          0 0.173648 0.984808,
+                          0 0.5 0.866025,
+                          0 0.5 0.866025,
+                          0 0.766044 0.642788,
+                          0 0.5 0.866025,
+                          0 0.173648 0.984808,
+                          0 0.5 0.866025,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.766044 0.642788,
+                          0 0.766044 0.642788,
+                          0 0.939693 0.34202,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.766044 0.642788,
+                          0 0.5 0.866025,
+                          0 0.766044 0.642788,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.939693 0.34202,
+                          0 0.766044 0.642788,
+                          0 0.939693 0.34202,
+                          0 0 1,
+                          0 0 1,
+                          0 -0.433884 0.900969,
+                          0 0.433884 0.900969,
+                          0 0.433884 0.900969,
+                          0 2.44921e-16 1,
+                          0 0.433884 0.900969,
+                          0 2.44921e-16 1,
+                          0 2.44921e-16 1,
+                          0 -0.433884 0.900969,
+                          0 -0.433884 0.900969,
+                          0 -0.781832 0.62349,
+                          0 -0.433884 0.900969,
+                          0 0 1,
+                          0 -0.433884 0.900969,
+                          0 -0.781832 0.62349,
+                          0 -0.781832 0.62349,
+                          0 -0.974928 0.222521,
+                          0 -0.433884 0.900969,
+                          0 -0.781832 0.62349,
+                          0 -0.781832 0.62349,
+                          0 -0.974928 0.222521,
+                          0 -0.974928 0.222521,
+                          0 -0.974928 -0.222521,
+                          0 -0.781832 0.62349,
+                          0 -0.974928 0.222521,
+                          0 -0.974928 0.222521,
+                          0 -0.974928 -0.222521,
+                          0 -0.974928 -0.222521,
+                          0 -0.781832 -0.62349,
+                          0 -0.974928 0.222521,
+                          0 -0.974928 -0.222521,
+                          0 -0.974928 -0.222521,
+                          0 -0.781832 -0.62349,
+                          0 -0.781832 -0.62349,
+                          0 -0.433884 -0.900969,
+                          0 -0.974928 -0.222521,
+                          0 -0.781832 -0.62349,
+                          0 -0.781832 -0.62349,
+                          0 -0.433884 -0.900969,
+                          0 -0.433884 -0.900969,
+                          0 -1.22461e-16 -1,
+                          0 -0.781832 -0.62349,
+                          0 -0.433884 -0.900969,
+                          0 -0.433884 -0.900969,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0 0.433884 -0.900969,
+                          0 -0.433884 -0.900969,
+                          0 -1.22461e-16 -1,
+                          0 -1.22461e-16 -1,
+                          0 0.433884 -0.900969,
+                          0 0.433884 -0.900969,
+                          0 0.781832 -0.62349,
+                          0 -1.22461e-16 -1,
+                          0 0.433884 -0.900969,
+                          0 0.433884 -0.900969,
+                          0 0.781832 -0.62349,
+                          0 0.781832 -0.62349,
+                          0 0.974928 -0.222521,
+                          0 0.433884 -0.900969,
+                          0 0.781832 -0.62349,
+                          0 0.781832 -0.62349,
+                          0 0.974928 -0.222521,
+                          0 0.974928 -0.222521,
+                          0 0.974928 0.222521,
+                          0 0.781832 -0.62349,
+                          0 0.974928 -0.222521,
+                          0 0.974928 -0.222521,
+                          0 0.974928 0.222521,
+                          0 0.974928 0.222521,
+                          0 0.781832 0.62349,
+                          0 0.974928 -0.222521,
+                          0 0.974928 0.222521,
+                          0 0.974928 0.222521,
+                          0 0.781832 0.62349,
+                          0 0.781832 0.62349,
+                          0 0.433884 0.900969,
+                          0 0.974928 0.222521,
+                          0 0.781832 0.62349,
+                          0 0.781832 0.62349,
+                          0 0.781832 0.62349,
+                          0 0.433884 0.900969,
+                          0 0.433884 0.900969,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.866082 -0.499901,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -0.809017 0.587785,
+                          0 -1 2.44921e-16,
+                          0 -1 2.44921e-16,
+                          0 -0.809017 -0.587785,
+                          0 -1 0,
+                          0 -0.866082 -0.499901,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -0.951057 -0.309017,
+                          0 -0.866082 -0.499901,
+                          0 -1 2.44921e-16,
+                          0 -0.951057 0.309017,
+                          0 -0.951057 -0.309017,
+                          0 -1 2.44921e-16,
+                          0 -0.809017 0.587785,
+                          0 -0.951057 0.309017,
+                          0 -1 2.44921e-16,
+                          0 -0.587785 -0.809017,
+                          0 -0.500122 -0.865955,
+                          0 -0.866082 -0.499901,
+                          0 -0.809017 -0.587785,
+                          0 -0.866082 -0.499901,
+                          0 -0.500122 -0.865955,
+                          0 -0.951057 -0.309017,
+                          0 -0.587785 -0.809017,
+                          0 -0.866082 -0.499901,
+                          0 -3.06152e-16 -1,
+                          0 -3.06152e-16 -1,
+                          0 -0.500122 -0.865955,
+                          0 -0.309017 -0.951057,
+                          0 -0.500122 -0.865955,
+                          0 -6.12303e-17 -1,
+                          0 -0.587785 -0.809017,
+                          0 -3.06152e-16 -1,
+                          0 -0.500122 -0.865955,
+                          0 -0.809017 -0.587785,
+                          0 -0.500122 -0.865955,
+                          0 -0.309017 -0.951057,
+                          0 0.587785 -0.809017,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0 0.309017 -0.951057,
+                          0 -6.12303e-17 -1,
+                          0 0.587785 -0.809017,
+                          0 -0.309017 -0.951057,
+                          0 -6.12303e-17 -1,
+                          0 0.309017 -0.951057,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.809017 0.587785,
+                          0 -0.587785 0.809017,
+                          0 -0.951057 0.309017,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 1.83691e-16 1,
+                          0 1.83691e-16 1,
+                          0 -0.587785 0.809017,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.309017 0.951057,
+                          0 1.83691e-16 1,
+                          0 -0.587785 0.809017,
+                          0 -0.809017 0.587785,
+                          0 -0.309017 0.951057,
+                          0 -0.587785 0.809017,
+                          0 0.500122 0.865955,
+                          0 1.83691e-16 1,
+                          0 1.83691e-16 1,
+                          0 0.587785 0.809017,
+                          0 1.83691e-16 1,
+                          0 0.500122 0.865955,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.309017 0.951057,
+                          0 0.500122 0.865955,
+                          0 1.83691e-16 1,
+                          0 -0.309017 0.951057,
+                          0 0.309017 0.951057,
+                          0 1.83691e-16 1,
+                          0 0.809017 0.587785,
+                          0 0.866082 0.499901,
+                          0 0.500122 0.865955,
+                          0 0.587785 0.809017,
+                          0 0.500122 0.865955,
+                          0 0.866082 0.499901,
+                          0 0.309017 0.951057,
+                          0 0.809017 0.587785,
+                          0 0.500122 0.865955,
+                          0 1 -1.22461e-16,
+                          0 1 -1.22461e-16,
+                          0 0.866082 0.499901,
+                          0 0.951057 0.309017,
+                          0 0.866082 0.499901,
+                          0 1 -1.22461e-16,
+                          0 0.809017 0.587785,
+                          0 1 -1.22461e-16,
+                          0 0.866082 0.499901,
+                          0 0.587785 0.809017,
+                          0 0.866082 0.499901,
+                          0 0.951057 0.309017,
+                          0 0.809017 -0.587785,
+                          0 1 -1.22461e-16,
+                          0 1 -1.22461e-16,
+                          0 0.951057 0.309017,
+                          0 1 -1.22461e-16,
+                          0 0.951057 -0.309017,
+                          0 0.809017 -0.587785,
+                          0 0.951057 -0.309017,
+                          0 1 -1.22461e-16,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.809017 -0.587785,
+                          0 0.587785 -0.809017,
+                          0 0.951057 -0.309017,
+                          0 0.309017 -0.951057,
+                          0 0.587785 -0.809017,
+                          0 0.809017 -0.587785,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -54 8.77428 -2.00246,
+                          -54 14.5652 -5.30107,
+                          -54 15.5 -1.89814e-15,
+                          -67 15.5 -1.89814e-15,
+                          -54 15.5 -1.89814e-15,
+                          -54 14.5652 -5.30107,
+                          -54 8.77428 2.00246,
+                          -54 15.5 -1.89814e-15,
+                          -54 14.5652 5.30107,
+                          -67 14.5652 5.30107,
+                          -54 14.5652 5.30107,
+                          -54 15.5 -1.89814e-15,
+                          -54 8.77428 2.00246,
+                          -54 8.77428 -2.00246,
+                          -54 15.5 -1.89814e-15,
+                          -67 14.5652 5.30107,
+                          -54 15.5 -1.89814e-15,
+                          -67 15.5 -1.89814e-15,
+                          -54 3.9054 -8.10847,
+                          -54 11.8733 -9.96364,
+                          -54 14.5652 -5.30107,
+                          -67 14.5652 -5.30107,
+                          -54 14.5652 -5.30107,
+                          -54 11.8733 -9.96364,
+                          -54 7.03673 -5.61096,
+                          -54 3.9054 -8.10847,
+                          -54 14.5652 -5.30107,
+                          -54 8.77428 -2.00246,
+                          -54 7.03673 -5.61096,
+                          -54 14.5652 -5.30107,
+                          -67 14.5652 -5.30107,
+                          -67 15.5 -1.89814e-15,
+                          -54 14.5652 -5.30107,
+                          -54 -7.75042 -13.423,
+                          -54 7.75042 -13.423,
+                          -54 11.8733 -9.96364,
+                          -67 11.8733 -9.96364,
+                          -54 11.8733 -9.96364,
+                          -54 7.75042 -13.423,
+                          -54 -11.8733 -9.96364,
+                          -54 -7.75042 -13.423,
+                          -54 11.8733 -9.96364,
+                          -54 -1.10215e-15 -9,
+                          -54 -11.8733 -9.96364,
+                          -54 11.8733 -9.96364,
+                          -54 3.9054 -8.10847,
+                          -54 -1.10215e-15 -9,
+                          -54 11.8733 -9.96364,
+                          -67 14.5652 -5.30107,
+                          -54 11.8733 -9.96364,
+                          -67 11.8733 -9.96364,
+                          -54 -2.69082 -15.2646,
+                          -54 2.69082 -15.2646,
+                          -54 7.75042 -13.423,
+                          -67 7.75042 -13.423,
+                          -54 7.75042 -13.423,
+                          -54 2.69082 -15.2646,
+                          -54 -7.75042 -13.423,
+                          -54 -2.69082 -15.2646,
+                          -54 7.75042 -13.423,
+                          -67 11.8733 -9.96364,
+                          -54 7.75042 -13.423,
+                          -67 7.75042 -13.423,
+                          -67 2.69082 -15.2646,
+                          -54 2.69082 -15.2646,
+                          -54 -2.69082 -15.2646,
+                          -67 7.75042 -13.423,
+                          -54 2.69082 -15.2646,
+                          -67 2.69082 -15.2646,
+                          -67 -2.69082 -15.2646,
+                          -54 -2.69082 -15.2646,
+                          -54 -7.75042 -13.423,
+                          -67 2.69082 -15.2646,
+                          -54 -2.69082 -15.2646,
+                          -67 -2.69082 -15.2646,
+                          -67 -7.75042 -13.423,
+                          -54 -7.75042 -13.423,
+                          -54 -11.8733 -9.96364,
+                          -67 -2.69082 -15.2646,
+                          -54 -7.75042 -13.423,
+                          -67 -7.75042 -13.423,
+                          -54 -7.03673 -5.61096,
+                          -54 -14.5652 -5.30107,
+                          -54 -11.8733 -9.96364,
+                          -67 -11.8733 -9.96364,
+                          -54 -11.8733 -9.96364,
+                          -54 -14.5652 -5.30107,
+                          -54 -3.9054 -8.10847,
+                          -54 -7.03673 -5.61096,
+                          -54 -11.8733 -9.96364,
+                          -54 -1.10215e-15 -9,
+                          -54 -3.9054 -8.10847,
+                          -54 -11.8733 -9.96364,
+                          -67 -7.75042 -13.423,
+                          -54 -11.8733 -9.96364,
+                          -67 -11.8733 -9.96364,
+                          -54 -8.77428 -2.00246,
+                          -54 -15.5 1.89814e-15,
+                          -54 -14.5652 -5.30107,
+                          -67 -14.5652 -5.30107,
+                          -54 -14.5652 -5.30107,
+                          -54 -15.5 1.89814e-15,
+                          -54 -7.03673 -5.61096,
+                          -54 -8.77428 -2.00246,
+                          -54 -14.5652 -5.30107,
+                          -67 -11.8733 -9.96364,
+                          -54 -14.5652 -5.30107,
+                          -67 -14.5652 -5.30107,
+                          -54 -8.77428 2.00246,
+                          -54 -14.5652 5.30107,
+                          -54 -15.5 1.89814e-15,
+                          -67 -15.5 1.89814e-15,
+                          -54 -15.5 1.89814e-15,
+                          -54 -14.5652 5.30107,
+                          -54 -8.77428 -2.00246,
+                          -54 -8.77428 2.00246,
+                          -54 -15.5 1.89814e-15,
+                          -67 -14.5652 -5.30107,
+                          -54 -15.5 1.89814e-15,
+                          -67 -15.5 1.89814e-15,
+                          -54 -3.9054 8.10847,
+                          -54 -11.8733 9.96364,
+                          -54 -14.5652 5.30107,
+                          -67 -14.5652 5.30107,
+                          -54 -14.5652 5.30107,
+                          -54 -11.8733 9.96364,
+                          -54 -7.03673 5.61096,
+                          -54 -3.9054 8.10847,
+                          -54 -14.5652 5.30107,
+                          -54 -8.77428 2.00246,
+                          -54 -7.03673 5.61096,
+                          -54 -14.5652 5.30107,
+                          -67 -14.5652 5.30107,
+                          -67 -15.5 1.89814e-15,
+                          -54 -14.5652 5.30107,
+                          -54 7.75042 13.423,
+                          -54 -7.75042 13.423,
+                          -54 -11.8733 9.96364,
+                          -67 -11.8733 9.96364,
+                          -54 -11.8733 9.96364,
+                          -54 -7.75042 13.423,
+                          -54 11.8733 9.96364,
+                          -54 7.75042 13.423,
+                          -54 -11.8733 9.96364,
+                          -54 1.10214e-15 9,
+                          -54 11.8733 9.96364,
+                          -54 -11.8733 9.96364,
+                          -54 -3.9054 8.10847,
+                          -54 1.10214e-15 9,
+                          -54 -11.8733 9.96364,
+                          -67 -11.8733 9.96364,
+                          -67 -14.5652 5.30107,
+                          -54 -11.8733 9.96364,
+                          -54 2.69082 15.2646,
+                          -54 -2.69082 15.2646,
+                          -54 -7.75042 13.423,
+                          -67 -7.75042 13.423,
+                          -54 -7.75042 13.423,
+                          -54 -2.69082 15.2646,
+                          -54 7.75042 13.423,
+                          -54 2.69082 15.2646,
+                          -54 -7.75042 13.423,
+                          -67 -7.75042 13.423,
+                          -67 -11.8733 9.96364,
+                          -54 -7.75042 13.423,
+                          -67 -2.69082 15.2646,
+                          -54 -2.69082 15.2646,
+                          -54 2.69082 15.2646,
+                          -67 -2.69082 15.2646,
+                          -67 -7.75042 13.423,
+                          -54 -2.69082 15.2646,
+                          -67 2.69082 15.2646,
+                          -54 2.69082 15.2646,
+                          -54 7.75042 13.423,
+                          -67 2.69082 15.2646,
+                          -67 -2.69082 15.2646,
+                          -54 2.69082 15.2646,
+                          -67 7.75042 13.423,
+                          -54 7.75042 13.423,
+                          -54 11.8733 9.96364,
+                          -67 7.75042 13.423,
+                          -67 2.69082 15.2646,
+                          -54 7.75042 13.423,
+                          -54 7.03673 5.61096,
+                          -54 14.5652 5.30107,
+                          -54 11.8733 9.96364,
+                          -67 11.8733 9.96364,
+                          -54 11.8733 9.96364,
+                          -54 14.5652 5.30107,
+                          -54 3.9054 8.10847,
+                          -54 11.8733 9.96364,
+                          -54 1.10214e-15 9,
+                          -54 3.9054 8.10847,
+                          -54 7.03673 5.61096,
+                          -54 11.8733 9.96364,
+                          -67 11.8733 9.96364,
+                          -67 7.75042 13.423,
+                          -54 11.8733 9.96364,
+                          -54 7.03673 5.61096,
+                          -54 8.77428 2.00246,
+                          -54 14.5652 5.30107,
+                          -67 14.5652 5.30107,
+                          -67 11.8733 9.96364,
+                          -54 14.5652 5.30107,
+                          -49.5 1.10214e-15 9,
+                          -54 1.10214e-15 9,
+                          -54 -3.9054 8.10847,
+                          -49.5 3.90544 8.10837,
+                          -54 3.9054 8.10847,
+                          -54 1.10214e-15 9,
+                          -49.5 3.90544 8.10837,
+                          -54 1.10214e-15 9,
+                          -49.5 1.10214e-15 9,
+                          -49.5 -3.90544 8.10837,
+                          -54 -3.9054 8.10847,
+                          -54 -7.03673 5.61096,
+                          -49.5 -3.90544 8.10837,
+                          -49.5 1.10214e-15 9,
+                          -54 -3.9054 8.10847,
+                          -49.5 -7.03622 5.6115,
+                          -54 -7.03673 5.61096,
+                          -54 -8.77428 2.00246,
+                          -49.5 -3.90544 8.10837,
+                          -54 -7.03673 5.61096,
+                          -49.5 -7.03622 5.6115,
+                          -49.5 -8.77418 2.00326,
+                          -54 -8.77428 2.00246,
+                          -54 -8.77428 -2.00246,
+                          -49.5 -7.03622 5.6115,
+                          -54 -8.77428 2.00246,
+                          -49.5 -8.77418 2.00326,
+                          -49.5 -8.77418 -2.00326,
+                          -54 -8.77428 -2.00246,
+                          -54 -7.03673 -5.61096,
+                          -49.5 -8.77418 2.00326,
+                          -54 -8.77428 -2.00246,
+                          -49.5 -8.77418 -2.00326,
+                          -49.5 -7.03622 -5.6115,
+                          -54 -7.03673 -5.61096,
+                          -54 -3.9054 -8.10847,
+                          -49.5 -8.77418 -2.00326,
+                          -54 -7.03673 -5.61096,
+                          -49.5 -7.03622 -5.6115,
+                          -49.5 -3.90544 -8.10837,
+                          -54 -3.9054 -8.10847,
+                          -54 -1.10215e-15 -9,
+                          -49.5 -7.03622 -5.6115,
+                          -54 -3.9054 -8.10847,
+                          -49.5 -3.90544 -8.10837,
+                          -49.5 -1.10215e-15 -9,
+                          -54 -1.10215e-15 -9,
+                          -54 3.9054 -8.10847,
+                          -49.5 -3.90544 -8.10837,
+                          -54 -1.10215e-15 -9,
+                          -49.5 -1.10215e-15 -9,
+                          -49.5 3.90544 -8.10837,
+                          -54 3.9054 -8.10847,
+                          -54 7.03673 -5.61096,
+                          -49.5 -1.10215e-15 -9,
+                          -54 3.9054 -8.10847,
+                          -49.5 3.90544 -8.10837,
+                          -49.5 7.03622 -5.6115,
+                          -54 7.03673 -5.61096,
+                          -54 8.77428 -2.00246,
+                          -49.5 3.90544 -8.10837,
+                          -54 7.03673 -5.61096,
+                          -49.5 7.03622 -5.6115,
+                          -49.5 8.77418 -2.00326,
+                          -54 8.77428 -2.00246,
+                          -54 8.77428 2.00246,
+                          -49.5 7.03622 -5.6115,
+                          -54 8.77428 -2.00246,
+                          -49.5 8.77418 -2.00326,
+                          -49.5 8.77418 2.00326,
+                          -54 8.77428 2.00246,
+                          -54 7.03673 5.61096,
+                          -49.5 8.77418 -2.00326,
+                          -54 8.77428 2.00246,
+                          -49.5 8.77418 2.00326,
+                          -49.5 7.03622 5.6115,
+                          -54 7.03673 5.61096,
+                          -54 3.9054 8.10847,
+                          -49.5 8.77418 2.00326,
+                          -54 7.03673 5.61096,
+                          -49.5 7.03622 5.6115,
+                          -49.5 7.03622 5.6115,
+                          -54 3.9054 8.10847,
+                          -49.5 3.90544 8.10837,
+                          -67 0.927051 2.85317,
+                          -67 14.5652 5.30107,
+                          -67 15.5 -1.89814e-15,
+                          -67 14.5652 -5.30107,
+                          -67 3 0,
+                          -67 15.5 -1.89814e-15,
+                          -67 2.42705 1.76336,
+                          -67 15.5 -1.89814e-15,
+                          -67 3 0,
+                          -67 2.42705 1.76336,
+                          -67 0.927051 2.85317,
+                          -67 15.5 -1.89814e-15,
+                          -67 -3 0,
+                          -67 -15.5 1.89814e-15,
+                          -67 -14.5652 5.30107,
+                          -67 -2.42705 -1.76336,
+                          -67 -15.5 1.89814e-15,
+                          -67 -3 0,
+                          -67 -0.927051 -2.85317,
+                          -67 -15.5 1.89814e-15,
+                          -67 -2.42705 -1.76336,
+                          -67 -14.5652 -5.30107,
+                          -67 -15.5 1.89814e-15,
+                          -67 -0.927051 -2.85317,
+                          -67 14.5652 5.30107,
+                          -67 -14.5652 5.30107,
+                          -67 -11.8733 9.96364,
+                          -67 0.927051 2.85317,
+                          -67 -14.5652 5.30107,
+                          -67 14.5652 5.30107,
+                          -67 -2.42705 1.76336,
+                          -67 -3 0,
+                          -67 -14.5652 5.30107,
+                          -67 -0.927051 2.85317,
+                          -67 -2.42705 1.76336,
+                          -67 -14.5652 5.30107,
+                          -67 0.927051 2.85317,
+                          -67 -0.927051 2.85317,
+                          -67 -14.5652 5.30107,
+                          -67 11.8733 9.96364,
+                          -67 -11.8733 9.96364,
+                          -67 -7.75042 13.423,
+                          -67 14.5652 5.30107,
+                          -67 -11.8733 9.96364,
+                          -67 11.8733 9.96364,
+                          -67 7.75042 13.423,
+                          -67 -7.75042 13.423,
+                          -67 -2.69082 15.2646,
+                          -67 11.8733 9.96364,
+                          -67 -7.75042 13.423,
+                          -67 7.75042 13.423,
+                          -67 7.75042 13.423,
+                          -67 -2.69082 15.2646,
+                          -67 2.69082 15.2646,
+                          -54 2.59825 1.4997,
+                          -67 3 0,
+                          -54 3 -7.34764e-16,
+                          -67 2.42705 -1.76336,
+                          -54 3 -7.34764e-16,
+                          -67 3 0,
+                          -67 2.42705 1.76336,
+                          -67 3 0,
+                          -54 2.59825 1.4997,
+                          -67 14.5652 -5.30107,
+                          -67 2.42705 -1.76336,
+                          -67 3 0,
+                          -49.5 2.8531 0.926741,
+                          -54 2.59825 1.4997,
+                          -54 3 -7.34764e-16,
+                          -49.5 2.8531 -0.926741,
+                          -49.5 2.8531 0.926741,
+                          -54 3 -7.34764e-16,
+                          -67 2.42705 -1.76336,
+                          -49.5 2.8531 -0.926741,
+                          -54 3 -7.34764e-16,
+                          -49.5 1.76375 2.42667,
+                          -54 1.50037 2.59786,
+                          -54 2.59825 1.4997,
+                          -67 2.42705 1.76336,
+                          -54 2.59825 1.4997,
+                          -54 1.50037 2.59786,
+                          -49.5 2.8531 0.926741,
+                          -49.5 1.76375 2.42667,
+                          -54 2.59825 1.4997,
+                          -49.5 -4.69051e-21 3,
+                          -54 9.1845e-16 3,
+                          -54 1.50037 2.59786,
+                          -67 0.927051 2.85317,
+                          -54 1.50037 2.59786,
+                          -54 9.1845e-16 3,
+                          -49.5 1.76375 2.42667,
+                          -49.5 -4.69051e-21 3,
+                          -54 1.50037 2.59786,
+                          -67 2.42705 1.76336,
+                          -54 1.50037 2.59786,
+                          -67 0.927051 2.85317,
+                          -49.5 -1.76375 2.42667,
+                          -54 9.1845e-16 3,
+                          -49.5 -4.69051e-21 3,
+                          -67 -0.927051 2.85317,
+                          -54 9.1845e-16 3,
+                          -49.5 -1.76375 2.42667,
+                          -67 0.927051 2.85317,
+                          -54 9.1845e-16 3,
+                          -67 -0.927051 2.85317,
+                          -49.5 1.10214e-15 9,
+                          -49.5 -4.69051e-21 3,
+                          -49.5 1.76375 2.42667,
+                          -49.5 -3.90544 8.10837,
+                          -49.5 -4.69051e-21 3,
+                          -49.5 1.10214e-15 9,
+                          -49.5 -1.76375 2.42667,
+                          -49.5 -4.69051e-21 3,
+                          -49.5 -3.90544 8.10837,
+                          -49.5 1.10214e-15 9,
+                          -49.5 1.76375 2.42667,
+                          -49.5 2.8531 0.926741,
+                          -49.5 3.90544 -8.10837,
+                          -49.5 2.8531 0.926741,
+                          -49.5 2.8531 -0.926741,
+                          -49.5 3.90544 8.10837,
+                          -49.5 1.10214e-15 9,
+                          -49.5 2.8531 0.926741,
+                          -49.5 3.90544 -8.10837,
+                          -49.5 3.90544 8.10837,
+                          -49.5 2.8531 0.926741,
+                          -67 2.42705 -1.76336,
+                          -49.5 1.76375 -2.42667,
+                          -49.5 2.8531 -0.926741,
+                          -49.5 3.90544 -8.10837,
+                          -49.5 2.8531 -0.926741,
+                          -49.5 1.76375 -2.42667,
+                          -54 -5.51078e-16 -3,
+                          -49.5 -4.69051e-21 -3,
+                          -49.5 1.76375 -2.42667,
+                          -49.5 3.90544 -8.10837,
+                          -49.5 1.76375 -2.42667,
+                          -49.5 -4.69051e-21 -3,
+                          -67 0.927051 -2.85317,
+                          -54 -5.51078e-16 -3,
+                          -49.5 1.76375 -2.42667,
+                          -67 2.42705 -1.76336,
+                          -67 0.927051 -2.85317,
+                          -49.5 1.76375 -2.42667,
+                          -54 -1.50037 -2.59786,
+                          -49.5 -4.69051e-21 -3,
+                          -54 -5.51078e-16 -3,
+                          -49.5 -1.76375 -2.42667,
+                          -49.5 -4.69051e-21 -3,
+                          -54 -1.50037 -2.59786,
+                          -49.5 -1.10215e-15 -9,
+                          -49.5 3.90544 -8.10837,
+                          -49.5 -4.69051e-21 -3,
+                          -49.5 -1.76375 -2.42667,
+                          -49.5 -1.10215e-15 -9,
+                          -49.5 -4.69051e-21 -3,
+                          -67 -0.927051 -2.85317,
+                          -54 -1.50037 -2.59786,
+                          -54 -5.51078e-16 -3,
+                          -67 0.927051 -2.85317,
+                          -67 -0.927051 -2.85317,
+                          -54 -5.51078e-16 -3,
+                          -67 -2.42705 -1.76336,
+                          -54 -2.59825 -1.4997,
+                          -54 -1.50037 -2.59786,
+                          -49.5 -1.76375 -2.42667,
+                          -54 -1.50037 -2.59786,
+                          -54 -2.59825 -1.4997,
+                          -67 -0.927051 -2.85317,
+                          -67 -2.42705 -1.76336,
+                          -54 -1.50037 -2.59786,
+                          -67 -3 0,
+                          -54 -3 3.67382e-16,
+                          -54 -2.59825 -1.4997,
+                          -49.5 -2.8531 -0.926741,
+                          -54 -2.59825 -1.4997,
+                          -54 -3 3.67382e-16,
+                          -67 -2.42705 -1.76336,
+                          -67 -3 0,
+                          -54 -2.59825 -1.4997,
+                          -49.5 -1.76375 -2.42667,
+                          -54 -2.59825 -1.4997,
+                          -49.5 -2.8531 -0.926741,
+                          -67 -2.42705 1.76336,
+                          -54 -3 3.67382e-16,
+                          -67 -3 0,
+                          -49.5 -2.8531 -0.926741,
+                          -54 -3 3.67382e-16,
+                          -49.5 -2.8531 0.926741,
+                          -67 -2.42705 1.76336,
+                          -49.5 -2.8531 0.926741,
+                          -54 -3 3.67382e-16,
+                          -67 14.5652 -5.30107,
+                          -67 -0.927051 -2.85317,
+                          -67 0.927051 -2.85317,
+                          -67 14.5652 -5.30107,
+                          -67 -14.5652 -5.30107,
+                          -67 -0.927051 -2.85317,
+                          -67 14.5652 -5.30107,
+                          -67 0.927051 -2.85317,
+                          -67 2.42705 -1.76336,
+                          -49.5 7.03622 -5.6115,
+                          -49.5 7.03622 5.6115,
+                          -49.5 3.90544 8.10837,
+                          -49.5 3.90544 -8.10837,
+                          -49.5 7.03622 -5.6115,
+                          -49.5 3.90544 8.10837,
+                          -49.5 8.77418 -2.00326,
+                          -49.5 8.77418 2.00326,
+                          -49.5 7.03622 5.6115,
+                          -49.5 7.03622 -5.6115,
+                          -49.5 8.77418 -2.00326,
+                          -49.5 7.03622 5.6115,
+                          -49.5 -2.8531 -0.926741,
+                          -49.5 -3.90544 -8.10837,
+                          -49.5 -1.10215e-15 -9,
+                          -49.5 -1.76375 -2.42667,
+                          -49.5 -2.8531 -0.926741,
+                          -49.5 -1.10215e-15 -9,
+                          -49.5 -7.03622 5.6115,
+                          -49.5 -7.03622 -5.6115,
+                          -49.5 -3.90544 -8.10837,
+                          -49.5 -3.90544 8.10837,
+                          -49.5 -7.03622 5.6115,
+                          -49.5 -3.90544 -8.10837,
+                          -49.5 -2.8531 -0.926741,
+                          -49.5 -3.90544 8.10837,
+                          -49.5 -3.90544 -8.10837,
+                          -49.5 -8.77418 2.00326,
+                          -49.5 -8.77418 -2.00326,
+                          -49.5 -7.03622 -5.6115,
+                          -49.5 -7.03622 5.6115,
+                          -49.5 -8.77418 2.00326,
+                          -49.5 -7.03622 -5.6115,
+                          -49.5 -2.8531 0.926741,
+                          -49.5 -1.76375 2.42667,
+                          -49.5 -3.90544 8.10837,
+                          -49.5 -2.8531 -0.926741,
+                          -49.5 -2.8531 0.926741,
+                          -49.5 -3.90544 8.10837,
+                          -67 -2.42705 1.76336,
+                          -49.5 -1.76375 2.42667,
+                          -49.5 -2.8531 0.926741,
+                          -67 -0.927051 2.85317,
+                          -49.5 -1.76375 2.42667,
+                          -67 -2.42705 1.76336,
+                          -67 11.8733 -9.96364,
+                          -67 -11.8733 -9.96364,
+                          -67 -14.5652 -5.30107,
+                          -67 14.5652 -5.30107,
+                          -67 11.8733 -9.96364,
+                          -67 -14.5652 -5.30107,
+                          -67 7.75042 -13.423,
+                          -67 -7.75042 -13.423,
+                          -67 -11.8733 -9.96364,
+                          -67 11.8733 -9.96364,
+                          -67 7.75042 -13.423,
+                          -67 -11.8733 -9.96364,
+                          -67 2.69082 -15.2646,
+                          -67 -2.69082 -15.2646,
+                          -67 -7.75042 -13.423,
+                          -67 7.75042 -13.423,
+                          -67 2.69082 -15.2646,
+                          -67 -7.75042 -13.423 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          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,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          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 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -41.5 -96 -44.5,
+                          -41.5 -96 -27,
+                          41.5 -96 -27,
+                          41.5 -137.5 -27,
+                          41.5 -96 -27,
+                          -41.5 -96 -27,
+                          41.5 -96 -44.5,
+                          -41.5 -96 -44.5,
+                          41.5 -96 -27,
+                          41.5 -137.5 -27,
+                          41.5 -96 -44.5,
+                          41.5 -96 -27,
+                          -41.5 -137.5 -44.5,
+                          -41.5 -96 -27,
+                          -41.5 -96 -44.5,
+                          -41.5 -137.5 -27,
+                          41.5 -137.5 -27,
+                          -41.5 -96 -27,
+                          -41.5 -137.5 -27,
+                          -41.5 -96 -27,
+                          -41.5 -137.5 -44.5,
+                          -41.5 -137.5 -44.5,
+                          -41.5 -96 -44.5,
+                          41.5 -96 -44.5,
+                          41.5 -137.5 -44.5,
+                          41.5 -96 -44.5,
+                          41.5 -137.5 -27,
+                          -41.5 -137.5 -44.5,
+                          41.5 -96 -44.5,
+                          41.5 -137.5 -44.5,
+                          -41.5 -137.5 -27,
+                          41.5 -137.5 -44.5,
+                          41.5 -137.5 -27,
+                          -41.5 -137.5 -27,
+                          -41.5 -137.5 -44.5,
+                          41.5 -137.5 -44.5 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          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,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          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 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 10 -99.5 -27,
+                          -10 -99.5 78,
+                          10 -99.5 78,
+                          10 -102.5 78,
+                          10 -99.5 78,
+                          -10 -99.5 78,
+                          10 -102.5 -27,
+                          10 -99.5 -27,
+                          10 -99.5 78,
+                          10 -102.5 -27,
+                          10 -99.5 78,
+                          10 -102.5 78,
+                          10 -99.5 -27,
+                          -10 -99.5 -27,
+                          -10 -99.5 78,
+                          -10 -102.5 78,
+                          -10 -99.5 78,
+                          -10 -99.5 -27,
+                          -10 -102.5 78,
+                          10 -102.5 78,
+                          -10 -99.5 78,
+                          -10 -102.5 -27,
+                          -10 -99.5 -27,
+                          10 -99.5 -27,
+                          -10 -102.5 78,
+                          -10 -99.5 -27,
+                          -10 -102.5 -27,
+                          -10 -102.5 -27,
+                          10 -99.5 -27,
+                          10 -102.5 -27,
+                          -10 -102.5 -27,
+                          10 -102.5 -27,
+                          10 -102.5 78,
+                          -10 -102.5 78,
+                          -10 -102.5 -27,
+                          10 -102.5 78 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 -1 0,
+                          0 -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,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -5 -127.5 -27,
+                          -5 -131.5 -27,
+                          -5 -131.5 78,
+                          5 -131.5 78,
+                          -5 -131.5 78,
+                          -5 -131.5 -27,
+                          -5 -127.5 78,
+                          -5 -127.5 -27,
+                          -5 -131.5 78,
+                          5 -131.5 78,
+                          -5 -127.5 78,
+                          -5 -131.5 78,
+                          5 -127.5 -27,
+                          -5 -131.5 -27,
+                          -5 -127.5 -27,
+                          5 -131.5 -27,
+                          -5 -131.5 -27,
+                          5 -127.5 -27,
+                          5 -131.5 78,
+                          -5 -131.5 -27,
+                          5 -131.5 -27,
+                          5 -127.5 -27,
+                          -5 -127.5 -27,
+                          -5 -127.5 78,
+                          5 -127.5 78,
+                          5 -127.5 -27,
+                          -5 -127.5 78,
+                          5 -131.5 78,
+                          5 -127.5 78,
+                          -5 -127.5 78,
+                          5 -131.5 -27,
+                          5 -127.5 -27,
+                          5 -127.5 78,
+                          5 -131.5 78,
+                          5 -131.5 -27,
+                          5 -127.5 78 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -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.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          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 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0.707107 -0.707107 0,
+                          0.707107 -0.707107 0,
+                          0.707107 -0.707107 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.707107 -0.707107 0,
+                          0.707107 -0.707107 0,
+                          0.707107 -0.707107 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,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 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,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.5 -0.5 0.707107,
+                          -0.5 -0.5 0.707107,
+                          -0.5 -0.5 0.707107,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 -0.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          0 -0.707107 0.707107,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.707107 0 0.707107,
+                          -0.707107 0 0.707107,
+                          -0.707107 0 0.707107,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.5 -0.5 0.707107,
+                          -0.5 -0.5 0.707107,
+                          -0.5 -0.5 0.707107,
+                          0 0.707107 0.707107,
+                          0 0.707107 0.707107,
+                          0 0.707107 0.707107,
+                          -0.707107 0 0.707107,
+                          -0.707107 0 0.707107,
+                          -0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          0 0.707107 0.707107,
+                          0 0.707107 0.707107,
+                          0 0.707107 0.707107,
+                          0.5 -0.5 0.707107,
+                          0.5 -0.5 0.707107,
+                          0.5 -0.5 0.707107,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          0.5 -0.5 0.707107,
+                          0.5 -0.5 0.707107,
+                          0.5 -0.5 0.707107,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          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.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          -0.707107 5.23364e-17 -0.707107,
+                          -0.707107 5.23364e-17 -0.707107,
+                          -0.707107 5.23364e-17 -0.707107,
+                          -0.707107 5.23364e-17 -0.707107,
+                          -0.707107 5.23364e-17 -0.707107,
+                          -0.707107 5.23364e-17 -0.707107,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          -0.707107 0 -0.707107,
+                          -0.707107 0 -0.707107,
+                          -0.707107 0 -0.707107,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.707107 0 -0.707107,
+                          -0.707107 0 -0.707107,
+                          -0.707107 0 -0.707107,
+                          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 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -10 -129.5 78,
+                          -5 -131.5 78,
+                          -5 -134.5 78,
+                          -5 -131.5 70,
+                          -5 -134.5 78,
+                          -5 -131.5 78,
+                          -5 -134.5 70,
+                          5 -134.5 78,
+                          -5 -134.5 78,
+                          5 -134.5 83,
+                          -5 -134.5 78,
+                          5 -134.5 78,
+                          -10 -129.5 83,
+                          -10 -129.5 78,
+                          -5 -134.5 78,
+                          -5 -131.5 70,
+                          -5 -134.5 70,
+                          -5 -134.5 78,
+                          5 -134.5 83,
+                          -5 -134.5 83,
+                          -5 -134.5 78,
+                          -10 -129.5 83,
+                          -5 -134.5 78,
+                          -5 -134.5 83,
+                          -10 -129.5 78,
+                          5 -131.5 78,
+                          -5 -131.5 78,
+                          5 -131.5 70,
+                          -5 -131.5 78,
+                          5 -131.5 78,
+                          5 -131.5 70,
+                          -5 -131.5 70,
+                          -5 -131.5 78,
+                          10 -129.5 78,
+                          5 -134.5 78,
+                          5 -131.5 78,
+                          5 -134.5 70,
+                          5 -131.5 78,
+                          5 -134.5 78,
+                          -10 -129.5 78,
+                          10 -129.5 78,
+                          5 -131.5 78,
+                          5 -131.5 70,
+                          5 -131.5 78,
+                          5 -134.5 70,
+                          5 -134.5 83,
+                          5 -134.5 78,
+                          10 -129.5 78,
+                          -5 -134.5 70,
+                          5 -134.5 70,
+                          5 -134.5 78,
+                          -10 -99.5 78,
+                          10 -99.5 78,
+                          10 -129.5 78,
+                          10 -129.5 83,
+                          10 -129.5 78,
+                          10 -99.5 78,
+                          -10 -129.5 78,
+                          -10 -99.5 78,
+                          10 -129.5 78,
+                          10 -129.5 83,
+                          5 -134.5 83,
+                          10 -129.5 78,
+                          10 -99.5 72,
+                          10 -99.5 78,
+                          -10 -99.5 78,
+                          10 -96.5 72,
+                          10 -96.5 83,
+                          10 -99.5 78,
+                          10 -129.5 83,
+                          10 -99.5 78,
+                          10 -96.5 83,
+                          10 -99.5 72,
+                          10 -96.5 72,
+                          10 -99.5 78,
+                          -10 -96.5 83,
+                          -10 -99.5 78,
+                          -10 -129.5 78,
+                          6 -99.5 68,
+                          10 -99.5 72,
+                          -10 -99.5 78,
+                          -10 -99.5 72,
+                          -10 -99.5 78,
+                          -10 -96.5 83,
+                          -6 -99.5 68,
+                          -10 -99.5 78,
+                          -10 -99.5 72,
+                          6 -99.5 68,
+                          -10 -99.5 78,
+                          -6 -99.5 68,
+                          -10 -129.5 83,
+                          -10 -96.5 83,
+                          -10 -129.5 78,
+                          7 -128.257 86,
+                          -7 -128.257 86,
+                          -3.75736 -131.5 86,
+                          -5 -134.5 83,
+                          -3.75736 -131.5 86,
+                          -7 -128.257 86,
+                          3.75736 -131.5 86,
+                          7 -128.257 86,
+                          -3.75736 -131.5 86,
+                          5 -134.5 83,
+                          3.75736 -131.5 86,
+                          -3.75736 -131.5 86,
+                          5 -134.5 83,
+                          -3.75736 -131.5 86,
+                          -5 -134.5 83,
+                          7 -99.5 86,
+                          -7 -99.5 86,
+                          -7 -128.257 86,
+                          -10 -129.5 83,
+                          -7 -128.257 86,
+                          -7 -99.5 86,
+                          7 -128.257 86,
+                          7 -99.5 86,
+                          -7 -128.257 86,
+                          -10 -129.5 83,
+                          -5 -134.5 83,
+                          -7 -128.257 86,
+                          -10 -96.5 83,
+                          -7 -99.5 86,
+                          7 -99.5 86,
+                          -10 -129.5 83,
+                          -7 -99.5 86,
+                          -10 -96.5 83,
+                          10 -96.5 83,
+                          7 -99.5 86,
+                          7 -128.257 86,
+                          -10 -96.5 83,
+                          7 -99.5 86,
+                          10 -96.5 83,
+                          10 -129.5 83,
+                          7 -128.257 86,
+                          3.75736 -131.5 86,
+                          10 -129.5 83,
+                          10 -96.5 83,
+                          7 -128.257 86,
+                          10 -129.5 83,
+                          3.75736 -131.5 86,
+                          5 -134.5 83,
+                          -1 -134.5 66,
+                          1 -134.5 66,
+                          5 -134.5 70,
+                          5 -131.5 70,
+                          5 -134.5 70,
+                          1 -134.5 66,
+                          -5 -134.5 70,
+                          -1 -134.5 66,
+                          5 -134.5 70,
+                          -1 -131.5 66,
+                          1 -134.5 66,
+                          -1 -134.5 66,
+                          -1 -131.5 66,
+                          1 -131.5 66,
+                          1 -134.5 66,
+                          5 -131.5 70,
+                          1 -134.5 66,
+                          1 -131.5 66,
+                          -1 -131.5 66,
+                          -1 -134.5 66,
+                          -5 -134.5 70,
+                          -5 -131.5 70,
+                          -1 -131.5 66,
+                          -5 -134.5 70,
+                          6 -96.5 68,
+                          10 -96.5 83,
+                          10 -96.5 72,
+                          -6 -96.5 68,
+                          -10 -96.5 72,
+                          10 -96.5 83,
+                          -10 -96.5 83,
+                          10 -96.5 83,
+                          -10 -96.5 72,
+                          6 -96.5 68,
+                          -6 -96.5 68,
+                          10 -96.5 83,
+                          6 -99.5 68,
+                          10 -96.5 72,
+                          10 -99.5 72,
+                          6 -99.5 68,
+                          6 -96.5 68,
+                          10 -96.5 72,
+                          -10 -99.5 72,
+                          -10 -96.5 72,
+                          -6 -96.5 68,
+                          -10 -99.5 72,
+                          -10 -96.5 83,
+                          -10 -96.5 72,
+                          -6 -99.5 68,
+                          -6 -96.5 68,
+                          6 -96.5 68,
+                          -6 -99.5 68,
+                          -10 -99.5 72,
+                          -6 -96.5 68,
+                          6 -99.5 68,
+                          -6 -99.5 68,
+                          6 -96.5 68,
+                          -5 -131.5 70,
+                          1 -131.5 66,
+                          -1 -131.5 66,
+                          5 -131.5 70,
+                          1 -131.5 66,
+                          -5 -131.5 70 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.866025 0.5,
+                          0 -0.866025 0.5,
+                          0 -0.994522 -0.104528,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.406737 0.913545,
+                          0 -0.406737 0.913545,
+                          0 -0.866025 0.5,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.406737 0.913545,
+                          0 -0.866025 0.5,
+                          0 -0.866025 0.5,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.994522 -0.104528,
+                          0 -0.994522 -0.104528,
+                          0 -0.743145 -0.669131,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.994522 -0.104528,
+                          0 -0.866025 0.5,
+                          0 -0.994522 -0.104528,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.743145 -0.669131,
+                          0 -0.743145 -0.669131,
+                          0 -0.207912 -0.978148,
+                          0 -0.994522 -0.104528,
+                          0 -0.743145 -0.669131,
+                          0 -0.743145 -0.669131,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -0.207912 -0.978148,
+                          0 -0.207912 -0.978148,
+                          0 0.406737 -0.913545,
+                          0 -0.743145 -0.669131,
+                          0 -0.207912 -0.978148,
+                          0 -0.207912 -0.978148,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.406737 -0.913545,
+                          0 0.406737 -0.913545,
+                          0 0.866025 -0.5,
+                          0 -0.207912 -0.978148,
+                          0 0.406737 -0.913545,
+                          0 0.406737 -0.913545,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.866025 -0.5,
+                          0 0.866025 -0.5,
+                          0 0.994522 0.104528,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.406737 -0.913545,
+                          0 0.866025 -0.5,
+                          0 0.866025 -0.5,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.994522 0.104528,
+                          0 0.994522 0.104528,
+                          0 0.743145 0.669131,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.866025 -0.5,
+                          0 0.994522 0.104528,
+                          0 0.994522 0.104528,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.743145 0.669131,
+                          0 0.743145 0.669131,
+                          0 0.207912 0.978148,
+                          0 0.994522 0.104528,
+                          0 0.743145 0.669131,
+                          0 0.743145 0.669131,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.207912 0.978148,
+                          0 0.207912 0.978148,
+                          0 -0.406737 0.913545,
+                          0 0.743145 0.669131,
+                          0 0.207912 0.978148,
+                          0 0.207912 0.978148,
+                          0 0.207912 0.978148,
+                          0 -0.406737 0.913545,
+                          0 -0.406737 0.913545,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -1 5.55112e-17,
+                          0 -1 5.55112e-17,
+                          0 -1 5.55112e-17,
+                          0 -0.5 -0.866025,
+                          0 -0.5 -0.866025,
+                          0 -0.5 -0.866025,
+                          0 -0.5 -0.866025,
+                          0 -0.5 -0.866025,
+                          0 -0.5 -0.866025,
+                          0 -0.5 0.866025,
+                          0 -0.5 0.866025,
+                          0 -0.5 0.866025,
+                          0 -1 5.55112e-17,
+                          0 -1 5.55112e-17,
+                          0 -1 5.55112e-17,
+                          0 0.5 0.866025,
+                          0 0.5 0.866025,
+                          0 0.5 0.866025,
+                          0 -0.5 0.866025,
+                          0 -0.5 0.866025,
+                          0 -0.5 0.866025,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 1 -5.55112e-17,
+                          0 1 -5.55112e-17,
+                          0 1 -5.55112e-17,
+                          0 0.5 0.866025,
+                          0 0.5 0.866025,
+                          0 0.5 0.866025,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 1 -5.55112e-17,
+                          0 1 -5.55112e-17,
+                          0 1 -5.55112e-17,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 61.5 8.5 4.90748,
+                          61.5 3.97799 0.418275,
+                          61.5 3.4641 -2,
+                          57.5 3.4641 -2,
+                          61.5 3.4641 -2,
+                          61.5 3.97799 0.418275,
+                          61.5 -1.77637e-15 -9.81495,
+                          61.5 3.4641 -2,
+                          61.5 1.62676 -3.65418,
+                          57.5 1.62676 -3.65418,
+                          61.5 1.62676 -3.65418,
+                          61.5 3.4641 -2,
+                          61.5 -1.77637e-15 -9.81495,
+                          61.5 8.5 4.90748,
+                          61.5 3.4641 -2,
+                          57.5 1.62676 -3.65418,
+                          61.5 3.4641 -2,
+                          57.5 3.4641 -2,
+                          61.5 1.77635e-15 9.81495,
+                          61.5 2.97278 2.67625,
+                          61.5 3.97799 0.418275,
+                          57.5 3.97799 0.418275,
+                          61.5 3.97799 0.418275,
+                          61.5 2.97278 2.67625,
+                          61.5 8.5 4.90748,
+                          61.5 1.77635e-15 9.81495,
+                          61.5 3.97799 0.418275,
+                          57.5 3.97799 0.418275,
+                          57.5 3.4641 -2,
+                          61.5 3.97799 0.418275,
+                          61.5 1.77635e-15 9.81495,
+                          61.5 0.831306 3.91263,
+                          61.5 2.97278 2.67625,
+                          57.5 2.97278 2.67625,
+                          61.5 2.97278 2.67625,
+                          61.5 0.831306 3.91263,
+                          57.5 3.97799 0.418275,
+                          61.5 2.97278 2.67625,
+                          57.5 2.97278 2.67625,
+                          61.5 1.77635e-15 9.81495,
+                          61.5 -1.62676 3.65418,
+                          61.5 0.831306 3.91263,
+                          57.5 0.831306 3.91263,
+                          61.5 0.831306 3.91263,
+                          61.5 -1.62676 3.65418,
+                          57.5 2.97278 2.67625,
+                          61.5 0.831306 3.91263,
+                          57.5 0.831306 3.91263,
+                          61.5 1.77635e-15 9.81495,
+                          61.5 -3.4641 2,
+                          61.5 -1.62676 3.65418,
+                          57.5 -1.62676 3.65418,
+                          61.5 -1.62676 3.65418,
+                          61.5 -3.4641 2,
+                          57.5 0.831306 3.91263,
+                          61.5 -1.62676 3.65418,
+                          57.5 -1.62676 3.65418,
+                          61.5 -8.5 -4.90748,
+                          61.5 -3.97799 -0.418275,
+                          61.5 -3.4641 2,
+                          57.5 -3.4641 2,
+                          61.5 -3.4641 2,
+                          61.5 -3.97799 -0.418275,
+                          61.5 1.77635e-15 9.81495,
+                          61.5 -8.5 -4.90748,
+                          61.5 -3.4641 2,
+                          57.5 -1.62676 3.65418,
+                          61.5 -3.4641 2,
+                          57.5 -3.4641 2,
+                          61.5 -1.77637e-15 -9.81495,
+                          61.5 -2.97278 -2.67625,
+                          61.5 -3.97799 -0.418275,
+                          57.5 -3.97799 -0.418275,
+                          61.5 -3.97799 -0.418275,
+                          61.5 -2.97278 -2.67625,
+                          61.5 -1.77637e-15 -9.81495,
+                          61.5 -3.97799 -0.418275,
+                          61.5 -8.5 -4.90748,
+                          57.5 -3.4641 2,
+                          61.5 -3.97799 -0.418275,
+                          57.5 -3.97799 -0.418275,
+                          61.5 -1.77637e-15 -9.81495,
+                          61.5 -0.831306 -3.91263,
+                          61.5 -2.97278 -2.67625,
+                          57.5 -2.97278 -2.67625,
+                          61.5 -2.97278 -2.67625,
+                          61.5 -0.831306 -3.91263,
+                          57.5 -3.97799 -0.418275,
+                          61.5 -2.97278 -2.67625,
+                          57.5 -2.97278 -2.67625,
+                          61.5 -1.77637e-15 -9.81495,
+                          61.5 1.62676 -3.65418,
+                          61.5 -0.831306 -3.91263,
+                          57.5 -0.831306 -3.91263,
+                          61.5 -0.831306 -3.91263,
+                          61.5 1.62676 -3.65418,
+                          57.5 -2.97278 -2.67625,
+                          61.5 -0.831306 -3.91263,
+                          57.5 -0.831306 -3.91263,
+                          57.5 -0.831306 -3.91263,
+                          61.5 1.62676 -3.65418,
+                          57.5 1.62676 -3.65418,
+                          61.5 1.77635e-15 9.81495,
+                          61.5 -8.5 4.90748,
+                          61.5 -8.5 -4.90748,
+                          57.5 -8.5 -4.90748,
+                          61.5 -8.5 -4.90748,
+                          61.5 -8.5 4.90748,
+                          57.5 -1.77637e-15 -9.81495,
+                          61.5 -1.77637e-15 -9.81495,
+                          61.5 -8.5 -4.90748,
+                          57.5 -1.77637e-15 -9.81495,
+                          61.5 -8.5 -4.90748,
+                          57.5 -8.5 -4.90748,
+                          57.5 -8.5 4.90748,
+                          61.5 -8.5 4.90748,
+                          61.5 1.77635e-15 9.81495,
+                          57.5 -8.5 4.90748,
+                          57.5 -8.5 -4.90748,
+                          61.5 -8.5 4.90748,
+                          57.5 1.77635e-15 9.81495,
+                          61.5 1.77635e-15 9.81495,
+                          61.5 8.5 4.90748,
+                          57.5 -8.5 4.90748,
+                          61.5 1.77635e-15 9.81495,
+                          57.5 1.77635e-15 9.81495,
+                          61.5 -1.77637e-15 -9.81495,
+                          61.5 8.5 -4.90748,
+                          61.5 8.5 4.90748,
+                          57.5 8.5 4.90748,
+                          61.5 8.5 4.90748,
+                          61.5 8.5 -4.90748,
+                          57.5 1.77635e-15 9.81495,
+                          61.5 8.5 4.90748,
+                          57.5 8.5 4.90748,
+                          57.5 8.5 -4.90748,
+                          61.5 8.5 -4.90748,
+                          61.5 -1.77637e-15 -9.81495,
+                          57.5 8.5 4.90748,
+                          61.5 8.5 -4.90748,
+                          57.5 8.5 -4.90748,
+                          57.5 8.5 -4.90748,
+                          61.5 -1.77637e-15 -9.81495,
+                          57.5 -1.77637e-15 -9.81495,
+                          57.5 -1.77637e-15 -9.81495,
+                          57.5 1.62676 -3.65418,
+                          57.5 3.4641 -2,
+                          57.5 8.5 4.90748,
+                          57.5 3.4641 -2,
+                          57.5 3.97799 0.418275,
+                          57.5 8.5 4.90748,
+                          57.5 -1.77637e-15 -9.81495,
+                          57.5 3.4641 -2,
+                          57.5 -8.5 -4.90748,
+                          57.5 -0.831306 -3.91263,
+                          57.5 1.62676 -3.65418,
+                          57.5 -1.77637e-15 -9.81495,
+                          57.5 -8.5 -4.90748,
+                          57.5 1.62676 -3.65418,
+                          57.5 -8.5 -4.90748,
+                          57.5 -2.97278 -2.67625,
+                          57.5 -0.831306 -3.91263,
+                          57.5 -8.5 -4.90748,
+                          57.5 -3.97799 -0.418275,
+                          57.5 -2.97278 -2.67625,
+                          57.5 -8.5 -4.90748,
+                          57.5 -3.4641 2,
+                          57.5 -3.97799 -0.418275,
+                          57.5 1.77635e-15 9.81495,
+                          57.5 -1.62676 3.65418,
+                          57.5 -3.4641 2,
+                          57.5 1.77635e-15 9.81495,
+                          57.5 -3.4641 2,
+                          57.5 -8.5 -4.90748,
+                          57.5 8.5 4.90748,
+                          57.5 0.831306 3.91263,
+                          57.5 -1.62676 3.65418,
+                          57.5 1.77635e-15 9.81495,
+                          57.5 8.5 4.90748,
+                          57.5 -1.62676 3.65418,
+                          57.5 8.5 4.90748,
+                          57.5 2.97278 2.67625,
+                          57.5 0.831306 3.91263,
+                          57.5 8.5 4.90748,
+                          57.5 3.97799 0.418275,
+                          57.5 2.97278 2.67625,
+                          57.5 -8.5 4.90748,
+                          57.5 1.77635e-15 9.81495,
+                          57.5 -8.5 -4.90748,
+                          57.5 8.5 4.90748,
+                          57.5 8.5 -4.90748,
+                          57.5 -1.77637e-15 -9.81495 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 0.433884 0 0.900969,
+                          0.433884 0 0.900969,
+                          7.13224e-17 0 1,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          7.13224e-17 0 1,
+                          0.433884 0 0.900969,
+                          7.13224e-17 0 1,
+                          -0.433884 0 0.900969,
+                          7.13224e-17 0 1,
+                          7.13224e-17 0 1,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.781832 0 0.62349,
+                          0.781832 0 0.62349,
+                          0.433884 0 0.900969,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.433884 0 0.900969,
+                          0.781832 0 0.62349,
+                          0.433884 0 0.900969,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.974928 0 0.222521,
+                          0.974928 0 0.222521,
+                          0.781832 0 0.62349,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.781832 0 0.62349,
+                          0.974928 0 0.222521,
+                          0.781832 0 0.62349,
+                          0.974928 0 -0.222521,
+                          0.974928 0 -0.222521,
+                          0.974928 0 0.222521,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.974928 0 0.222521,
+                          0.974928 0 -0.222521,
+                          0.974928 0 0.222521,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.781832 0 -0.62349,
+                          0.781832 0 -0.62349,
+                          0.974928 0 -0.222521,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.974928 0 -0.222521,
+                          0.781832 0 -0.62349,
+                          0.974928 0 -0.222521,
+                          0.433884 0 -0.900969,
+                          0.433884 0 -0.900969,
+                          0.781832 0 -0.62349,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.781832 0 -0.62349,
+                          0.433884 0 -0.900969,
+                          0.781832 0 -0.62349,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          5.11382e-17 0 -1,
+                          5.11382e-17 0 -1,
+                          0.433884 0 -0.900969,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.433884 0 -0.900969,
+                          5.11382e-17 0 -1,
+                          0.433884 0 -0.900969,
+                          -0.433884 0 -0.900969,
+                          -1.93783e-16 0 -1,
+                          -1.93783e-16 0 -1,
+                          -0.433884 0 -0.900969,
+                          -1.93783e-16 0 -1,
+                          -0.433884 0 -0.900969,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.433884 0 0.900969,
+                          -0.433884 0 0.900969,
+                          7.13224e-17 0 1,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -7.13224e-17 0 -1,
+                          -7.13224e-17 0 -1,
+                          0.258819 0 -0.965926,
+                          -0.258819 0 -0.965926,
+                          -0.258819 0 -0.965926,
+                          -7.13224e-17 0 -1,
+                          -7.13224e-17 0 -1,
+                          -0.258819 0 -0.965926,
+                          -7.13224e-17 0 -1,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.258819 0 -0.965926,
+                          0.258819 0 -0.965926,
+                          0.5 0 -0.866025,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.258819 0 -0.965926,
+                          -7.13224e-17 0 -1,
+                          0.258819 0 -0.965926,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.5 0 -0.866025,
+                          0.5 0 -0.866025,
+                          0.707107 0 -0.707107,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.258819 0 -0.965926,
+                          0.5 0 -0.866025,
+                          0.5 0 -0.866025,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          0.866025 0 -0.5,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.5 0 -0.866025,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.866025 0 -0.5,
+                          0.866025 0 -0.5,
+                          0.965926 0 -0.258819,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.707107 0 -0.707107,
+                          0.866025 0 -0.5,
+                          0.866025 0 -0.5,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.965926 0 -0.258819,
+                          0.965926 0 -0.258819,
+                          1 0 -1.32553e-16,
+                          0.866025 0 -0.5,
+                          0.965926 0 -0.258819,
+                          0.965926 0 -0.258819,
+                          1 0 -1.32553e-16,
+                          1 0 -1.32553e-16,
+                          0.965926 0 0.258819,
+                          0.965926 0 -0.258819,
+                          1 0 -1.32553e-16,
+                          1 0 -1.32553e-16,
+                          0.965926 0 0.258819,
+                          0.965926 0 0.258819,
+                          0.866025 0 0.5,
+                          1 0 -1.32553e-16,
+                          0.965926 0 0.258819,
+                          0.965926 0 0.258819,
+                          0.866025 0 0.5,
+                          0.866025 0 0.5,
+                          0.707107 0 0.707107,
+                          0.965926 0 0.258819,
+                          0.866025 0 0.5,
+                          0.866025 0 0.5,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          0.5 0 0.866025,
+                          0.866025 0 0.5,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.5 0 0.866025,
+                          0.5 0 0.866025,
+                          0.258819 0 0.965926,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.707107 0 0.707107,
+                          0.5 0 0.866025,
+                          0.5 0 0.866025,
+                          0.258819 0 0.965926,
+                          0.258819 0 0.965926,
+                          1.93783e-16 0 1,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.5 0 0.866025,
+                          0.258819 0 0.965926,
+                          0.258819 0 0.965926,
+                          -5.11382e-17 0 1,
+                          -5.11382e-17 0 1,
+                          -0.258819 0 0.965926,
+                          0.258819 0 0.965926,
+                          1.93783e-16 0 1,
+                          1.93783e-16 0 1,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.258819 0 0.965926,
+                          -0.258819 0 0.965926,
+                          -0.5 0 0.866025,
+                          -0.258819 0 0.965926,
+                          -5.11382e-17 0 1,
+                          -0.258819 0 0.965926,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.5 0 0.866025,
+                          -0.5 0 0.866025,
+                          -0.707107 0 0.707107,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.5 0 0.866025,
+                          -0.258819 0 0.965926,
+                          -0.5 0 0.866025,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.707107 0 0.707107,
+                          -0.707107 0 0.707107,
+                          -0.866025 0 0.5,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.707107 0 0.707107,
+                          -0.5 0 0.866025,
+                          -0.707107 0 0.707107,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.866025 0 0.5,
+                          -0.866025 0 0.5,
+                          -0.965926 0 0.258819,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.866025 0 0.5,
+                          -0.707107 0 0.707107,
+                          -0.866025 0 0.5,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.965926 0 0.258819,
+                          -0.965926 0 0.258819,
+                          -1 0 1.00921e-17,
+                          -0.965926 0 0.258819,
+                          -0.866025 0 0.5,
+                          -0.965926 0 0.258819,
+                          -1 0 1.00921e-17,
+                          -1 0 1.00921e-17,
+                          -0.965926 0 -0.258819,
+                          -1 0 1.00921e-17,
+                          -0.965926 0 0.258819,
+                          -1 0 1.00921e-17,
+                          -0.965926 0 -0.258819,
+                          -0.965926 0 -0.258819,
+                          -0.866025 0 -0.5,
+                          -0.965926 0 -0.258819,
+                          -1 0 1.00921e-17,
+                          -0.965926 0 -0.258819,
+                          -0.866025 0 -0.5,
+                          -0.866025 0 -0.5,
+                          -0.707107 0 -0.707107,
+                          -0.866025 0 -0.5,
+                          -0.965926 0 -0.258819,
+                          -0.866025 0 -0.5,
+                          -0.707107 0 -0.707107,
+                          -0.707107 0 -0.707107,
+                          -0.5 0 -0.866025,
+                          -0.707107 0 -0.707107,
+                          -0.866025 0 -0.5,
+                          -0.707107 0 -0.707107,
+                          -0.5 0 -0.866025,
+                          -0.5 0 -0.866025,
+                          -0.258819 0 -0.965926,
+                          -0.5 0 -0.866025,
+                          -0.707107 0 -0.707107,
+                          -0.5 0 -0.866025,
+                          -0.258819 0 -0.965926,
+                          -0.5 0 -0.866025,
+                          -0.258819 0 -0.965926,
+                          -0.433884 0 -0.900969,
+                          -0.433884 0 -0.900969,
+                          -0.781832 0 -0.62349,
+                          -0.781832 0 -0.62349,
+                          -0.781832 0 -0.62349,
+                          -0.974928 0 -0.222521,
+                          -0.433884 0 -0.900969,
+                          -0.781832 0 -0.62349,
+                          -0.781832 0 -0.62349,
+                          -0.974928 0 -0.222521,
+                          -0.974928 0 -0.222521,
+                          -0.974928 0 0.222521,
+                          -0.781832 0 -0.62349,
+                          -0.974928 0 -0.222521,
+                          -0.974928 0 -0.222521,
+                          -0.974928 0 0.222521,
+                          -0.974928 0 0.222521,
+                          -0.781832 0 0.62349,
+                          -0.974928 0 -0.222521,
+                          -0.974928 0 0.222521,
+                          -0.974928 0 0.222521,
+                          -0.781832 0 0.62349,
+                          -0.781832 0 0.62349,
+                          -0.433884 0 0.900969,
+                          -0.974928 0 0.222521,
+                          -0.781832 0 0.62349,
+                          -0.781832 0 0.62349,
+                          -0.781832 0 0.62349,
+                          -0.433884 0 0.900969,
+                          -0.433884 0 0.900969,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          7.13224e-17 0 1,
+                          7.13224e-17 0 1,
+                          -0.433884 0 0.900969,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.433884 0 0.900969,
+                          0.433884 0 0.900969,
+                          7.13224e-17 0 1,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          7.13224e-17 0 1,
+                          0.433884 0 0.900969,
+                          7.13224e-17 0 1,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.433884 0 0.900969,
+                          -0.433884 0 0.900969,
+                          -0.781832 0 0.62349,
+                          -0.433884 0 0.900969,
+                          7.13224e-17 0 1,
+                          -0.433884 0 0.900969,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.781832 0 0.62349,
+                          -0.781832 0 0.62349,
+                          -0.974928 0 0.222521,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.433884 0 0.900969,
+                          -0.781832 0 0.62349,
+                          -0.781832 0 0.62349,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.974928 0 0.222521,
+                          -0.974928 0 0.222521,
+                          -0.974928 0 -0.222521,
+                          -0.781832 0 0.62349,
+                          -0.974928 0 0.222521,
+                          -0.974928 0 0.222521,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.974928 0 -0.222521,
+                          -0.974928 0 -0.222521,
+                          -0.781832 0 -0.62349,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.974928 0 0.222521,
+                          -0.974928 0 -0.222521,
+                          -0.974928 0 -0.222521,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.781832 0 -0.62349,
+                          -0.781832 0 -0.62349,
+                          -0.433884 0 -0.900969,
+                          -0.974928 0 -0.222521,
+                          -0.781832 0 -0.62349,
+                          -0.781832 0 -0.62349,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.433884 0 -0.900969,
+                          -0.433884 0 -0.900969,
+                          -1.93783e-16 0 -1,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.781832 0 -0.62349,
+                          -0.433884 0 -0.900969,
+                          -0.433884 0 -0.900969,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          5.11382e-17 0 -1,
+                          5.11382e-17 0 -1,
+                          0.433884 0 -0.900969,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.433884 0 -0.900969,
+                          -1.93783e-16 0 -1,
+                          -1.93783e-16 0 -1,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.433884 0 -0.900969,
+                          0.433884 0 -0.900969,
+                          0.781832 0 -0.62349,
+                          0.433884 0 -0.900969,
+                          5.11382e-17 0 -1,
+                          0.433884 0 -0.900969,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.781832 0 -0.62349,
+                          0.781832 0 -0.62349,
+                          0.974928 0 -0.222521,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.781832 0 -0.62349,
+                          0.433884 0 -0.900969,
+                          0.781832 0 -0.62349,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.974928 0 -0.222521,
+                          0.974928 0 -0.222521,
+                          0.974928 0 0.222521,
+                          0.974928 0 -0.222521,
+                          0.781832 0 -0.62349,
+                          0.974928 0 -0.222521,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.974928 0 0.222521,
+                          0.974928 0 0.222521,
+                          0.781832 0 0.62349,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.974928 0 0.222521,
+                          0.974928 0 -0.222521,
+                          0.974928 0 0.222521,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.781832 0 0.62349,
+                          0.781832 0 0.62349,
+                          0.433884 0 0.900969,
+                          0.781832 0 0.62349,
+                          0.974928 0 0.222521,
+                          0.781832 0 0.62349,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.433884 0 0.900969,
+                          0.781832 0 0.62349,
+                          0.433884 0 0.900969,
+                          -7.13224e-17 0 -1,
+                          -7.13224e-17 0 -1,
+                          -0.258819 0 -0.965926,
+                          0.258819 0 -0.965926,
+                          0.258819 0 -0.965926,
+                          -7.13224e-17 0 -1,
+                          0.258819 0 -0.965926,
+                          -7.13224e-17 0 -1,
+                          -7.13224e-17 0 -1,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.258819 0 -0.965926,
+                          -0.258819 0 -0.965926,
+                          -0.5 0 -0.866025,
+                          -0.258819 0 -0.965926,
+                          -7.13224e-17 0 -1,
+                          -0.258819 0 -0.965926,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.5 0 -0.866025,
+                          -0.5 0 -0.866025,
+                          -0.707107 0 -0.707107,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.258819 0 -0.965926,
+                          -0.5 0 -0.866025,
+                          -0.5 0 -0.866025,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.707107 0 -0.707107,
+                          -0.707107 0 -0.707107,
+                          -0.866025 0 -0.5,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.5 0 -0.866025,
+                          -0.707107 0 -0.707107,
+                          -0.707107 0 -0.707107,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.866025 0 -0.5,
+                          -0.866025 0 -0.5,
+                          -0.965926 0 -0.258819,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.707107 0 -0.707107,
+                          -0.866025 0 -0.5,
+                          -0.866025 0 -0.5,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.965926 0 -0.258819,
+                          -0.965926 0 -0.258819,
+                          -1 0 1.00921e-17,
+                          -0.866025 0 -0.5,
+                          -0.965926 0 -0.258819,
+                          -0.965926 0 -0.258819,
+                          -1 0 1.00921e-17,
+                          -1 0 1.00921e-17,
+                          -0.965926 0 0.258819,
+                          -0.965926 0 -0.258819,
+                          -1 0 1.00921e-17,
+                          -1 0 1.00921e-17,
+                          -0.965926 0 0.258819,
+                          -0.965926 0 0.258819,
+                          -0.866025 0 0.5,
+                          -1 0 1.00921e-17,
+                          -0.965926 0 0.258819,
+                          -0.965926 0 0.258819,
+                          -0.866025 0 0.5,
+                          -0.866025 0 0.5,
+                          -0.707107 0 0.707107,
+                          -0.965926 0 0.258819,
+                          -0.866025 0 0.5,
+                          -0.866025 0 0.5,
+                          -0.707107 0 0.707107,
+                          -0.707107 0 0.707107,
+                          -0.5 0 0.866025,
+                          -0.866025 0 0.5,
+                          -0.707107 0 0.707107,
+                          -0.707107 0 0.707107,
+                          -0.5 0 0.866025,
+                          -0.5 0 0.866025,
+                          -0.258819 0 0.965926,
+                          -0.707107 0 0.707107,
+                          -0.5 0 0.866025,
+                          -0.5 0 0.866025,
+                          -0.258819 0 0.965926,
+                          -0.258819 0 0.965926,
+                          -5.11382e-17 0 1,
+                          -0.5 0 0.866025,
+                          -0.258819 0 0.965926,
+                          -0.258819 0 0.965926,
+                          1.93783e-16 0 1,
+                          1.93783e-16 0 1,
+                          0.258819 0 0.965926,
+                          -0.258819 0 0.965926,
+                          -5.11382e-17 0 1,
+                          -5.11382e-17 0 1,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.258819 0 0.965926,
+                          0.258819 0 0.965926,
+                          0.5 0 0.866025,
+                          1.93783e-16 0 1,
+                          0.258819 0 0.965926,
+                          0.258819 0 0.965926,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.5 0 0.866025,
+                          0.5 0 0.866025,
+                          0.707107 0 0.707107,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.258819 0 0.965926,
+                          0.5 0 0.866025,
+                          0.5 0 0.866025,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          0.866025 0 0.5,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.5 0 0.866025,
+                          0.707107 0 0.707107,
+                          0.707107 0 0.707107,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.866025 0 0.5,
+                          0.866025 0 0.5,
+                          0.965926 0 0.258819,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.707107 0 0.707107,
+                          0.866025 0 0.5,
+                          0.866025 0 0.5,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.965926 0 0.258819,
+                          0.965926 0 0.258819,
+                          1 0 -1.32553e-16,
+                          0.866025 0 0.5,
+                          0.965926 0 0.258819,
+                          0.965926 0 0.258819,
+                          1 0 -1.32553e-16,
+                          1 0 -1.32553e-16,
+                          0.965926 0 -0.258819,
+                          0.965926 0 0.258819,
+                          1 0 -1.32553e-16,
+                          1 0 -1.32553e-16,
+                          0.965926 0 -0.258819,
+                          0.965926 0 -0.258819,
+                          0.866025 0 -0.5,
+                          1 0 -1.32553e-16,
+                          0.965926 0 -0.258819,
+                          0.965926 0 -0.258819,
+                          0.866025 0 -0.5,
+                          0.866025 0 -0.5,
+                          0.707107 0 -0.707107,
+                          0.965926 0 -0.258819,
+                          0.866025 0 -0.5,
+                          0.866025 0 -0.5,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          0.5 0 -0.866025,
+                          0.866025 0 -0.5,
+                          0.707107 0 -0.707107,
+                          0.707107 0 -0.707107,
+                          0.5 0 -0.866025,
+                          0.5 0 -0.866025,
+                          0.258819 0 -0.965926,
+                          0.707107 0 -0.707107,
+                          0.5 0 -0.866025,
+                          0.5 0 -0.866025,
+                          0.5 0 -0.866025,
+                          0.258819 0 -0.965926,
+                          0.258819 0 -0.965926,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -7.13224e-17 0 -1,
+                          -7.13224e-17 0 -1,
+                          0.433884 0 -0.900969,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.433884 0 -0.900969,
+                          -0.433884 0 -0.900969,
+                          -7.13224e-17 0 -1,
+                          -7.13224e-17 0 -1,
+                          -0.433884 0 -0.900969,
+                          -7.13224e-17 0 -1,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.433884 0 -0.900969,
+                          0.433884 0 -0.900969,
+                          0.781832 0 -0.62349,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.433884 0 -0.900969,
+                          -7.13224e-17 0 -1,
+                          0.433884 0 -0.900969,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.781832 0 -0.62349,
+                          0.781832 0 -0.62349,
+                          0.974928 0 -0.222521,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.433884 0 -0.900969,
+                          0.781832 0 -0.62349,
+                          0.781832 0 -0.62349,
+                          0.974928 0 -0.222521,
+                          0.974928 0 -0.222521,
+                          0.974928 0 0.222521,
+                          0.781832 0 -0.62349,
+                          0.974928 0 -0.222521,
+                          0.974928 0 -0.222521,
+                          0.974928 0 0.222521,
+                          0.974928 0 0.222521,
+                          0.781832 0 0.62349,
+                          0.974928 0 -0.222521,
+                          0.974928 0 0.222521,
+                          0.974928 0 0.222521,
+                          0.781832 0 0.62349,
+                          0.781832 0 0.62349,
+                          0.433884 0 0.900969,
+                          0.974928 0 0.222521,
+                          0.781832 0 0.62349,
+                          0.781832 0 0.62349,
+                          0.433884 0 0.900969,
+                          0.433884 0 0.900969,
+                          1.93783e-16 0 1,
+                          0.781832 0 0.62349,
+                          0.433884 0 0.900969,
+                          0.433884 0 0.900969,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -5.11382e-17 0 1,
+                          -5.11382e-17 0 1,
+                          -0.433884 0 0.900969,
+                          0.433884 0 0.900969,
+                          1.93783e-16 0 1,
+                          1.93783e-16 0 1,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.433884 0 0.900969,
+                          -0.433884 0 0.900969,
+                          -0.781832 0 0.62349,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.433884 0 0.900969,
+                          -5.11382e-17 0 1,
+                          -0.433884 0 0.900969,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.781832 0 0.62349,
+                          -0.781832 0 0.62349,
+                          -0.974928 0 0.222521,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.781832 0 0.62349,
+                          -0.433884 0 0.900969,
+                          -0.781832 0 0.62349,
+                          -0.974928 0 0.222521,
+                          -0.974928 0 0.222521,
+                          -0.974928 0 -0.222521,
+                          -0.974928 0 0.222521,
+                          -0.781832 0 0.62349,
+                          -0.974928 0 0.222521,
+                          -0.974928 0 -0.222521,
+                          -0.974928 0 -0.222521,
+                          -0.781832 0 -0.62349,
+                          -0.974928 0 -0.222521,
+                          -0.974928 0 0.222521,
+                          -0.974928 0 -0.222521,
+                          -0.781832 0 -0.62349,
+                          -0.781832 0 -0.62349,
+                          -0.433884 0 -0.900969,
+                          -0.781832 0 -0.62349,
+                          -0.974928 0 -0.222521,
+                          -0.781832 0 -0.62349,
+                          -0.433884 0 -0.900969,
+                          -0.781832 0 -0.62349,
+                          -0.433884 0 -0.900969,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -7.13224e-17 0 -1,
+                          -7.13224e-17 0 -1,
+                          0.309017 0 -0.951057,
+                          -0.309017 0 -0.951057,
+                          -0.309017 0 -0.951057,
+                          -7.13224e-17 0 -1,
+                          -7.13224e-17 0 -1,
+                          -0.309017 0 -0.951057,
+                          -7.13224e-17 0 -1,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.309017 0 -0.951057,
+                          0.309017 0 -0.951057,
+                          0.587785 0 -0.809017,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.309017 0 -0.951057,
+                          -7.13224e-17 0 -1,
+                          0.309017 0 -0.951057,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.587785 0 -0.809017,
+                          0.587785 0 -0.809017,
+                          0.809017 0 -0.587785,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.309017 0 -0.951057,
+                          0.587785 0 -0.809017,
+                          0.587785 0 -0.809017,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.809017 0 -0.587785,
+                          0.809017 0 -0.587785,
+                          0.951057 0 -0.309017,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.587785 0 -0.809017,
+                          0.809017 0 -0.587785,
+                          0.809017 0 -0.587785,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.951057 0 -0.309017,
+                          0.951057 0 -0.309017,
+                          1 0 -1.32553e-16,
+                          0.809017 0 -0.587785,
+                          0.951057 0 -0.309017,
+                          0.951057 0 -0.309017,
+                          1 0 -1.32553e-16,
+                          1 0 -1.32553e-16,
+                          0.951057 0 0.309017,
+                          0.951057 0 -0.309017,
+                          1 0 -1.32553e-16,
+                          1 0 -1.32553e-16,
+                          0.951057 0 0.309017,
+                          0.951057 0 0.309017,
+                          0.809017 0 0.587785,
+                          1 0 -1.32553e-16,
+                          0.951057 0 0.309017,
+                          0.951057 0 0.309017,
+                          0.809017 0 0.587785,
+                          0.809017 0 0.587785,
+                          0.587785 0 0.809017,
+                          0.951057 0 0.309017,
+                          0.809017 0 0.587785,
+                          0.809017 0 0.587785,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.587785 0 0.809017,
+                          0.587785 0 0.809017,
+                          0.309017 0 0.951057,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.809017 0 0.587785,
+                          0.587785 0 0.809017,
+                          0.587785 0 0.809017,
+                          0.309017 0 0.951057,
+                          0.309017 0 0.951057,
+                          1.93783e-16 0 1,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.587785 0 0.809017,
+                          0.309017 0 0.951057,
+                          0.309017 0 0.951057,
+                          -5.11382e-17 0 1,
+                          -5.11382e-17 0 1,
+                          -0.309017 0 0.951057,
+                          0.309017 0 0.951057,
+                          1.93783e-16 0 1,
+                          1.93783e-16 0 1,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.309017 0 0.951057,
+                          -0.309017 0 0.951057,
+                          -0.587785 0 0.809017,
+                          -0.309017 0 0.951057,
+                          -5.11382e-17 0 1,
+                          -0.309017 0 0.951057,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.587785 0 0.809017,
+                          -0.587785 0 0.809017,
+                          -0.809017 0 0.587785,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.587785 0 0.809017,
+                          -0.309017 0 0.951057,
+                          -0.587785 0 0.809017,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.809017 0 0.587785,
+                          -0.809017 0 0.587785,
+                          -0.951057 0 0.309017,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.809017 0 0.587785,
+                          -0.587785 0 0.809017,
+                          -0.809017 0 0.587785,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.951057 0 0.309017,
+                          -0.951057 0 0.309017,
+                          -1 0 1.00921e-17,
+                          -0.951057 0 0.309017,
+                          -0.809017 0 0.587785,
+                          -0.951057 0 0.309017,
+                          -1 0 1.00921e-17,
+                          -1 0 1.00921e-17,
+                          -0.951057 0 -0.309017,
+                          -1 0 1.00921e-17,
+                          -0.951057 0 0.309017,
+                          -1 0 1.00921e-17,
+                          -0.951057 0 -0.309017,
+                          -0.951057 0 -0.309017,
+                          -0.809017 0 -0.587785,
+                          -0.951057 0 -0.309017,
+                          -1 0 1.00921e-17,
+                          -0.951057 0 -0.309017,
+                          -0.809017 0 -0.587785,
+                          -0.809017 0 -0.587785,
+                          -0.587785 0 -0.809017,
+                          -0.809017 0 -0.587785,
+                          -0.951057 0 -0.309017,
+                          -0.809017 0 -0.587785,
+                          -0.587785 0 -0.809017,
+                          -0.587785 0 -0.809017,
+                          -0.309017 0 -0.951057,
+                          -0.587785 0 -0.809017,
+                          -0.809017 0 -0.587785,
+                          -0.587785 0 -0.809017,
+                          -0.309017 0 -0.951057,
+                          -0.587785 0 -0.809017,
+                          -0.309017 0 -0.951057,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -7.13224e-17 0 -1,
+                          -7.13224e-17 0 -1,
+                          0.433884 0 -0.900969,
+                          -0.433884 0 -0.900969,
+                          -0.433884 0 -0.900969,
+                          -7.13224e-17 0 -1,
+                          -7.13224e-17 0 -1,
+                          -0.433884 0 -0.900969,
+                          -7.13224e-17 0 -1,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.433884 0 -0.900969,
+                          0.433884 0 -0.900969,
+                          0.781832 0 -0.62349,
+                          0.433884 0 -0.900969,
+                          -7.13224e-17 0 -1,
+                          0.433884 0 -0.900969,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.781832 0 -0.62349,
+                          0.781832 0 -0.62349,
+                          0.974928 0 -0.222521,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.433884 0 -0.900969,
+                          0.781832 0 -0.62349,
+                          0.781832 0 -0.62349,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.974928 0 -0.222521,
+                          0.974928 0 -0.222521,
+                          0.974928 0 0.222521,
+                          0.781832 0 -0.62349,
+                          0.974928 0 -0.222521,
+                          0.974928 0 -0.222521,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.974928 0 0.222521,
+                          0.974928 0 0.222521,
+                          0.781832 0 0.62349,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.974928 0 -0.222521,
+                          0.974928 0 0.222521,
+                          0.974928 0 0.222521,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.781832 0 0.62349,
+                          0.781832 0 0.62349,
+                          0.433884 0 0.900969,
+                          0.974928 0 0.222521,
+                          0.781832 0 0.62349,
+                          0.781832 0 0.62349,
+                          0.433884 0 0.900969,
+                          0.433884 0 0.900969,
+                          1.93783e-16 0 1,
+                          0.781832 0 0.62349,
+                          0.433884 0 0.900969,
+                          0.433884 0 0.900969,
+                          -5.11382e-17 0 1,
+                          -5.11382e-17 0 1,
+                          -0.433884 0 0.900969,
+                          0.433884 0 0.900969,
+                          1.93783e-16 0 1,
+                          1.93783e-16 0 1,
+                          -0.433884 0 0.900969,
+                          -0.433884 0 0.900969,
+                          -0.781832 0 0.62349,
+                          -0.433884 0 0.900969,
+                          -5.11382e-17 0 1,
+                          -0.433884 0 0.900969,
+                          -0.781832 0 0.62349,
+                          -0.781832 0 0.62349,
+                          -0.974928 0 0.222521,
+                          -0.781832 0 0.62349,
+                          -0.433884 0 0.900969,
+                          -0.781832 0 0.62349,
+                          -0.974928 0 0.222521,
+                          -0.974928 0 0.222521,
+                          -0.974928 0 -0.222521,
+                          -0.974928 0 0.222521,
+                          -0.781832 0 0.62349,
+                          -0.974928 0 0.222521,
+                          -0.974928 0 -0.222521,
+                          -0.974928 0 -0.222521,
+                          -0.781832 0 -0.62349,
+                          -0.974928 0 -0.222521,
+                          -0.974928 0 0.222521,
+                          -0.974928 0 -0.222521,
+                          -0.781832 0 -0.62349,
+                          -0.781832 0 -0.62349,
+                          -0.433884 0 -0.900969,
+                          -0.781832 0 -0.62349,
+                          -0.974928 0 -0.222521,
+                          -0.781832 0 -0.62349,
+                          -0.433884 0 -0.900969,
+                          -0.781832 0 -0.62349,
+                          -0.433884 0 -0.900969,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -4.12237 208.8 -8.55894,
+                          -4.12237 188 -8.55894,
+                          4.85819e-16 188 -9.5,
+                          1.43188e-15 188 -28,
+                          4.85819e-16 188 -9.5,
+                          -4.12237 188 -8.55894,
+                          4.85819e-16 208.8 -9.5,
+                          -4.12237 208.8 -8.55894,
+                          4.85819e-16 188 -9.5,
+                          4.12237 188 -8.55894,
+                          4.85819e-16 208.8 -9.5,
+                          4.85819e-16 188 -9.5,
+                          7.24644 188 -27.046,
+                          4.85819e-16 188 -9.5,
+                          1.43188e-15 188 -28,
+                          7.24644 188 -27.046,
+                          4.12237 188 -8.55894,
+                          4.85819e-16 188 -9.5,
+                          -7.42766 208.8 -5.92268,
+                          -7.42766 188 -5.92268,
+                          -4.12237 188 -8.55894,
+                          -7.24644 188 -27.046,
+                          -4.12237 188 -8.55894,
+                          -7.42766 188 -5.92268,
+                          -4.12237 208.8 -8.55894,
+                          -7.42766 208.8 -5.92268,
+                          -4.12237 188 -8.55894,
+                          1.43188e-15 188 -28,
+                          -4.12237 188 -8.55894,
+                          -7.24644 188 -27.046,
+                          -9.26174 208.8 -2.11371,
+                          -9.26174 188 -2.11371,
+                          -7.42766 188 -5.92268,
+                          -7.24644 188 -27.046,
+                          -7.42766 188 -5.92268,
+                          -9.26174 188 -2.11371,
+                          -7.42766 208.8 -5.92268,
+                          -9.26174 208.8 -2.11371,
+                          -7.42766 188 -5.92268,
+                          -9.26174 208.8 2.11371,
+                          -9.26174 188 2.11371,
+                          -9.26174 188 -2.11371,
+                          -14.0004 188 24.2484,
+                          -9.26174 188 -2.11371,
+                          -9.26174 188 2.11371,
+                          -9.26174 208.8 -2.11371,
+                          -9.26174 208.8 2.11371,
+                          -9.26174 188 -2.11371,
+                          -7.24644 188 -27.046,
+                          -9.26174 188 -2.11371,
+                          -14.0004 188 24.2484,
+                          -7.42766 208.8 5.92268,
+                          -7.42766 188 5.92268,
+                          -9.26174 188 2.11371,
+                          -14.0004 188 24.2484,
+                          -9.26174 188 2.11371,
+                          -7.42766 188 5.92268,
+                          -9.26174 208.8 2.11371,
+                          -7.42766 208.8 5.92268,
+                          -9.26174 188 2.11371,
+                          -4.12237 208.8 8.55894,
+                          -4.12237 188 8.55894,
+                          -7.42766 188 5.92268,
+                          -7.24644 188 27.046,
+                          -7.42766 188 5.92268,
+                          -4.12237 188 8.55894,
+                          -7.42766 208.8 5.92268,
+                          -4.12237 208.8 8.55894,
+                          -7.42766 188 5.92268,
+                          -14.0004 188 24.2484,
+                          -7.42766 188 5.92268,
+                          -7.24644 188 27.046,
+                          -4.85807e-16 208.8 9.5,
+                          -4.85807e-16 188 9.5,
+                          -4.12237 188 8.55894,
+                          -7.24644 188 27.046,
+                          -4.12237 188 8.55894,
+                          -4.85807e-16 188 9.5,
+                          -4.12237 208.8 8.55894,
+                          -4.85807e-16 208.8 9.5,
+                          -4.12237 188 8.55894,
+                          4.12237 208.8 8.55894,
+                          -4.85807e-16 188 9.5,
+                          -4.85807e-16 208.8 9.5,
+                          4.12237 188 8.55894,
+                          -4.85807e-16 188 9.5,
+                          4.12237 208.8 8.55894,
+                          -7.24644 188 27.046,
+                          -4.85807e-16 188 9.5,
+                          -1.43186e-15 188 28,
+                          4.12237 188 8.55894,
+                          -1.43186e-15 188 28,
+                          -4.85807e-16 188 9.5,
+                          -1.43186e-15 208.8 28,
+                          -4.85807e-16 208.8 9.5,
+                          -4.12237 208.8 8.55894,
+                          -1.43186e-15 208.8 28,
+                          7.24644 208.8 27.046,
+                          -4.85807e-16 208.8 9.5,
+                          4.12237 208.8 8.55894,
+                          -4.85807e-16 208.8 9.5,
+                          7.24644 208.8 27.046,
+                          -7.24644 208.8 27.046,
+                          -4.12237 208.8 8.55894,
+                          -7.42766 208.8 5.92268,
+                          -7.24644 208.8 27.046,
+                          -1.43186e-15 208.8 28,
+                          -4.12237 208.8 8.55894,
+                          -7.24644 208.8 27.046,
+                          -7.42766 208.8 5.92268,
+                          -9.26174 208.8 2.11371,
+                          -14.0004 208.8 -24.2484,
+                          -9.26174 208.8 2.11371,
+                          -9.26174 208.8 -2.11371,
+                          -14.0004 208.8 -24.2484,
+                          -7.24644 208.8 27.046,
+                          -9.26174 208.8 2.11371,
+                          -14.0004 208.8 -24.2484,
+                          -9.26174 208.8 -2.11371,
+                          -7.42766 208.8 -5.92268,
+                          -7.24644 208.8 -27.046,
+                          -7.42766 208.8 -5.92268,
+                          -4.12237 208.8 -8.55894,
+                          -7.24644 208.8 -27.046,
+                          -14.0004 208.8 -24.2484,
+                          -7.42766 208.8 -5.92268,
+                          -7.24644 208.8 -27.046,
+                          -4.12237 208.8 -8.55894,
+                          4.85819e-16 208.8 -9.5,
+                          -7.24644 208.8 -27.046,
+                          4.85819e-16 208.8 -9.5,
+                          1.43188e-15 208.8 -28,
+                          4.12237 208.8 -8.55894,
+                          1.43188e-15 208.8 -28,
+                          4.85819e-16 208.8 -9.5,
+                          4.12237 188 -8.55894,
+                          4.12237 208.8 -8.55894,
+                          4.85819e-16 208.8 -9.5,
+                          4.12237 208.8 -8.55894,
+                          7.24644 208.8 -27.046,
+                          1.43188e-15 208.8 -28,
+                          1.43188e-15 188 -28,
+                          1.43188e-15 208.8 -28,
+                          7.24644 208.8 -27.046,
+                          -7.24644 188 -27.046,
+                          -7.24644 208.8 -27.046,
+                          1.43188e-15 208.8 -28,
+                          1.43188e-15 188 -28,
+                          -7.24644 188 -27.046,
+                          1.43188e-15 208.8 -28,
+                          14.0004 208.8 24.2484,
+                          14.0004 208.8 -24.2484,
+                          7.24644 208.8 -27.046,
+                          7.24644 188 -27.046,
+                          7.24644 208.8 -27.046,
+                          14.0004 208.8 -24.2484,
+                          9.26174 208.8 -2.11371,
+                          14.0004 208.8 24.2484,
+                          7.24644 208.8 -27.046,
+                          7.42766 208.8 -5.92268,
+                          9.26174 208.8 -2.11371,
+                          7.24644 208.8 -27.046,
+                          4.12237 208.8 -8.55894,
+                          7.42766 208.8 -5.92268,
+                          7.24644 208.8 -27.046,
+                          7.24644 188 -27.046,
+                          1.43188e-15 188 -28,
+                          7.24644 208.8 -27.046,
+                          19.799 208.8 19.799,
+                          19.799 208.8 -19.799,
+                          14.0004 208.8 -24.2484,
+                          14.0004 188 -24.2484,
+                          14.0004 208.8 -24.2484,
+                          19.799 208.8 -19.799,
+                          14.0004 208.8 24.2484,
+                          19.799 208.8 19.799,
+                          14.0004 208.8 -24.2484,
+                          7.24644 188 -27.046,
+                          14.0004 208.8 -24.2484,
+                          14.0004 188 -24.2484,
+                          24.2484 208.8 14.0004,
+                          24.2484 208.8 -14.0004,
+                          19.799 208.8 -19.799,
+                          19.799 188 -19.799,
+                          19.799 208.8 -19.799,
+                          24.2484 208.8 -14.0004,
+                          19.799 208.8 19.799,
+                          24.2484 208.8 14.0004,
+                          19.799 208.8 -19.799,
+                          14.0004 188 -24.2484,
+                          19.799 208.8 -19.799,
+                          19.799 188 -19.799,
+                          27.046 208.8 7.24644,
+                          27.046 208.8 -7.24644,
+                          24.2484 208.8 -14.0004,
+                          24.2484 188 -14.0004,
+                          24.2484 208.8 -14.0004,
+                          27.046 208.8 -7.24644,
+                          24.2484 208.8 14.0004,
+                          27.046 208.8 7.24644,
+                          24.2484 208.8 -14.0004,
+                          19.799 188 -19.799,
+                          24.2484 208.8 -14.0004,
+                          24.2484 188 -14.0004,
+                          27.046 208.8 7.24644,
+                          28 208.8 -2.82579e-16,
+                          27.046 208.8 -7.24644,
+                          27.046 188 -7.24644,
+                          27.046 208.8 -7.24644,
+                          28 208.8 -2.82579e-16,
+                          24.2484 188 -14.0004,
+                          27.046 208.8 -7.24644,
+                          27.046 188 -7.24644,
+                          28 188 -2.82579e-16,
+                          28 208.8 -2.82579e-16,
+                          27.046 208.8 7.24644,
+                          27.046 188 -7.24644,
+                          28 208.8 -2.82579e-16,
+                          28 188 -2.82579e-16,
+                          27.046 188 7.24644,
+                          27.046 208.8 7.24644,
+                          24.2484 208.8 14.0004,
+                          28 188 -2.82579e-16,
+                          27.046 208.8 7.24644,
+                          27.046 188 7.24644,
+                          24.2484 188 14.0004,
+                          24.2484 208.8 14.0004,
+                          19.799 208.8 19.799,
+                          27.046 188 7.24644,
+                          24.2484 208.8 14.0004,
+                          24.2484 188 14.0004,
+                          19.799 188 19.799,
+                          19.799 208.8 19.799,
+                          14.0004 208.8 24.2484,
+                          24.2484 188 14.0004,
+                          19.799 208.8 19.799,
+                          19.799 188 19.799,
+                          7.42766 208.8 5.92268,
+                          7.24644 208.8 27.046,
+                          14.0004 208.8 24.2484,
+                          14.0004 188 24.2484,
+                          14.0004 208.8 24.2484,
+                          7.24644 208.8 27.046,
+                          9.26174 208.8 2.11371,
+                          7.42766 208.8 5.92268,
+                          14.0004 208.8 24.2484,
+                          9.26174 208.8 -2.11371,
+                          9.26174 208.8 2.11371,
+                          14.0004 208.8 24.2484,
+                          19.799 188 19.799,
+                          14.0004 208.8 24.2484,
+                          14.0004 188 24.2484,
+                          7.24644 188 27.046,
+                          7.24644 208.8 27.046,
+                          -1.43186e-15 208.8 28,
+                          7.42766 208.8 5.92268,
+                          4.12237 208.8 8.55894,
+                          7.24644 208.8 27.046,
+                          14.0004 188 24.2484,
+                          7.24644 208.8 27.046,
+                          7.24644 188 27.046,
+                          -1.43186e-15 188 28,
+                          -1.43186e-15 208.8 28,
+                          -7.24644 208.8 27.046,
+                          7.24644 188 27.046,
+                          -1.43186e-15 208.8 28,
+                          -1.43186e-15 188 28,
+                          -14.0004 208.8 -24.2484,
+                          -14.0004 208.8 24.2484,
+                          -7.24644 208.8 27.046,
+                          -7.24644 188 27.046,
+                          -7.24644 208.8 27.046,
+                          -14.0004 208.8 24.2484,
+                          -7.24644 188 27.046,
+                          -1.43186e-15 188 28,
+                          -7.24644 208.8 27.046,
+                          -19.799 208.8 -19.799,
+                          -19.799 208.8 19.799,
+                          -14.0004 208.8 24.2484,
+                          -14.0004 188 24.2484,
+                          -14.0004 208.8 24.2484,
+                          -19.799 208.8 19.799,
+                          -14.0004 208.8 -24.2484,
+                          -19.799 208.8 -19.799,
+                          -14.0004 208.8 24.2484,
+                          -14.0004 188 24.2484,
+                          -7.24644 188 27.046,
+                          -14.0004 208.8 24.2484,
+                          -24.2484 208.8 -14.0004,
+                          -24.2484 208.8 14.0004,
+                          -19.799 208.8 19.799,
+                          -19.799 188 19.799,
+                          -19.799 208.8 19.799,
+                          -24.2484 208.8 14.0004,
+                          -19.799 208.8 -19.799,
+                          -24.2484 208.8 -14.0004,
+                          -19.799 208.8 19.799,
+                          -19.799 188 19.799,
+                          -14.0004 188 24.2484,
+                          -19.799 208.8 19.799,
+                          -27.046 208.8 -7.24644,
+                          -27.046 208.8 7.24644,
+                          -24.2484 208.8 14.0004,
+                          -24.2484 188 14.0004,
+                          -24.2484 208.8 14.0004,
+                          -27.046 208.8 7.24644,
+                          -24.2484 208.8 -14.0004,
+                          -27.046 208.8 -7.24644,
+                          -24.2484 208.8 14.0004,
+                          -24.2484 188 14.0004,
+                          -19.799 188 19.799,
+                          -24.2484 208.8 14.0004,
+                          -27.046 208.8 -7.24644,
+                          -28 208.8 -3.14632e-15,
+                          -27.046 208.8 7.24644,
+                          -27.046 188 7.24644,
+                          -27.046 208.8 7.24644,
+                          -28 208.8 -3.14632e-15,
+                          -27.046 188 7.24644,
+                          -24.2484 188 14.0004,
+                          -27.046 208.8 7.24644,
+                          -28 188 -3.14632e-15,
+                          -28 208.8 -3.14632e-15,
+                          -27.046 208.8 -7.24644,
+                          -28 188 -3.14632e-15,
+                          -27.046 188 7.24644,
+                          -28 208.8 -3.14632e-15,
+                          -27.046 188 -7.24644,
+                          -27.046 208.8 -7.24644,
+                          -24.2484 208.8 -14.0004,
+                          -27.046 188 -7.24644,
+                          -28 188 -3.14632e-15,
+                          -27.046 208.8 -7.24644,
+                          -24.2484 188 -14.0004,
+                          -24.2484 208.8 -14.0004,
+                          -19.799 208.8 -19.799,
+                          -24.2484 188 -14.0004,
+                          -27.046 188 -7.24644,
+                          -24.2484 208.8 -14.0004,
+                          -19.799 188 -19.799,
+                          -19.799 208.8 -19.799,
+                          -14.0004 208.8 -24.2484,
+                          -19.799 188 -19.799,
+                          -24.2484 188 -14.0004,
+                          -19.799 208.8 -19.799,
+                          -14.0004 188 -24.2484,
+                          -14.0004 208.8 -24.2484,
+                          -7.24644 208.8 -27.046,
+                          -14.0004 188 -24.2484,
+                          -19.799 188 -19.799,
+                          -14.0004 208.8 -24.2484,
+                          -7.24644 188 -27.046,
+                          -14.0004 188 -24.2484,
+                          -7.24644 208.8 -27.046,
+                          4.12237 188 8.55894,
+                          4.12237 208.8 8.55894,
+                          7.42766 208.8 5.92268,
+                          7.42766 188 5.92268,
+                          7.42766 208.8 5.92268,
+                          9.26174 208.8 2.11371,
+                          4.12237 188 8.55894,
+                          7.42766 208.8 5.92268,
+                          7.42766 188 5.92268,
+                          9.26174 188 2.11371,
+                          9.26174 208.8 2.11371,
+                          9.26174 208.8 -2.11371,
+                          7.42766 188 5.92268,
+                          9.26174 208.8 2.11371,
+                          9.26174 188 2.11371,
+                          9.26174 188 -2.11371,
+                          9.26174 208.8 -2.11371,
+                          7.42766 208.8 -5.92268,
+                          9.26174 188 2.11371,
+                          9.26174 208.8 -2.11371,
+                          9.26174 188 -2.11371,
+                          7.42766 188 -5.92268,
+                          7.42766 208.8 -5.92268,
+                          4.12237 208.8 -8.55894,
+                          9.26174 188 -2.11371,
+                          7.42766 208.8 -5.92268,
+                          7.42766 188 -5.92268,
+                          7.42766 188 -5.92268,
+                          4.12237 208.8 -8.55894,
+                          4.12237 188 -8.55894,
+                          7.24644 188 27.046,
+                          -1.43186e-15 188 28,
+                          4.12237 188 8.55894,
+                          -14.0004 188 -24.2484,
+                          -14.0004 188 24.2484,
+                          -19.799 188 19.799,
+                          -7.24644 188 -27.046,
+                          -14.0004 188 24.2484,
+                          -14.0004 188 -24.2484,
+                          -19.799 188 -19.799,
+                          -19.799 188 19.799,
+                          -24.2484 188 14.0004,
+                          -14.0004 188 -24.2484,
+                          -19.799 188 19.799,
+                          -19.799 188 -19.799,
+                          -24.2484 188 -14.0004,
+                          -24.2484 188 14.0004,
+                          -27.046 188 7.24644,
+                          -19.799 188 -19.799,
+                          -24.2484 188 14.0004,
+                          -24.2484 188 -14.0004,
+                          -27.046 188 -7.24644,
+                          -27.046 188 7.24644,
+                          -28 188 -3.14632e-15,
+                          -24.2484 188 -14.0004,
+                          -27.046 188 7.24644,
+                          -27.046 188 -7.24644,
+                          7.24644 188 -27.046,
+                          7.42766 188 -5.92268,
+                          4.12237 188 -8.55894,
+                          14.0004 188 -24.2484,
+                          9.26174 188 -2.11371,
+                          7.42766 188 -5.92268,
+                          7.24644 188 -27.046,
+                          14.0004 188 -24.2484,
+                          7.42766 188 -5.92268,
+                          14.0004 188 -24.2484,
+                          9.26174 188 2.11371,
+                          9.26174 188 -2.11371,
+                          7.24644 188 27.046,
+                          7.42766 188 5.92268,
+                          9.26174 188 2.11371,
+                          14.0004 188 -24.2484,
+                          7.24644 188 27.046,
+                          9.26174 188 2.11371,
+                          7.24644 188 27.046,
+                          4.12237 188 8.55894,
+                          7.42766 188 5.92268,
+                          14.0004 188 -24.2484,
+                          14.0004 188 24.2484,
+                          7.24644 188 27.046,
+                          19.799 188 -19.799,
+                          19.799 188 19.799,
+                          14.0004 188 24.2484,
+                          14.0004 188 -24.2484,
+                          19.799 188 -19.799,
+                          14.0004 188 24.2484,
+                          24.2484 188 -14.0004,
+                          24.2484 188 14.0004,
+                          19.799 188 19.799,
+                          19.799 188 -19.799,
+                          24.2484 188 -14.0004,
+                          19.799 188 19.799,
+                          27.046 188 -7.24644,
+                          27.046 188 7.24644,
+                          24.2484 188 14.0004,
+                          24.2484 188 -14.0004,
+                          27.046 188 -7.24644,
+                          24.2484 188 14.0004,
+                          27.046 188 -7.24644,
+                          28 188 -2.82579e-16,
+                          27.046 188 7.24644,
+                          7.24644 215.8 -27.046,
+                          4.12237 215.8 -8.55894,
+                          4.85819e-16 215.8 -9.5,
+                          4.85819e-16 219.8 -9.5,
+                          4.85819e-16 215.8 -9.5,
+                          4.12237 215.8 -8.55894,
+                          1.43188e-15 215.8 -28,
+                          4.85819e-16 215.8 -9.5,
+                          -4.12237 215.8 -8.55894,
+                          -4.12237 219.8 -8.55894,
+                          -4.12237 215.8 -8.55894,
+                          4.85819e-16 215.8 -9.5,
+                          7.24644 215.8 -27.046,
+                          4.85819e-16 215.8 -9.5,
+                          1.43188e-15 215.8 -28,
+                          4.85819e-16 219.8 -9.5,
+                          -4.12237 219.8 -8.55894,
+                          4.85819e-16 215.8 -9.5,
+                          7.24644 215.8 -27.046,
+                          7.42766 215.8 -5.92268,
+                          4.12237 215.8 -8.55894,
+                          4.12237 219.8 -8.55894,
+                          4.12237 215.8 -8.55894,
+                          7.42766 215.8 -5.92268,
+                          4.12237 219.8 -8.55894,
+                          4.85819e-16 219.8 -9.5,
+                          4.12237 215.8 -8.55894,
+                          14.0004 215.8 -24.2484,
+                          9.26174 215.8 -2.11371,
+                          7.42766 215.8 -5.92268,
+                          7.42766 219.8 -5.92268,
+                          7.42766 215.8 -5.92268,
+                          9.26174 215.8 -2.11371,
+                          7.24644 215.8 -27.046,
+                          14.0004 215.8 -24.2484,
+                          7.42766 215.8 -5.92268,
+                          4.12237 219.8 -8.55894,
+                          7.42766 215.8 -5.92268,
+                          7.42766 219.8 -5.92268,
+                          14.0004 215.8 -24.2484,
+                          9.26174 215.8 2.11371,
+                          9.26174 215.8 -2.11371,
+                          9.26174 219.8 -2.11371,
+                          9.26174 215.8 -2.11371,
+                          9.26174 215.8 2.11371,
+                          7.42766 219.8 -5.92268,
+                          9.26174 215.8 -2.11371,
+                          9.26174 219.8 -2.11371,
+                          7.24644 215.8 27.046,
+                          7.42766 215.8 5.92268,
+                          9.26174 215.8 2.11371,
+                          9.26174 219.8 2.11371,
+                          9.26174 215.8 2.11371,
+                          7.42766 215.8 5.92268,
+                          14.0004 215.8 -24.2484,
+                          7.24644 215.8 27.046,
+                          9.26174 215.8 2.11371,
+                          9.26174 219.8 -2.11371,
+                          9.26174 215.8 2.11371,
+                          9.26174 219.8 2.11371,
+                          7.24644 215.8 27.046,
+                          4.12237 215.8 8.55894,
+                          7.42766 215.8 5.92268,
+                          7.42766 219.8 5.92268,
+                          7.42766 215.8 5.92268,
+                          4.12237 215.8 8.55894,
+                          9.26174 219.8 2.11371,
+                          7.42766 215.8 5.92268,
+                          7.42766 219.8 5.92268,
+                          -1.43186e-15 215.8 28,
+                          -4.85807e-16 215.8 9.5,
+                          4.12237 215.8 8.55894,
+                          4.12237 219.8 8.55894,
+                          4.12237 215.8 8.55894,
+                          -4.85807e-16 215.8 9.5,
+                          7.24644 215.8 27.046,
+                          -1.43186e-15 215.8 28,
+                          4.12237 215.8 8.55894,
+                          7.42766 219.8 5.92268,
+                          4.12237 215.8 8.55894,
+                          4.12237 219.8 8.55894,
+                          -7.24644 215.8 27.046,
+                          -4.12237 215.8 8.55894,
+                          -4.85807e-16 215.8 9.5,
+                          -4.85807e-16 219.8 9.5,
+                          -4.85807e-16 215.8 9.5,
+                          -4.12237 215.8 8.55894,
+                          -1.43186e-15 215.8 28,
+                          -7.24644 215.8 27.046,
+                          -4.85807e-16 215.8 9.5,
+                          4.12237 219.8 8.55894,
+                          -4.85807e-16 215.8 9.5,
+                          -4.85807e-16 219.8 9.5,
+                          -7.24644 215.8 27.046,
+                          -7.42766 215.8 5.92268,
+                          -4.12237 215.8 8.55894,
+                          -4.12237 219.8 8.55894,
+                          -4.12237 215.8 8.55894,
+                          -7.42766 215.8 5.92268,
+                          -4.12237 219.8 8.55894,
+                          -4.85807e-16 219.8 9.5,
+                          -4.12237 215.8 8.55894,
+                          -14.0004 215.8 24.2484,
+                          -9.26174 215.8 2.11371,
+                          -7.42766 215.8 5.92268,
+                          -7.42766 219.8 5.92268,
+                          -7.42766 215.8 5.92268,
+                          -9.26174 215.8 2.11371,
+                          -7.24644 215.8 27.046,
+                          -14.0004 215.8 24.2484,
+                          -7.42766 215.8 5.92268,
+                          -7.42766 219.8 5.92268,
+                          -4.12237 219.8 8.55894,
+                          -7.42766 215.8 5.92268,
+                          -14.0004 215.8 24.2484,
+                          -9.26174 215.8 -2.11371,
+                          -9.26174 215.8 2.11371,
+                          -9.26174 219.8 2.11371,
+                          -9.26174 215.8 2.11371,
+                          -9.26174 215.8 -2.11371,
+                          -9.26174 219.8 2.11371,
+                          -7.42766 219.8 5.92268,
+                          -9.26174 215.8 2.11371,
+                          -7.24644 215.8 -27.046,
+                          -7.42766 215.8 -5.92268,
+                          -9.26174 215.8 -2.11371,
+                          -9.26174 219.8 -2.11371,
+                          -9.26174 215.8 -2.11371,
+                          -7.42766 215.8 -5.92268,
+                          -14.0004 215.8 24.2484,
+                          -7.24644 215.8 -27.046,
+                          -9.26174 215.8 -2.11371,
+                          -9.26174 219.8 -2.11371,
+                          -9.26174 219.8 2.11371,
+                          -9.26174 215.8 -2.11371,
+                          -7.24644 215.8 -27.046,
+                          -4.12237 215.8 -8.55894,
+                          -7.42766 215.8 -5.92268,
+                          -7.42766 219.8 -5.92268,
+                          -7.42766 215.8 -5.92268,
+                          -4.12237 215.8 -8.55894,
+                          -7.42766 219.8 -5.92268,
+                          -9.26174 219.8 -2.11371,
+                          -7.42766 215.8 -5.92268,
+                          -7.24644 215.8 -27.046,
+                          1.43188e-15 215.8 -28,
+                          -4.12237 215.8 -8.55894,
+                          -4.12237 219.8 -8.55894,
+                          -7.42766 219.8 -5.92268,
+                          -4.12237 215.8 -8.55894,
+                          1.43188e-15 219.8 -28,
+                          1.43188e-15 215.8 -28,
+                          -7.24644 215.8 -27.046,
+                          7.24644 219.8 -27.046,
+                          7.24644 215.8 -27.046,
+                          1.43188e-15 215.8 -28,
+                          7.24644 219.8 -27.046,
+                          1.43188e-15 215.8 -28,
+                          1.43188e-15 219.8 -28,
+                          -14.0004 215.8 24.2484,
+                          -14.0004 215.8 -24.2484,
+                          -7.24644 215.8 -27.046,
+                          -7.24644 219.8 -27.046,
+                          -7.24644 215.8 -27.046,
+                          -14.0004 215.8 -24.2484,
+                          -7.24644 219.8 -27.046,
+                          1.43188e-15 219.8 -28,
+                          -7.24644 215.8 -27.046,
+                          -19.799 215.8 19.799,
+                          -19.799 215.8 -19.799,
+                          -14.0004 215.8 -24.2484,
+                          -14.0004 219.8 -24.2484,
+                          -14.0004 215.8 -24.2484,
+                          -19.799 215.8 -19.799,
+                          -14.0004 215.8 24.2484,
+                          -19.799 215.8 19.799,
+                          -14.0004 215.8 -24.2484,
+                          -7.24644 219.8 -27.046,
+                          -14.0004 215.8 -24.2484,
+                          -14.0004 219.8 -24.2484,
+                          -24.2484 215.8 14.0004,
+                          -24.2484 215.8 -14.0004,
+                          -19.799 215.8 -19.799,
+                          -19.799 219.8 -19.799,
+                          -19.799 215.8 -19.799,
+                          -24.2484 215.8 -14.0004,
+                          -19.799 215.8 19.799,
+                          -24.2484 215.8 14.0004,
+                          -19.799 215.8 -19.799,
+                          -14.0004 219.8 -24.2484,
+                          -19.799 215.8 -19.799,
+                          -19.799 219.8 -19.799,
+                          -27.046 215.8 7.24644,
+                          -27.046 215.8 -7.24644,
+                          -24.2484 215.8 -14.0004,
+                          -24.2484 219.8 -14.0004,
+                          -24.2484 215.8 -14.0004,
+                          -27.046 215.8 -7.24644,
+                          -24.2484 215.8 14.0004,
+                          -27.046 215.8 7.24644,
+                          -24.2484 215.8 -14.0004,
+                          -19.799 219.8 -19.799,
+                          -24.2484 215.8 -14.0004,
+                          -24.2484 219.8 -14.0004,
+                          -27.046 215.8 7.24644,
+                          -28 215.8 -3.14632e-15,
+                          -27.046 215.8 -7.24644,
+                          -27.046 219.8 -7.24644,
+                          -27.046 215.8 -7.24644,
+                          -28 215.8 -3.14632e-15,
+                          -24.2484 219.8 -14.0004,
+                          -27.046 215.8 -7.24644,
+                          -27.046 219.8 -7.24644,
+                          -28 219.8 -3.14632e-15,
+                          -28 215.8 -3.14632e-15,
+                          -27.046 215.8 7.24644,
+                          -27.046 219.8 -7.24644,
+                          -28 215.8 -3.14632e-15,
+                          -28 219.8 -3.14632e-15,
+                          -27.046 219.8 7.24644,
+                          -27.046 215.8 7.24644,
+                          -24.2484 215.8 14.0004,
+                          -28 219.8 -3.14632e-15,
+                          -27.046 215.8 7.24644,
+                          -27.046 219.8 7.24644,
+                          -24.2484 219.8 14.0004,
+                          -24.2484 215.8 14.0004,
+                          -19.799 215.8 19.799,
+                          -27.046 219.8 7.24644,
+                          -24.2484 215.8 14.0004,
+                          -24.2484 219.8 14.0004,
+                          -19.799 219.8 19.799,
+                          -19.799 215.8 19.799,
+                          -14.0004 215.8 24.2484,
+                          -24.2484 219.8 14.0004,
+                          -19.799 215.8 19.799,
+                          -19.799 219.8 19.799,
+                          -14.0004 219.8 24.2484,
+                          -14.0004 215.8 24.2484,
+                          -7.24644 215.8 27.046,
+                          -19.799 219.8 19.799,
+                          -14.0004 215.8 24.2484,
+                          -14.0004 219.8 24.2484,
+                          -7.24644 219.8 27.046,
+                          -7.24644 215.8 27.046,
+                          -1.43186e-15 215.8 28,
+                          -14.0004 219.8 24.2484,
+                          -7.24644 215.8 27.046,
+                          -7.24644 219.8 27.046,
+                          -1.43186e-15 219.8 28,
+                          -1.43186e-15 215.8 28,
+                          7.24644 215.8 27.046,
+                          -7.24644 219.8 27.046,
+                          -1.43186e-15 215.8 28,
+                          -1.43186e-15 219.8 28,
+                          14.0004 215.8 -24.2484,
+                          14.0004 215.8 24.2484,
+                          7.24644 215.8 27.046,
+                          7.24644 219.8 27.046,
+                          7.24644 215.8 27.046,
+                          14.0004 215.8 24.2484,
+                          -1.43186e-15 219.8 28,
+                          7.24644 215.8 27.046,
+                          7.24644 219.8 27.046,
+                          19.799 215.8 -19.799,
+                          19.799 215.8 19.799,
+                          14.0004 215.8 24.2484,
+                          14.0004 219.8 24.2484,
+                          14.0004 215.8 24.2484,
+                          19.799 215.8 19.799,
+                          14.0004 215.8 -24.2484,
+                          19.799 215.8 -19.799,
+                          14.0004 215.8 24.2484,
+                          7.24644 219.8 27.046,
+                          14.0004 215.8 24.2484,
+                          14.0004 219.8 24.2484,
+                          24.2484 215.8 -14.0004,
+                          24.2484 215.8 14.0004,
+                          19.799 215.8 19.799,
+                          19.799 219.8 19.799,
+                          19.799 215.8 19.799,
+                          24.2484 215.8 14.0004,
+                          19.799 215.8 -19.799,
+                          24.2484 215.8 -14.0004,
+                          19.799 215.8 19.799,
+                          14.0004 219.8 24.2484,
+                          19.799 215.8 19.799,
+                          19.799 219.8 19.799,
+                          27.046 215.8 -7.24644,
+                          27.046 215.8 7.24644,
+                          24.2484 215.8 14.0004,
+                          24.2484 219.8 14.0004,
+                          24.2484 215.8 14.0004,
+                          27.046 215.8 7.24644,
+                          24.2484 215.8 -14.0004,
+                          27.046 215.8 -7.24644,
+                          24.2484 215.8 14.0004,
+                          19.799 219.8 19.799,
+                          24.2484 215.8 14.0004,
+                          24.2484 219.8 14.0004,
+                          27.046 215.8 -7.24644,
+                          28 215.8 -2.82579e-16,
+                          27.046 215.8 7.24644,
+                          27.046 219.8 7.24644,
+                          27.046 215.8 7.24644,
+                          28 215.8 -2.82579e-16,
+                          24.2484 219.8 14.0004,
+                          27.046 215.8 7.24644,
+                          27.046 219.8 7.24644,
+                          28 219.8 -2.82579e-16,
+                          28 215.8 -2.82579e-16,
+                          27.046 215.8 -7.24644,
+                          27.046 219.8 7.24644,
+                          28 215.8 -2.82579e-16,
+                          28 219.8 -2.82579e-16,
+                          27.046 219.8 -7.24644,
+                          27.046 215.8 -7.24644,
+                          24.2484 215.8 -14.0004,
+                          28 219.8 -2.82579e-16,
+                          27.046 215.8 -7.24644,
+                          27.046 219.8 -7.24644,
+                          24.2484 219.8 -14.0004,
+                          24.2484 215.8 -14.0004,
+                          19.799 215.8 -19.799,
+                          27.046 219.8 -7.24644,
+                          24.2484 215.8 -14.0004,
+                          24.2484 219.8 -14.0004,
+                          19.799 219.8 -19.799,
+                          19.799 215.8 -19.799,
+                          14.0004 215.8 -24.2484,
+                          24.2484 219.8 -14.0004,
+                          19.799 215.8 -19.799,
+                          19.799 219.8 -19.799,
+                          14.0004 219.8 -24.2484,
+                          14.0004 215.8 -24.2484,
+                          7.24644 215.8 -27.046,
+                          19.799 219.8 -19.799,
+                          14.0004 215.8 -24.2484,
+                          14.0004 219.8 -24.2484,
+                          14.0004 219.8 -24.2484,
+                          7.24644 215.8 -27.046,
+                          7.24644 219.8 -27.046,
+                          -1.43186e-15 219.8 28,
+                          -4.85807e-16 219.8 9.5,
+                          -4.12237 219.8 8.55894,
+                          -1.43186e-15 219.8 28,
+                          7.24644 219.8 27.046,
+                          -4.85807e-16 219.8 9.5,
+                          4.12237 219.8 8.55894,
+                          -4.85807e-16 219.8 9.5,
+                          7.24644 219.8 27.046,
+                          -7.24644 219.8 27.046,
+                          -4.12237 219.8 8.55894,
+                          -7.42766 219.8 5.92268,
+                          -7.24644 219.8 27.046,
+                          -1.43186e-15 219.8 28,
+                          -4.12237 219.8 8.55894,
+                          -7.24644 219.8 27.046,
+                          -7.42766 219.8 5.92268,
+                          -9.26174 219.8 2.11371,
+                          -14.0004 219.8 -24.2484,
+                          -9.26174 219.8 2.11371,
+                          -9.26174 219.8 -2.11371,
+                          -14.0004 219.8 -24.2484,
+                          -7.24644 219.8 27.046,
+                          -9.26174 219.8 2.11371,
+                          -14.0004 219.8 -24.2484,
+                          -9.26174 219.8 -2.11371,
+                          -7.42766 219.8 -5.92268,
+                          -7.24644 219.8 -27.046,
+                          -7.42766 219.8 -5.92268,
+                          -4.12237 219.8 -8.55894,
+                          -7.24644 219.8 -27.046,
+                          -14.0004 219.8 -24.2484,
+                          -7.42766 219.8 -5.92268,
+                          -7.24644 219.8 -27.046,
+                          -4.12237 219.8 -8.55894,
+                          4.85819e-16 219.8 -9.5,
+                          -7.24644 219.8 -27.046,
+                          4.85819e-16 219.8 -9.5,
+                          1.43188e-15 219.8 -28,
+                          4.12237 219.8 -8.55894,
+                          1.43188e-15 219.8 -28,
+                          4.85819e-16 219.8 -9.5,
+                          4.12237 219.8 -8.55894,
+                          7.24644 219.8 -27.046,
+                          1.43188e-15 219.8 -28,
+                          14.0004 219.8 24.2484,
+                          14.0004 219.8 -24.2484,
+                          7.24644 219.8 -27.046,
+                          9.26174 219.8 -2.11371,
+                          14.0004 219.8 24.2484,
+                          7.24644 219.8 -27.046,
+                          7.42766 219.8 -5.92268,
+                          9.26174 219.8 -2.11371,
+                          7.24644 219.8 -27.046,
+                          4.12237 219.8 -8.55894,
+                          7.42766 219.8 -5.92268,
+                          7.24644 219.8 -27.046,
+                          19.799 219.8 19.799,
+                          19.799 219.8 -19.799,
+                          14.0004 219.8 -24.2484,
+                          14.0004 219.8 24.2484,
+                          19.799 219.8 19.799,
+                          14.0004 219.8 -24.2484,
+                          24.2484 219.8 14.0004,
+                          24.2484 219.8 -14.0004,
+                          19.799 219.8 -19.799,
+                          19.799 219.8 19.799,
+                          24.2484 219.8 14.0004,
+                          19.799 219.8 -19.799,
+                          27.046 219.8 7.24644,
+                          27.046 219.8 -7.24644,
+                          24.2484 219.8 -14.0004,
+                          24.2484 219.8 14.0004,
+                          27.046 219.8 7.24644,
+                          24.2484 219.8 -14.0004,
+                          27.046 219.8 7.24644,
+                          28 219.8 -2.82579e-16,
+                          27.046 219.8 -7.24644,
+                          7.42766 219.8 5.92268,
+                          7.24644 219.8 27.046,
+                          14.0004 219.8 24.2484,
+                          9.26174 219.8 2.11371,
+                          7.42766 219.8 5.92268,
+                          14.0004 219.8 24.2484,
+                          9.26174 219.8 -2.11371,
+                          9.26174 219.8 2.11371,
+                          14.0004 219.8 24.2484,
+                          7.42766 219.8 5.92268,
+                          4.12237 219.8 8.55894,
+                          7.24644 219.8 27.046,
+                          -14.0004 219.8 -24.2484,
+                          -14.0004 219.8 24.2484,
+                          -7.24644 219.8 27.046,
+                          -19.799 219.8 -19.799,
+                          -19.799 219.8 19.799,
+                          -14.0004 219.8 24.2484,
+                          -14.0004 219.8 -24.2484,
+                          -19.799 219.8 -19.799,
+                          -14.0004 219.8 24.2484,
+                          -24.2484 219.8 -14.0004,
+                          -24.2484 219.8 14.0004,
+                          -19.799 219.8 19.799,
+                          -19.799 219.8 -19.799,
+                          -24.2484 219.8 -14.0004,
+                          -19.799 219.8 19.799,
+                          -27.046 219.8 -7.24644,
+                          -27.046 219.8 7.24644,
+                          -24.2484 219.8 14.0004,
+                          -24.2484 219.8 -14.0004,
+                          -27.046 219.8 -7.24644,
+                          -24.2484 219.8 14.0004,
+                          -27.046 219.8 -7.24644,
+                          -28 219.8 -3.14632e-15,
+                          -27.046 219.8 7.24644,
+                          4.03562 219.8 8.37865,
+                          4.03562 219.8 -8.37865,
+                          4.75591e-16 219.8 -9.3,
+                          4.75591e-16 215.5 -9.3,
+                          4.75591e-16 219.8 -9.3,
+                          4.03562 219.8 -8.37865,
+                          -4.75579e-16 219.8 9.3,
+                          4.03562 219.8 8.37865,
+                          4.75591e-16 219.8 -9.3,
+                          -4.03562 219.8 -8.37865,
+                          -4.75579e-16 219.8 9.3,
+                          4.75591e-16 219.8 -9.3,
+                          -4.03562 215.5 -8.37865,
+                          -4.03562 219.8 -8.37865,
+                          4.75591e-16 219.8 -9.3,
+                          4.75591e-16 215.5 -9.3,
+                          -4.03562 215.5 -8.37865,
+                          4.75591e-16 219.8 -9.3,
+                          7.27076 219.8 5.79855,
+                          7.27076 219.8 -5.79855,
+                          4.03562 219.8 -8.37865,
+                          4.03562 215.5 -8.37865,
+                          4.03562 219.8 -8.37865,
+                          7.27076 219.8 -5.79855,
+                          4.03562 219.8 8.37865,
+                          7.27076 219.8 5.79855,
+                          4.03562 219.8 -8.37865,
+                          4.03562 215.5 -8.37865,
+                          4.75591e-16 215.5 -9.3,
+                          4.03562 219.8 -8.37865,
+                          9.06666 219.8 2.07003,
+                          9.06666 219.8 -2.07003,
+                          7.27076 219.8 -5.79855,
+                          7.27076 215.5 -5.79855,
+                          7.27076 219.8 -5.79855,
+                          9.06666 219.8 -2.07003,
+                          7.27076 219.8 5.79855,
+                          9.06666 219.8 2.07003,
+                          7.27076 219.8 -5.79855,
+                          4.03562 215.5 -8.37865,
+                          7.27076 219.8 -5.79855,
+                          7.27076 215.5 -5.79855,
+                          9.06666 215.5 -2.07003,
+                          9.06666 219.8 -2.07003,
+                          9.06666 219.8 2.07003,
+                          7.27076 215.5 -5.79855,
+                          9.06666 219.8 -2.07003,
+                          9.06666 215.5 -2.07003,
+                          9.06666 215.5 2.07003,
+                          9.06666 219.8 2.07003,
+                          7.27076 219.8 5.79855,
+                          9.06666 215.5 -2.07003,
+                          9.06666 219.8 2.07003,
+                          9.06666 215.5 2.07003,
+                          7.27076 215.5 5.79855,
+                          7.27076 219.8 5.79855,
+                          4.03562 219.8 8.37865,
+                          9.06666 215.5 2.07003,
+                          7.27076 219.8 5.79855,
+                          7.27076 215.5 5.79855,
+                          4.03562 215.5 8.37865,
+                          4.03562 219.8 8.37865,
+                          -4.75579e-16 219.8 9.3,
+                          7.27076 215.5 5.79855,
+                          4.03562 219.8 8.37865,
+                          4.03562 215.5 8.37865,
+                          -4.03562 219.8 -8.37865,
+                          -4.03562 219.8 8.37865,
+                          -4.75579e-16 219.8 9.3,
+                          -4.75579e-16 215.5 9.3,
+                          -4.75579e-16 219.8 9.3,
+                          -4.03562 219.8 8.37865,
+                          4.03562 215.5 8.37865,
+                          -4.75579e-16 219.8 9.3,
+                          -4.75579e-16 215.5 9.3,
+                          -7.27076 219.8 -5.79855,
+                          -7.27076 219.8 5.79855,
+                          -4.03562 219.8 8.37865,
+                          -4.03562 215.5 8.37865,
+                          -4.03562 219.8 8.37865,
+                          -7.27076 219.8 5.79855,
+                          -4.03562 219.8 -8.37865,
+                          -7.27076 219.8 -5.79855,
+                          -4.03562 219.8 8.37865,
+                          -4.03562 215.5 8.37865,
+                          -4.75579e-16 215.5 9.3,
+                          -4.03562 219.8 8.37865,
+                          -9.06666 219.8 -2.07003,
+                          -9.06666 219.8 2.07003,
+                          -7.27076 219.8 5.79855,
+                          -7.27076 215.5 5.79855,
+                          -7.27076 219.8 5.79855,
+                          -9.06666 219.8 2.07003,
+                          -7.27076 219.8 -5.79855,
+                          -9.06666 219.8 -2.07003,
+                          -7.27076 219.8 5.79855,
+                          -7.27076 215.5 5.79855,
+                          -4.03562 215.5 8.37865,
+                          -7.27076 219.8 5.79855,
+                          -9.06666 215.5 2.07003,
+                          -9.06666 219.8 2.07003,
+                          -9.06666 219.8 -2.07003,
+                          -9.06666 215.5 2.07003,
+                          -7.27076 215.5 5.79855,
+                          -9.06666 219.8 2.07003,
+                          -9.06666 215.5 -2.07003,
+                          -9.06666 219.8 -2.07003,
+                          -7.27076 219.8 -5.79855,
+                          -9.06666 215.5 -2.07003,
+                          -9.06666 215.5 2.07003,
+                          -9.06666 219.8 -2.07003,
+                          -7.27076 215.5 -5.79855,
+                          -7.27076 219.8 -5.79855,
+                          -4.03562 219.8 -8.37865,
+                          -7.27076 215.5 -5.79855,
+                          -9.06666 215.5 -2.07003,
+                          -7.27076 219.8 -5.79855,
+                          -4.03562 215.5 -8.37865,
+                          -7.27076 215.5 -5.79855,
+                          -4.03562 219.8 -8.37865,
+                          -1.0739e-15 215.5 21,
+                          -4.75579e-16 215.5 9.3,
+                          -4.03562 215.5 8.37865,
+                          -1.0739e-15 215.5 21,
+                          6.48932 215.5 19.9721,
+                          -4.75579e-16 215.5 9.3,
+                          4.03562 215.5 8.37865,
+                          -4.75579e-16 215.5 9.3,
+                          6.48932 215.5 19.9721,
+                          -6.48932 215.5 19.9721,
+                          -4.03562 215.5 8.37865,
+                          -7.27076 215.5 5.79855,
+                          -6.48932 215.5 19.9721,
+                          -1.0739e-15 215.5 21,
+                          -4.03562 215.5 8.37865,
+                          -6.48932 215.5 19.9721,
+                          -7.27076 215.5 5.79855,
+                          -9.06666 215.5 2.07003,
+                          -12.3435 215.5 -16.9894,
+                          -9.06666 215.5 2.07003,
+                          -9.06666 215.5 -2.07003,
+                          -12.3435 215.5 -16.9894,
+                          -6.48932 215.5 19.9721,
+                          -9.06666 215.5 2.07003,
+                          -12.3435 215.5 -16.9894,
+                          -9.06666 215.5 -2.07003,
+                          -7.27076 215.5 -5.79855,
+                          -6.48932 215.5 -19.9721,
+                          -7.27076 215.5 -5.79855,
+                          -4.03562 215.5 -8.37865,
+                          -6.48932 215.5 -19.9721,
+                          -12.3435 215.5 -16.9894,
+                          -7.27076 215.5 -5.79855,
+                          -6.48932 215.5 -19.9721,
+                          -4.03562 215.5 -8.37865,
+                          4.75591e-16 215.5 -9.3,
+                          -6.48932 215.5 -19.9721,
+                          4.75591e-16 215.5 -9.3,
+                          1.07391e-15 215.5 -21,
+                          4.03562 215.5 -8.37865,
+                          1.07391e-15 215.5 -21,
+                          4.75591e-16 215.5 -9.3,
+                          4.03562 215.5 -8.37865,
+                          6.48932 215.5 -19.9721,
+                          1.07391e-15 215.5 -21,
+                          1.07391e-15 209.1 -21,
+                          1.07391e-15 215.5 -21,
+                          6.48932 215.5 -19.9721,
+                          -6.48932 209.1 -19.9721,
+                          -6.48932 215.5 -19.9721,
+                          1.07391e-15 215.5 -21,
+                          1.07391e-15 209.1 -21,
+                          -6.48932 209.1 -19.9721,
+                          1.07391e-15 215.5 -21,
+                          12.3435 215.5 16.9894,
+                          12.3435 215.5 -16.9894,
+                          6.48932 215.5 -19.9721,
+                          6.48932 209.1 -19.9721,
+                          6.48932 215.5 -19.9721,
+                          12.3435 215.5 -16.9894,
+                          9.06666 215.5 -2.07003,
+                          12.3435 215.5 16.9894,
+                          6.48932 215.5 -19.9721,
+                          7.27076 215.5 -5.79855,
+                          9.06666 215.5 -2.07003,
+                          6.48932 215.5 -19.9721,
+                          4.03562 215.5 -8.37865,
+                          7.27076 215.5 -5.79855,
+                          6.48932 215.5 -19.9721,
+                          6.48932 209.1 -19.9721,
+                          1.07391e-15 209.1 -21,
+                          6.48932 215.5 -19.9721,
+                          16.9893 215.5 12.3434,
+                          16.9893 215.5 -12.3434,
+                          12.3435 215.5 -16.9894,
+                          12.3435 209.1 -16.9894,
+                          12.3435 215.5 -16.9894,
+                          16.9893 215.5 -12.3434,
+                          12.3435 215.5 16.9894,
+                          16.9893 215.5 12.3434,
+                          12.3435 215.5 -16.9894,
+                          6.48932 209.1 -19.9721,
+                          12.3435 215.5 -16.9894,
+                          12.3435 209.1 -16.9894,
+                          19.9722 215.5 6.48936,
+                          19.9722 215.5 -6.48936,
+                          16.9893 215.5 -12.3434,
+                          16.9893 209.1 -12.3434,
+                          16.9893 215.5 -12.3434,
+                          19.9722 215.5 -6.48936,
+                          16.9893 215.5 12.3434,
+                          19.9722 215.5 6.48936,
+                          16.9893 215.5 -12.3434,
+                          12.3435 209.1 -16.9894,
+                          16.9893 215.5 -12.3434,
+                          16.9893 209.1 -12.3434,
+                          19.9722 215.5 6.48936,
+                          20.9999 215.5 -5.91439e-16,
+                          19.9722 215.5 -6.48936,
+                          19.9722 209.1 -6.48936,
+                          19.9722 215.5 -6.48936,
+                          20.9999 215.5 -5.91439e-16,
+                          16.9893 209.1 -12.3434,
+                          19.9722 215.5 -6.48936,
+                          19.9722 209.1 -6.48936,
+                          20.9999 209.1 -5.91439e-16,
+                          20.9999 215.5 -5.91439e-16,
+                          19.9722 215.5 6.48936,
+                          19.9722 209.1 -6.48936,
+                          20.9999 215.5 -5.91439e-16,
+                          20.9999 209.1 -5.91439e-16,
+                          19.9722 209.1 6.48936,
+                          19.9722 215.5 6.48936,
+                          16.9893 215.5 12.3434,
+                          20.9999 209.1 -5.91439e-16,
+                          19.9722 215.5 6.48936,
+                          19.9722 209.1 6.48936,
+                          16.9893 209.1 12.3434,
+                          16.9893 215.5 12.3434,
+                          12.3435 215.5 16.9894,
+                          19.9722 209.1 6.48936,
+                          16.9893 215.5 12.3434,
+                          16.9893 209.1 12.3434,
+                          7.27076 215.5 5.79855,
+                          6.48932 215.5 19.9721,
+                          12.3435 215.5 16.9894,
+                          12.3435 209.1 16.9894,
+                          12.3435 215.5 16.9894,
+                          6.48932 215.5 19.9721,
+                          9.06666 215.5 2.07003,
+                          7.27076 215.5 5.79855,
+                          12.3435 215.5 16.9894,
+                          9.06666 215.5 -2.07003,
+                          9.06666 215.5 2.07003,
+                          12.3435 215.5 16.9894,
+                          16.9893 209.1 12.3434,
+                          12.3435 215.5 16.9894,
+                          12.3435 209.1 16.9894,
+                          6.48932 209.1 19.9721,
+                          6.48932 215.5 19.9721,
+                          -1.0739e-15 215.5 21,
+                          7.27076 215.5 5.79855,
+                          4.03562 215.5 8.37865,
+                          6.48932 215.5 19.9721,
+                          12.3435 209.1 16.9894,
+                          6.48932 215.5 19.9721,
+                          6.48932 209.1 19.9721,
+                          -1.0739e-15 209.1 21,
+                          -1.0739e-15 215.5 21,
+                          -6.48932 215.5 19.9721,
+                          6.48932 209.1 19.9721,
+                          -1.0739e-15 215.5 21,
+                          -1.0739e-15 209.1 21,
+                          -12.3435 215.5 -16.9894,
+                          -12.3435 215.5 16.9894,
+                          -6.48932 215.5 19.9721,
+                          -6.48932 209.1 19.9721,
+                          -6.48932 215.5 19.9721,
+                          -12.3435 215.5 16.9894,
+                          -6.48932 209.1 19.9721,
+                          -1.0739e-15 209.1 21,
+                          -6.48932 215.5 19.9721,
+                          -16.9893 215.5 -12.3434,
+                          -16.9893 215.5 12.3434,
+                          -12.3435 215.5 16.9894,
+                          -12.3435 209.1 16.9894,
+                          -12.3435 215.5 16.9894,
+                          -16.9893 215.5 12.3434,
+                          -12.3435 215.5 -16.9894,
+                          -16.9893 215.5 -12.3434,
+                          -12.3435 215.5 16.9894,
+                          -12.3435 209.1 16.9894,
+                          -6.48932 209.1 19.9721,
+                          -12.3435 215.5 16.9894,
+                          -19.9722 215.5 -6.48936,
+                          -19.9722 215.5 6.48936,
+                          -16.9893 215.5 12.3434,
+                          -16.9893 209.1 12.3434,
+                          -16.9893 215.5 12.3434,
+                          -19.9722 215.5 6.48936,
+                          -16.9893 215.5 -12.3434,
+                          -19.9722 215.5 -6.48936,
+                          -16.9893 215.5 12.3434,
+                          -16.9893 209.1 12.3434,
+                          -12.3435 209.1 16.9894,
+                          -16.9893 215.5 12.3434,
+                          -19.9722 215.5 -6.48936,
+                          -20.9999 215.5 -2.73923e-15,
+                          -19.9722 215.5 6.48936,
+                          -19.9722 209.1 6.48936,
+                          -19.9722 215.5 6.48936,
+                          -20.9999 215.5 -2.73923e-15,
+                          -19.9722 209.1 6.48936,
+                          -16.9893 209.1 12.3434,
+                          -19.9722 215.5 6.48936,
+                          -20.9999 209.1 -2.73923e-15,
+                          -20.9999 215.5 -2.73923e-15,
+                          -19.9722 215.5 -6.48936,
+                          -20.9999 209.1 -2.73923e-15,
+                          -19.9722 209.1 6.48936,
+                          -20.9999 215.5 -2.73923e-15,
+                          -19.9722 209.1 -6.48936,
+                          -19.9722 215.5 -6.48936,
+                          -16.9893 215.5 -12.3434,
+                          -19.9722 209.1 -6.48936,
+                          -20.9999 209.1 -2.73923e-15,
+                          -19.9722 215.5 -6.48936,
+                          -16.9893 209.1 -12.3434,
+                          -16.9893 215.5 -12.3434,
+                          -12.3435 215.5 -16.9894,
+                          -16.9893 209.1 -12.3434,
+                          -19.9722 209.1 -6.48936,
+                          -16.9893 215.5 -12.3434,
+                          -12.3435 209.1 -16.9894,
+                          -12.3435 215.5 -16.9894,
+                          -6.48932 215.5 -19.9721,
+                          -12.3435 209.1 -16.9894,
+                          -16.9893 209.1 -12.3434,
+                          -12.3435 215.5 -16.9894,
+                          -6.48932 209.1 -19.9721,
+                          -12.3435 209.1 -16.9894,
+                          -6.48932 215.5 -19.9721,
+                          -4.75579e-16 209.1 9.3,
+                          -1.0739e-15 209.1 21,
+                          -6.48932 209.1 19.9721,
+                          -4.75579e-16 209.1 9.3,
+                          4.03562 209.1 8.37865,
+                          -1.0739e-15 209.1 21,
+                          6.48932 209.1 19.9721,
+                          -1.0739e-15 209.1 21,
+                          4.03562 209.1 8.37865,
+                          -7.27076 209.1 5.79855,
+                          -6.48932 209.1 19.9721,
+                          -12.3435 209.1 16.9894,
+                          -4.03562 209.1 8.37865,
+                          -4.75579e-16 209.1 9.3,
+                          -6.48932 209.1 19.9721,
+                          -7.27076 209.1 5.79855,
+                          -4.03562 209.1 8.37865,
+                          -6.48932 209.1 19.9721,
+                          -12.3435 209.1 -16.9894,
+                          -12.3435 209.1 16.9894,
+                          -16.9893 209.1 12.3434,
+                          -6.48932 209.1 -19.9721,
+                          -12.3435 209.1 16.9894,
+                          -12.3435 209.1 -16.9894,
+                          -9.06666 209.1 -2.07003,
+                          -12.3435 209.1 16.9894,
+                          -6.48932 209.1 -19.9721,
+                          -9.06666 209.1 2.07003,
+                          -7.27076 209.1 5.79855,
+                          -12.3435 209.1 16.9894,
+                          -9.06666 209.1 -2.07003,
+                          -9.06666 209.1 2.07003,
+                          -12.3435 209.1 16.9894,
+                          -16.9893 209.1 -12.3434,
+                          -16.9893 209.1 12.3434,
+                          -19.9722 209.1 6.48936,
+                          -12.3435 209.1 -16.9894,
+                          -16.9893 209.1 12.3434,
+                          -16.9893 209.1 -12.3434,
+                          -19.9722 209.1 -6.48936,
+                          -19.9722 209.1 6.48936,
+                          -20.9999 209.1 -2.73923e-15,
+                          -16.9893 209.1 -12.3434,
+                          -19.9722 209.1 6.48936,
+                          -19.9722 209.1 -6.48936,
+                          -4.03562 209.1 -8.37865,
+                          -6.48932 209.1 -19.9721,
+                          1.07391e-15 209.1 -21,
+                          -7.27076 209.1 -5.79855,
+                          -9.06666 209.1 -2.07003,
+                          -6.48932 209.1 -19.9721,
+                          -4.03562 209.1 -8.37865,
+                          -7.27076 209.1 -5.79855,
+                          -6.48932 209.1 -19.9721,
+                          -4.03562 209.1 -8.37865,
+                          1.07391e-15 209.1 -21,
+                          4.75591e-16 209.1 -9.3,
+                          6.48932 209.1 -19.9721,
+                          4.75591e-16 209.1 -9.3,
+                          1.07391e-15 209.1 -21,
+                          6.48932 209.1 -19.9721,
+                          4.03562 209.1 -8.37865,
+                          4.75591e-16 209.1 -9.3,
+                          4.75591e-16 208.8 -9.3,
+                          4.75591e-16 209.1 -9.3,
+                          4.03562 209.1 -8.37865,
+                          -4.03562 208.8 -8.37865,
+                          -4.03562 209.1 -8.37865,
+                          4.75591e-16 209.1 -9.3,
+                          4.75591e-16 208.8 -9.3,
+                          -4.03562 208.8 -8.37865,
+                          4.75591e-16 209.1 -9.3,
+                          6.48932 209.1 -19.9721,
+                          7.27076 209.1 -5.79855,
+                          4.03562 209.1 -8.37865,
+                          4.03562 208.8 -8.37865,
+                          4.03562 209.1 -8.37865,
+                          7.27076 209.1 -5.79855,
+                          4.03562 208.8 -8.37865,
+                          4.75591e-16 208.8 -9.3,
+                          4.03562 209.1 -8.37865,
+                          12.3435 209.1 -16.9894,
+                          9.06666 209.1 -2.07003,
+                          7.27076 209.1 -5.79855,
+                          7.27076 208.8 -5.79855,
+                          7.27076 209.1 -5.79855,
+                          9.06666 209.1 -2.07003,
+                          6.48932 209.1 -19.9721,
+                          12.3435 209.1 -16.9894,
+                          7.27076 209.1 -5.79855,
+                          4.03562 208.8 -8.37865,
+                          7.27076 209.1 -5.79855,
+                          7.27076 208.8 -5.79855,
+                          12.3435 209.1 -16.9894,
+                          9.06666 209.1 2.07003,
+                          9.06666 209.1 -2.07003,
+                          9.06666 208.8 -2.07003,
+                          9.06666 209.1 -2.07003,
+                          9.06666 209.1 2.07003,
+                          7.27076 208.8 -5.79855,
+                          9.06666 209.1 -2.07003,
+                          9.06666 208.8 -2.07003,
+                          6.48932 209.1 19.9721,
+                          7.27076 209.1 5.79855,
+                          9.06666 209.1 2.07003,
+                          9.06666 208.8 2.07003,
+                          9.06666 209.1 2.07003,
+                          7.27076 209.1 5.79855,
+                          12.3435 209.1 -16.9894,
+                          6.48932 209.1 19.9721,
+                          9.06666 209.1 2.07003,
+                          9.06666 208.8 -2.07003,
+                          9.06666 209.1 2.07003,
+                          9.06666 208.8 2.07003,
+                          6.48932 209.1 19.9721,
+                          4.03562 209.1 8.37865,
+                          7.27076 209.1 5.79855,
+                          7.27076 208.8 5.79855,
+                          7.27076 209.1 5.79855,
+                          4.03562 209.1 8.37865,
+                          9.06666 208.8 2.07003,
+                          7.27076 209.1 5.79855,
+                          7.27076 208.8 5.79855,
+                          4.03562 208.8 8.37865,
+                          4.03562 209.1 8.37865,
+                          -4.75579e-16 209.1 9.3,
+                          7.27076 208.8 5.79855,
+                          4.03562 209.1 8.37865,
+                          4.03562 208.8 8.37865,
+                          -4.75579e-16 208.8 9.3,
+                          -4.75579e-16 209.1 9.3,
+                          -4.03562 209.1 8.37865,
+                          4.03562 208.8 8.37865,
+                          -4.75579e-16 209.1 9.3,
+                          -4.75579e-16 208.8 9.3,
+                          -4.03562 208.8 8.37865,
+                          -4.03562 209.1 8.37865,
+                          -7.27076 209.1 5.79855,
+                          -4.03562 208.8 8.37865,
+                          -4.75579e-16 208.8 9.3,
+                          -4.03562 209.1 8.37865,
+                          -7.27076 208.8 5.79855,
+                          -7.27076 209.1 5.79855,
+                          -9.06666 209.1 2.07003,
+                          -7.27076 208.8 5.79855,
+                          -4.03562 208.8 8.37865,
+                          -7.27076 209.1 5.79855,
+                          -9.06666 208.8 2.07003,
+                          -9.06666 209.1 2.07003,
+                          -9.06666 209.1 -2.07003,
+                          -9.06666 208.8 2.07003,
+                          -7.27076 208.8 5.79855,
+                          -9.06666 209.1 2.07003,
+                          -9.06666 208.8 -2.07003,
+                          -9.06666 209.1 -2.07003,
+                          -7.27076 209.1 -5.79855,
+                          -9.06666 208.8 -2.07003,
+                          -9.06666 208.8 2.07003,
+                          -9.06666 209.1 -2.07003,
+                          -7.27076 208.8 -5.79855,
+                          -7.27076 209.1 -5.79855,
+                          -4.03562 209.1 -8.37865,
+                          -7.27076 208.8 -5.79855,
+                          -9.06666 208.8 -2.07003,
+                          -7.27076 209.1 -5.79855,
+                          -4.03562 208.8 -8.37865,
+                          -7.27076 208.8 -5.79855,
+                          -4.03562 209.1 -8.37865,
+                          12.3435 209.1 -16.9894,
+                          12.3435 209.1 16.9894,
+                          6.48932 209.1 19.9721,
+                          16.9893 209.1 -12.3434,
+                          16.9893 209.1 12.3434,
+                          12.3435 209.1 16.9894,
+                          12.3435 209.1 -16.9894,
+                          16.9893 209.1 -12.3434,
+                          12.3435 209.1 16.9894,
+                          19.9722 209.1 -6.48936,
+                          19.9722 209.1 6.48936,
+                          16.9893 209.1 12.3434,
+                          16.9893 209.1 -12.3434,
+                          19.9722 209.1 -6.48936,
+                          16.9893 209.1 12.3434,
+                          19.9722 209.1 -6.48936,
+                          20.9999 209.1 -5.91439e-16,
+                          19.9722 209.1 6.48936,
+                          4.75591e-16 208.8 -9.3,
+                          -4.75579e-16 208.8 9.3,
+                          -4.03562 208.8 8.37865,
+                          4.03562 208.8 -8.37865,
+                          -4.75579e-16 208.8 9.3,
+                          4.75591e-16 208.8 -9.3,
+                          4.03562 208.8 -8.37865,
+                          4.03562 208.8 8.37865,
+                          -4.75579e-16 208.8 9.3,
+                          -4.03562 208.8 -8.37865,
+                          -4.03562 208.8 8.37865,
+                          -7.27076 208.8 5.79855,
+                          4.75591e-16 208.8 -9.3,
+                          -4.03562 208.8 8.37865,
+                          -4.03562 208.8 -8.37865,
+                          -7.27076 208.8 -5.79855,
+                          -7.27076 208.8 5.79855,
+                          -9.06666 208.8 2.07003,
+                          -4.03562 208.8 -8.37865,
+                          -7.27076 208.8 5.79855,
+                          -7.27076 208.8 -5.79855,
+                          -7.27076 208.8 -5.79855,
+                          -9.06666 208.8 2.07003,
+                          -9.06666 208.8 -2.07003,
+                          7.27076 208.8 -5.79855,
+                          7.27076 208.8 5.79855,
+                          4.03562 208.8 8.37865,
+                          4.03562 208.8 -8.37865,
+                          7.27076 208.8 -5.79855,
+                          4.03562 208.8 8.37865,
+                          9.06666 208.8 -2.07003,
+                          9.06666 208.8 2.07003,
+                          7.27076 208.8 5.79855,
+                          7.27076 208.8 -5.79855,
+                          9.06666 208.8 -2.07003,
+                          7.27076 208.8 5.79855 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/platform/hd_platform_roll_link.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/platform/hd_platform_roll_link.iv
new file mode 100644
index 0000000000000000000000000000000000000000..40dd134f3a7b786cd82e3cda53ef53c02f32e9ca
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/platform/hd_platform_roll_link.iv
@@ -0,0 +1,16782 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+
+    Material {
+        diffuseColor    0.85 0.9 0.47
+    }
+    Separator {
+        Normal {
+            vector      [ 0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.849248 0 0.527994,
+                          0.849248 0 0.527994,
+                          0.849248 0 0.527994,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0.485802 -1.70573e-15 0.874069,
+                          0.485802 -1.70573e-15 0.874069,
+                          0.849248 -2.98186e-15 0.527994,
+                          0.485802 -1.70573e-15 0.874069,
+                          0.849248 -2.98186e-15 0.527994,
+                          0.849248 -2.98186e-15 0.527994,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0.849248 0 0.527994,
+                          0.849248 0 0.527994,
+                          0.849248 0 0.527994,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          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,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          -1 0 3.15097e-15,
+                          -1 0 3.15097e-15,
+                          -1 0 3.15097e-15,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 -2.84217e-14 0,
+                          -1 -2.84217e-14 0,
+                          -1 -2.84217e-14 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.844969 0 0.534816,
+                          -0.844969 0 0.534816,
+                          -0.844969 0 0.534816,
+                          -1 0 3.15097e-15,
+                          -1 0 3.15097e-15,
+                          -1 0 3.15097e-15,
+                          -0.844969 0 0.534816,
+                          -0.844969 0 0.534816,
+                          -0.482278 0 0.876018,
+                          -0.844969 0 0.534816,
+                          -0.844969 0 0.534816,
+                          -0.844969 0 0.534816,
+                          -0.482278 0 0.876018,
+                          -0.482278 0 0.876018,
+                          -1.42109e-16 0 1,
+                          -0.844969 0 0.534816,
+                          -0.482278 0 0.876018,
+                          -0.482278 0 0.876018,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.482278 0 0.876018,
+                          -1.42109e-16 0 1,
+                          -1.03029e-15 0 1,
+                          -1.16573e-15 4.35233e-30 1,
+                          -1.16573e-15 4.35233e-30 1,
+                          0.485802 -1.70573e-15 0.874069,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.485802 -1.70573e-15 0.874069,
+                          -1.16573e-15 4.35233e-30 1,
+                          0.485802 -1.70573e-15 0.874069,
+                          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,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -1 0 3.15097e-15,
+                          -1 0 3.15097e-15,
+                          -1 0 3.15097e-15,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          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 2.84217e-14,
+                          -1 0 2.84217e-14,
+                          -1 0 2.84217e-14,
+                          -1 0 3.15097e-15,
+                          -1 0 3.15097e-15,
+                          -1 0 3.15097e-15,
+                          -0.844969 0 0.534816,
+                          -0.844969 0 0.534816,
+                          -0.844969 0 0.534816,
+                          -0.482278 6.77345e-15 0.876018,
+                          -0.482278 6.77345e-15 0.876018,
+                          -0.844969 1.18673e-14 0.534816,
+                          -0.482278 6.77345e-15 0.876018,
+                          -0.844969 1.18673e-14 0.534816,
+                          -0.844969 1.18673e-14 0.534816,
+                          -0.844969 0 0.534816,
+                          -0.844969 0 0.534816,
+                          -0.844969 0 0.534816,
+                          0.849248 0 0.527994,
+                          0.849248 0 0.527994,
+                          0.849248 0 0.527994,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0.849248 -1.34184e-14 0.527994,
+                          0.849248 -1.34184e-14 0.527994,
+                          0.485802 -7.67581e-15 0.874069,
+                          0.849248 0 0.527994,
+                          0.849248 0 0.527994,
+                          0.849248 0 0.527994,
+                          0.485802 -7.67581e-15 0.874069,
+                          0.485802 -7.67581e-15 0.874069,
+                          0 0 1,
+                          0.849248 -1.34184e-14 0.527994,
+                          0.485802 -7.67581e-15 0.874069,
+                          0.485802 -7.67581e-15 0.874069,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.485802 -7.67581e-15 0.874069,
+                          0 0 1,
+                          0 0 1,
+                          7.21645e-16 -9.45274e-30 1,
+                          7.21645e-16 -9.45274e-30 1,
+                          -0.482278 6.77345e-15 0.876018,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.482278 6.77345e-15 0.876018,
+                          7.21645e-16 -9.45274e-30 1,
+                          -0.482278 6.77345e-15 0.876018,
+                          0 0.707107 -0.707107,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -1 -2.84217e-14 0,
+                          -1 -2.84217e-14 0,
+                          -1 -2.84217e-14 0,
+                          0 0.707107 -0.707107,
+                          0 0.707107 -0.707107,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 6.12303e-17 -1,
+                          0 6.12303e-17 -1,
+                          0 0.707107 -0.707107,
+                          0 0.707107 -0.707107,
+                          0 6.12303e-17 -1,
+                          0 0.707107 -0.707107,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 -0.707107 -0.707107,
+                          0 0 -1,
+                          0 0 -1,
+                          -1 0 2.84217e-14,
+                          -1 0 2.84217e-14,
+                          -1 0 2.84217e-14,
+                          0 -0.707107 -0.707107,
+                          0 -0.707107 -0.707107,
+                          0 0 -1,
+                          0 -1 -6.12303e-17,
+                          0 -1 -6.12303e-17,
+                          0 -0.707107 -0.707107,
+                          0 -0.707107 -0.707107,
+                          0 -1 -6.12303e-17,
+                          0 -0.707107 -0.707107,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 114.5 130 1,
+                          114.5 130 10.02,
+                          35.119 130 137.7,
+                          35.119 131 137.7,
+                          35.119 130 137.7,
+                          114.5 130 10.02,
+                          26.0324 130 146.351,
+                          114.5 130 1,
+                          35.119 130 137.7,
+                          26.0324 131 146.351,
+                          26.0324 130 146.351,
+                          35.119 130 137.7,
+                          26.0324 131 146.351,
+                          35.119 130 137.7,
+                          35.119 131 137.7,
+                          114.5 131 10.02,
+                          114.5 130 10.02,
+                          114.5 130 1,
+                          35.119 131 137.7,
+                          114.5 130 10.02,
+                          114.5 131 10.02,
+                          -118.5 130 10.02,
+                          -118.5 130 1,
+                          114.5 130 1,
+                          114.5 -67 1,
+                          114.5 130 1,
+                          -118.5 130 1,
+                          -37.5782 130 137.87,
+                          -118.5 130 10.02,
+                          114.5 130 1,
+                          -28.5105 130 146.4,
+                          -37.5782 130 137.87,
+                          114.5 130 1,
+                          -16.454 130 149.5,
+                          -28.5105 130 146.4,
+                          114.5 130 1,
+                          13.8878 130 149.5,
+                          -16.454 130 149.5,
+                          114.5 130 1,
+                          26.0324 130 146.351,
+                          13.8878 130 149.5,
+                          114.5 130 1,
+                          114.5 130 0,
+                          114.5 130 1,
+                          114.5 -67 1,
+                          114.5 130.707 0.292893,
+                          114.5 131 1,
+                          114.5 130 1,
+                          114.5 131 10.02,
+                          114.5 130 1,
+                          114.5 131 1,
+                          114.5 130.707 0.292893,
+                          114.5 130 1,
+                          114.5 130 0,
+                          -118.5 131 1,
+                          -118.5 130 1,
+                          -118.5 130 10.02,
+                          -118.5 -67 1,
+                          114.5 -67 1,
+                          -118.5 130 1,
+                          -118.5 -67 0,
+                          -118.5 -67 1,
+                          -118.5 130 1,
+                          -118.5 130 0,
+                          -118.5 130 1,
+                          -118.5 131 1,
+                          -118.5 -67 0,
+                          -118.5 130 1,
+                          -118.5 130 0,
+                          -118.5 131 10.02,
+                          -118.5 130 10.02,
+                          -37.5782 130 137.87,
+                          -118.5 131 10.02,
+                          -118.5 131 1,
+                          -118.5 130 10.02,
+                          -37.5782 131 137.87,
+                          -37.5782 130 137.87,
+                          -28.5105 130 146.4,
+                          -118.5 131 10.02,
+                          -37.5782 130 137.87,
+                          -37.5782 131 137.87,
+                          -28.5105 131 146.4,
+                          -28.5105 130 146.4,
+                          -16.454 130 149.5,
+                          -37.5782 131 137.87,
+                          -28.5105 130 146.4,
+                          -28.5105 131 146.4,
+                          -16.454 131 149.5,
+                          -16.454 130 149.5,
+                          13.8878 130 149.5,
+                          -28.5105 131 146.4,
+                          -16.454 130 149.5,
+                          -16.454 131 149.5,
+                          13.8878 131 149.5,
+                          13.8878 130 149.5,
+                          26.0324 130 146.351,
+                          -16.454 131 149.5,
+                          13.8878 130 149.5,
+                          13.8878 131 149.5,
+                          26.0324 131 146.351,
+                          13.8878 131 149.5,
+                          26.0324 130 146.351,
+                          114.5 -67 10.02,
+                          114.5 -67 1,
+                          -118.5 -67 1,
+                          114.5 -68 1,
+                          114.5 -67 1,
+                          114.5 -67 10.02,
+                          114.5 -67 0,
+                          114.5 130 0,
+                          114.5 -67 1,
+                          114.5 -67.7071 0.292893,
+                          114.5 -67 0,
+                          114.5 -67 1,
+                          114.5 -67.7071 0.292893,
+                          114.5 -67 1,
+                          114.5 -68 1,
+                          -118.5 -67 10.02,
+                          -37.5782 -67 137.87,
+                          -118.5 -67 1,
+                          -28.5105 -67 146.4,
+                          -118.5 -67 1,
+                          -37.5782 -67 137.87,
+                          -118.5 -68 10.02,
+                          -118.5 -67 10.02,
+                          -118.5 -67 1,
+                          35.119 -67 137.7,
+                          114.5 -67 10.02,
+                          -118.5 -67 1,
+                          26.0324 -67 146.351,
+                          35.119 -67 137.7,
+                          -118.5 -67 1,
+                          13.8878 -67 149.5,
+                          26.0324 -67 146.351,
+                          -118.5 -67 1,
+                          -16.454 -67 149.5,
+                          13.8878 -67 149.5,
+                          -118.5 -67 1,
+                          -28.5105 -67 146.4,
+                          -16.454 -67 149.5,
+                          -118.5 -67 1,
+                          -118.5 -68 1,
+                          -118.5 -67 1,
+                          -118.5 -67 0,
+                          -118.5 -68 10.02,
+                          -118.5 -67 1,
+                          -118.5 -68 1,
+                          -37.5782 -68 137.87,
+                          -37.5782 -67 137.87,
+                          -118.5 -67 10.02,
+                          -28.5105 -68 146.4,
+                          -28.5105 -67 146.4,
+                          -37.5782 -67 137.87,
+                          -28.5105 -68 146.4,
+                          -37.5782 -67 137.87,
+                          -37.5782 -68 137.87,
+                          -37.5782 -68 137.87,
+                          -118.5 -67 10.02,
+                          -118.5 -68 10.02,
+                          114.5 -68 10.02,
+                          114.5 -67 10.02,
+                          35.119 -67 137.7,
+                          114.5 -68 10.02,
+                          114.5 -68 1,
+                          114.5 -67 10.02,
+                          35.119 -68 137.7,
+                          35.119 -67 137.7,
+                          26.0324 -67 146.351,
+                          114.5 -68 10.02,
+                          35.119 -67 137.7,
+                          35.119 -68 137.7,
+                          26.0324 -68 146.351,
+                          26.0324 -67 146.351,
+                          13.8878 -67 149.5,
+                          35.119 -68 137.7,
+                          26.0324 -67 146.351,
+                          26.0324 -68 146.351,
+                          13.8878 -68 149.5,
+                          13.8878 -67 149.5,
+                          -16.454 -67 149.5,
+                          26.0324 -68 146.351,
+                          13.8878 -67 149.5,
+                          13.8878 -68 149.5,
+                          -16.454 -68 149.5,
+                          -16.454 -67 149.5,
+                          -28.5105 -67 146.4,
+                          13.8878 -68 149.5,
+                          -16.454 -67 149.5,
+                          -16.454 -68 149.5,
+                          -28.5105 -68 146.4,
+                          -16.454 -68 149.5,
+                          -28.5105 -67 146.4,
+                          114.5 130.707 0.292893,
+                          -118.5 131 1,
+                          114.5 131 1,
+                          114.5 131 10.02,
+                          114.5 131 1,
+                          -118.5 131 1,
+                          -118.5 130 0,
+                          -118.5 131 1,
+                          -118.5 130.707 0.292893,
+                          114.5 130.707 0.292893,
+                          -118.5 130.707 0.292893,
+                          -118.5 131 1,
+                          -16.454 131 149.5,
+                          13.8878 131 149.5,
+                          -118.5 131 1,
+                          26.0324 131 146.351,
+                          -118.5 131 1,
+                          13.8878 131 149.5,
+                          -28.5105 131 146.4,
+                          -16.454 131 149.5,
+                          -118.5 131 1,
+                          -37.5782 131 137.87,
+                          -28.5105 131 146.4,
+                          -118.5 131 1,
+                          -118.5 131 10.02,
+                          -37.5782 131 137.87,
+                          -118.5 131 1,
+                          35.119 131 137.7,
+                          114.5 131 10.02,
+                          -118.5 131 1,
+                          26.0324 131 146.351,
+                          35.119 131 137.7,
+                          -118.5 131 1,
+                          114.5 130 0,
+                          -118.5 130 0,
+                          -118.5 130.707 0.292893,
+                          114.5 130.707 0.292893,
+                          114.5 130 0,
+                          -118.5 130.707 0.292893,
+                          -118.5 -67 0,
+                          -118.5 130 0,
+                          114.5 130 0,
+                          -118.5 -67 0,
+                          114.5 130 0,
+                          114.5 -67 0,
+                          114.5 -67.7071 0.292893,
+                          -118.5 -67 0,
+                          114.5 -67 0,
+                          -118.5 -68 1,
+                          -118.5 -67 0,
+                          -118.5 -67.7071 0.292893,
+                          114.5 -67.7071 0.292893,
+                          -118.5 -67.7071 0.292893,
+                          -118.5 -67 0,
+                          114.5 -68 1,
+                          -118.5 -68 1,
+                          -118.5 -67.7071 0.292893,
+                          114.5 -67.7071 0.292893,
+                          114.5 -68 1,
+                          -118.5 -67.7071 0.292893,
+                          -118.5 -68 10.02,
+                          -118.5 -68 1,
+                          114.5 -68 1,
+                          13.8878 -68 149.5,
+                          -16.454 -68 149.5,
+                          114.5 -68 1,
+                          -28.5105 -68 146.4,
+                          114.5 -68 1,
+                          -16.454 -68 149.5,
+                          26.0324 -68 146.351,
+                          13.8878 -68 149.5,
+                          114.5 -68 1,
+                          35.119 -68 137.7,
+                          26.0324 -68 146.351,
+                          114.5 -68 1,
+                          114.5 -68 10.02,
+                          35.119 -68 137.7,
+                          114.5 -68 1,
+                          -37.5782 -68 137.87,
+                          -118.5 -68 10.02,
+                          114.5 -68 1,
+                          -28.5105 -68 146.4,
+                          -37.5782 -68 137.87,
+                          114.5 -68 1 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0 0 0
+    }
+    Separator {
+        Normal {
+            vector      [ 0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          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,
+                          -1 0 -4.06024e-16,
+                          -1 0 -4.06024e-16,
+                          -1 0 -4.06024e-16,
+                          -1 0 -4.06024e-16,
+                          -1 0 -4.06024e-16,
+                          -1 0 -4.06024e-16,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.795729 0 0.605652,
+                          0.795729 0 0.605652,
+                          0.795729 0 0.605652,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0.794864 0 0.606788,
+                          0.794864 0 0.606788,
+                          0.564076 0 0.825723,
+                          0.795729 0 0.605652,
+                          0.795729 0 0.605652,
+                          0.795729 0 0.605652,
+                          0.564076 0 0.825723,
+                          0.564076 0 0.825723,
+                          0.275269 0 0.961367,
+                          0.794864 0 0.606788,
+                          0.564076 0 0.825723,
+                          0.564076 0 0.825723,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.564076 0 0.825723,
+                          0.275269 0 0.961367,
+                          0.275269 0 0.961367,
+                          -0.275219 0 0.961382,
+                          -0.275219 0 0.961382,
+                          -0.564101 0 0.825705,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.564101 0 0.825705,
+                          -0.564101 0 0.825705,
+                          -0.794928 0 0.606703,
+                          -0.275219 0 0.961382,
+                          -0.564101 0 0.825705,
+                          -0.564101 0 0.825705,
+                          -0.795729 0 0.605652,
+                          -0.795729 0 0.605652,
+                          -0.795729 0 0.605652,
+                          -0.564101 0 0.825705,
+                          -0.794928 0 0.606703,
+                          -0.794928 0 0.606703,
+                          -0.795729 0 0.605652,
+                          -0.795729 0 0.605652,
+                          -0.795729 0 0.605652,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 116 -68 36,
+                          116 -68 1,
+                          -116 -68 1,
+                          -116 -69 1,
+                          -116 -68 1,
+                          116 -68 1,
+                          37.7478 -68 138.811,
+                          116 -68 36,
+                          -116 -68 1,
+                          30.7763 -68 145.437,
+                          37.7478 -68 138.811,
+                          -116 -68 1,
+                          22.1207 -68 149.5,
+                          30.7763 -68 145.437,
+                          -116 -68 1,
+                          -22.1207 -68 149.5,
+                          22.1207 -68 149.5,
+                          -116 -68 1,
+                          -30.7767 -68 145.437,
+                          -22.1207 -68 149.5,
+                          -116 -68 1,
+                          -37.7478 -68 138.811,
+                          -30.7767 -68 145.437,
+                          -116 -68 1,
+                          -116 -68 36,
+                          -37.7478 -68 138.811,
+                          -116 -68 1,
+                          -116 -69 36,
+                          -116 -68 36,
+                          -116 -68 1,
+                          -116 -69 36,
+                          -116 -68 1,
+                          -116 -69 1,
+                          116 -69 1,
+                          116 -68 1,
+                          116 -68 36,
+                          116 -69 1,
+                          -116 -69 1,
+                          116 -68 1,
+                          116 -69 36,
+                          116 -68 36,
+                          37.7478 -68 138.811,
+                          116 -69 1,
+                          116 -68 36,
+                          116 -69 36,
+                          37.7478 -69 138.811,
+                          37.7478 -68 138.811,
+                          30.7763 -68 145.437,
+                          116 -69 36,
+                          37.7478 -68 138.811,
+                          37.7478 -69 138.811,
+                          30.7763 -69 145.437,
+                          30.7763 -68 145.437,
+                          22.1207 -68 149.5,
+                          37.7478 -69 138.811,
+                          30.7763 -68 145.437,
+                          30.7763 -69 145.437,
+                          22.1207 -69 149.5,
+                          22.1207 -68 149.5,
+                          -22.1207 -68 149.5,
+                          30.7763 -69 145.437,
+                          22.1207 -68 149.5,
+                          22.1207 -69 149.5,
+                          -22.1207 -69 149.5,
+                          -22.1207 -68 149.5,
+                          -30.7767 -68 145.437,
+                          22.1207 -69 149.5,
+                          -22.1207 -68 149.5,
+                          -22.1207 -69 149.5,
+                          -30.7767 -69 145.437,
+                          -30.7767 -68 145.437,
+                          -37.7478 -68 138.811,
+                          -22.1207 -69 149.5,
+                          -30.7767 -68 145.437,
+                          -30.7767 -69 145.437,
+                          -37.7478 -69 138.811,
+                          -37.7478 -68 138.811,
+                          -116 -68 36,
+                          -30.7767 -69 145.437,
+                          -37.7478 -68 138.811,
+                          -37.7478 -69 138.811,
+                          -37.7478 -69 138.811,
+                          -116 -68 36,
+                          -116 -69 36,
+                          116 -69 1,
+                          -116 -69 36,
+                          -116 -69 1,
+                          116 -69 1,
+                          -37.7478 -69 138.811,
+                          -116 -69 36,
+                          116 -69 1,
+                          -30.7767 -69 145.437,
+                          -37.7478 -69 138.811,
+                          116 -69 1,
+                          -22.1207 -69 149.5,
+                          -30.7767 -69 145.437,
+                          116 -69 1,
+                          22.1207 -69 149.5,
+                          -22.1207 -69 149.5,
+                          116 -69 1,
+                          30.7763 -69 145.437,
+                          22.1207 -69 149.5,
+                          116 -69 1,
+                          37.7478 -69 138.811,
+                          30.7763 -69 145.437,
+                          116 -69 1,
+                          116 -69 36,
+                          37.7478 -69 138.811 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    1 0.8 0.4
+    }
+    Separator {
+        Normal {
+            vector      [ 0 -1 -2.77556e-17,
+                          0 -1 -2.77556e-17,
+                          0 -1 -2.77556e-17,
+                          0 -1.37113e-14 -1,
+                          0 -1.37113e-14 -1,
+                          0 -1.37113e-14 -1,
+                          0 -1 -2.77556e-17,
+                          0 -1 -2.77556e-17,
+                          0 -1 -2.77556e-17,
+                          0 -1 -2.77556e-17,
+                          0 -1 -2.77556e-17,
+                          0 -1 -2.77556e-17,
+                          0 -1 -2.77556e-17,
+                          0 -1 -2.77556e-17,
+                          0 -1 -2.77556e-17,
+                          0 -1 -2.77556e-17,
+                          0 -1 -2.77556e-17,
+                          0 -1 -2.77556e-17,
+                          0 -1 -2.77556e-17,
+                          0 -1 -2.77556e-17,
+                          0 -1 -2.77556e-17,
+                          0 -1 -2.77556e-17,
+                          0 -1 -2.77556e-17,
+                          0 -1 -2.77556e-17,
+                          0 -1 -2.77556e-17,
+                          0 -1 -2.77556e-17,
+                          0 -1 -2.77556e-17,
+                          0.925169 5.20417e-15 0.379555,
+                          0.925169 5.20417e-15 0.379555,
+                          0.925169 5.20417e-15 0.379555,
+                          0.925169 5.20417e-15 0.379555,
+                          0.925169 5.20417e-15 0.379555,
+                          0.925169 5.20417e-15 0.379555,
+                          -0.925303 5.19723e-15 0.379229,
+                          -0.925303 5.19723e-15 0.379229,
+                          -0.925303 5.19723e-15 0.379229,
+                          0 -1.37113e-14 -1,
+                          0 -1.37113e-14 -1,
+                          0 -1.37113e-14 -1,
+                          -0.924507 2.51188e-14 0.381165,
+                          -0.924507 2.51257e-14 0.381165,
+                          -0.709382 4.93217e-14 0.704824,
+                          -0.925303 5.19723e-15 0.379229,
+                          -0.925303 5.19723e-15 0.379229,
+                          -0.925303 5.19723e-15 0.379229,
+                          -0.709382 4.93217e-14 0.704824,
+                          -0.709382 4.93217e-14 0.704824,
+                          -0.384121 1.26843e-14 0.923283,
+                          -0.924507 2.51188e-14 0.381165,
+                          -0.709382 4.93217e-14 0.704824,
+                          -0.709382 4.93217e-14 0.704824,
+                          -0.384121 1.26843e-14 0.923283,
+                          -0.384121 1.26843e-14 0.923283,
+                          -0.0017717 6.99718e-14 0.999998,
+                          -0.709382 4.93217e-14 0.704824,
+                          -0.384121 1.26843e-14 0.923283,
+                          -0.384121 1.26843e-14 0.923283,
+                          0 6.99718e-14 1,
+                          0 6.99718e-14 1,
+                          0 6.99718e-14 1,
+                          -0.384121 1.26843e-14 0.923283,
+                          -0.0017717 6.99718e-14 0.999998,
+                          -0.0017717 6.99718e-14 0.999998,
+                          0.0017697 6.99718e-14 0.999998,
+                          0.0017697 6.99718e-14 0.999998,
+                          0.384012 6.83897e-14 0.923328,
+                          0 6.99718e-14 1,
+                          0 6.99718e-14 1,
+                          0 6.99718e-14 1,
+                          0.384012 6.8362e-14 0.923328,
+                          0.384012 6.83897e-14 0.923328,
+                          0.709217 4.93355e-14 0.704991,
+                          0.0017697 6.99718e-14 0.999998,
+                          0.384012 6.83897e-14 0.923328,
+                          0.384012 6.8362e-14 0.923328,
+                          0.709217 4.93494e-14 0.704991,
+                          0.709217 4.93355e-14 0.704991,
+                          0.924374 5.23886e-15 0.381489,
+                          0.384012 6.8362e-14 0.923328,
+                          0.709217 4.93355e-14 0.704991,
+                          0.709217 4.93494e-14 0.704991,
+                          0.709217 4.93494e-14 0.704991,
+                          0.924374 5.23886e-15 0.381489,
+                          0.924374 5.23886e-15 0.381489,
+                          0 1 2.77556e-17,
+                          0 1 2.77556e-17,
+                          0 1 2.77556e-17,
+                          0 1 2.77556e-17,
+                          0 1 2.77556e-17,
+                          0 1 2.77556e-17,
+                          0 1 2.77556e-17,
+                          0 1 2.77556e-17,
+                          0 1 2.77556e-17,
+                          0 1 2.77556e-17,
+                          0 1 2.77556e-17,
+                          0 1 2.77556e-17,
+                          0 1 2.77556e-17,
+                          0 1 2.77556e-17,
+                          0 1 2.77556e-17,
+                          0 1 2.77556e-17,
+                          0 1 2.77556e-17,
+                          0 1 2.77556e-17,
+                          0 1 2.77556e-17,
+                          0 1 2.77556e-17,
+                          0 1 2.77556e-17,
+                          0 1 2.77556e-17,
+                          0 1 2.77556e-17,
+                          0 1 2.77556e-17 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -37.5675 -70 133.941,
+                          -92.687 -70 -0.548326,
+                          94.7971 -70 -0.548326,
+                          94.7971 -69 -0.548326,
+                          94.7971 -70 -0.548326,
+                          -92.687 -70 -0.548326,
+                          -32.137 -70 142.132,
+                          -37.5675 -70 133.941,
+                          94.7971 -70 -0.548326,
+                          -24.0163 -70 147.588,
+                          -32.137 -70 142.132,
+                          94.7971 -70 -0.548326,
+                          -14.4528 -70 149.5,
+                          -24.0163 -70 147.588,
+                          94.7971 -70 -0.548326,
+                          16.5076 -70 149.5,
+                          -14.4528 -70 149.5,
+                          94.7971 -70 -0.548326,
+                          26.0683 -70 147.589,
+                          16.5076 -70 149.5,
+                          94.7971 -70 -0.548326,
+                          34.1876 -70 142.136,
+                          26.0683 -70 147.589,
+                          94.7971 -70 -0.548326,
+                          39.6189 -70 133.949,
+                          34.1876 -70 142.136,
+                          94.7971 -70 -0.548326,
+                          39.6189 -69 133.949,
+                          39.6189 -70 133.949,
+                          94.7971 -70 -0.548326,
+                          39.6189 -69 133.949,
+                          94.7971 -70 -0.548326,
+                          94.7971 -69 -0.548326,
+                          -92.687 -69 -0.548326,
+                          -92.687 -70 -0.548326,
+                          -37.5675 -70 133.941,
+                          -92.687 -69 -0.548326,
+                          94.7971 -69 -0.548326,
+                          -92.687 -70 -0.548326,
+                          -37.5675 -69 133.941,
+                          -37.5675 -70 133.941,
+                          -32.137 -70 142.132,
+                          -92.687 -69 -0.548326,
+                          -37.5675 -70 133.941,
+                          -37.5675 -69 133.941,
+                          -32.137 -69 142.132,
+                          -32.137 -70 142.132,
+                          -24.0163 -70 147.588,
+                          -37.5675 -69 133.941,
+                          -32.137 -70 142.132,
+                          -32.137 -69 142.132,
+                          -24.0163 -69 147.588,
+                          -24.0163 -70 147.588,
+                          -14.4528 -70 149.5,
+                          -32.137 -69 142.132,
+                          -24.0163 -70 147.588,
+                          -24.0163 -69 147.588,
+                          -14.4528 -69 149.5,
+                          -14.4528 -70 149.5,
+                          16.5076 -70 149.5,
+                          -24.0163 -69 147.588,
+                          -14.4528 -70 149.5,
+                          -14.4528 -69 149.5,
+                          16.5076 -69 149.5,
+                          16.5076 -70 149.5,
+                          26.0683 -70 147.589,
+                          -14.4528 -69 149.5,
+                          16.5076 -70 149.5,
+                          16.5076 -69 149.5,
+                          26.0683 -69 147.589,
+                          26.0683 -70 147.589,
+                          34.1876 -70 142.136,
+                          16.5076 -69 149.5,
+                          26.0683 -70 147.589,
+                          26.0683 -69 147.589,
+                          34.1876 -69 142.136,
+                          34.1876 -70 142.136,
+                          39.6189 -70 133.949,
+                          26.0683 -69 147.589,
+                          34.1876 -70 142.136,
+                          34.1876 -69 142.136,
+                          34.1876 -69 142.136,
+                          39.6189 -70 133.949,
+                          39.6189 -69 133.949,
+                          -92.687 -69 -0.548326,
+                          39.6189 -69 133.949,
+                          94.7971 -69 -0.548326,
+                          -92.687 -69 -0.548326,
+                          34.1876 -69 142.136,
+                          39.6189 -69 133.949,
+                          -92.687 -69 -0.548326,
+                          26.0683 -69 147.589,
+                          34.1876 -69 142.136,
+                          -92.687 -69 -0.548326,
+                          16.5076 -69 149.5,
+                          26.0683 -69 147.589,
+                          -92.687 -69 -0.548326,
+                          -14.4528 -69 149.5,
+                          16.5076 -69 149.5,
+                          -92.687 -69 -0.548326,
+                          -24.0163 -69 147.588,
+                          -14.4528 -69 149.5,
+                          -92.687 -69 -0.548326,
+                          -32.137 -69 142.132,
+                          -24.0163 -69 147.588,
+                          -92.687 -69 -0.548326,
+                          -37.5675 -69 133.941,
+                          -32.137 -69 142.132 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.85 0.9 0.47
+    }
+    Separator {
+        Normal {
+            vector      [ 0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 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,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -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,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 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,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -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,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -0.382683 -0.92388 0,
+                          0.382683 -0.92388 0,
+                          0.382683 -0.92388 0,
+                          1.83691e-16 -1 0,
+                          0.382683 -0.92388 0,
+                          1.83691e-16 -1 0,
+                          1.83691e-16 -1 0,
+                          -0.382683 -0.92388 0,
+                          -0.382683 -0.92388 0,
+                          -0.707107 -0.707107 0,
+                          -0.382683 -0.92388 0,
+                          -6.12303e-17 -1 0,
+                          -0.382683 -0.92388 0,
+                          -0.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          -0.92388 -0.382683 0,
+                          -0.382683 -0.92388 0,
+                          -0.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          -0.92388 -0.382683 0,
+                          -0.92388 -0.382683 0,
+                          -1 0 0,
+                          -0.707107 -0.707107 0,
+                          -0.92388 -0.382683 0,
+                          -0.92388 -0.382683 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.92388 0.382683 0,
+                          -0.92388 -0.382683 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.92388 0.382683 0,
+                          -0.92388 0.382683 0,
+                          -0.707107 0.707107 0,
+                          -1 0 0,
+                          -0.92388 0.382683 0,
+                          -0.92388 0.382683 0,
+                          -0.707107 0.707107 0,
+                          -0.707107 0.707107 0,
+                          -0.382683 0.92388 0,
+                          -0.92388 0.382683 0,
+                          -0.707107 0.707107 0,
+                          -0.707107 0.707107 0,
+                          -0.382683 0.92388 0,
+                          -0.382683 0.92388 0,
+                          -6.12303e-17 1 0,
+                          -0.707107 0.707107 0,
+                          -0.382683 0.92388 0,
+                          -0.382683 0.92388 0,
+                          -6.12303e-17 1 0,
+                          -6.12303e-17 1 0,
+                          0.382683 0.92388 0,
+                          -0.382683 0.92388 0,
+                          -6.12303e-17 1 0,
+                          -6.12303e-17 1 0,
+                          0.382683 0.92388 0,
+                          0.382683 0.92388 0,
+                          0.707107 0.707107 0,
+                          -6.12303e-17 1 0,
+                          0.382683 0.92388 0,
+                          0.382683 0.92388 0,
+                          0.707107 0.707107 0,
+                          0.707107 0.707107 0,
+                          0.92388 0.382683 0,
+                          0.382683 0.92388 0,
+                          0.707107 0.707107 0,
+                          0.707107 0.707107 0,
+                          0.92388 0.382683 0,
+                          0.92388 0.382683 0,
+                          1 1.22461e-16 0,
+                          0.707107 0.707107 0,
+                          0.92388 0.382683 0,
+                          0.92388 0.382683 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          0.92388 -0.382683 0,
+                          0.92388 0.382683 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          0.92388 -0.382683 0,
+                          0.92388 -0.382683 0,
+                          0.707107 -0.707107 0,
+                          1 1.22461e-16 0,
+                          0.92388 -0.382683 0,
+                          0.92388 -0.382683 0,
+                          0.707107 -0.707107 0,
+                          0.707107 -0.707107 0,
+                          0.382683 -0.92388 0,
+                          0.92388 -0.382683 0,
+                          0.707107 -0.707107 0,
+                          0.707107 -0.707107 0,
+                          0.707107 -0.707107 0,
+                          0.382683 -0.92388 0,
+                          0.382683 -0.92388 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,
+                          3.06152e-16 1 0,
+                          3.06152e-16 1 0,
+                          0.382683 0.92388 0,
+                          -0.382683 0.92388 0,
+                          -0.382683 0.92388 0,
+                          1.83691e-16 1 0,
+                          -0.382683 0.92388 0,
+                          1.83691e-16 1 0,
+                          6.12303e-17 1 0,
+                          0.382683 0.92388 0,
+                          0.382683 0.92388 0,
+                          0.707107 0.707107 0,
+                          0.382683 0.92388 0,
+                          3.06152e-16 1 0,
+                          0.382683 0.92388 0,
+                          0.707107 0.707107 0,
+                          0.707107 0.707107 0,
+                          0.92388 0.382683 0,
+                          0.382683 0.92388 0,
+                          0.707107 0.707107 0,
+                          0.707107 0.707107 0,
+                          0.92388 0.382683 0,
+                          0.92388 0.382683 0,
+                          1 -2.44921e-16 0,
+                          0.707107 0.707107 0,
+                          0.92388 0.382683 0,
+                          0.92388 0.382683 0,
+                          1 -2.44921e-16 0,
+                          1 -2.44921e-16 0,
+                          0.92388 -0.382683 0,
+                          0.92388 0.382683 0,
+                          1 -2.44921e-16 0,
+                          1 -2.44921e-16 0,
+                          0.92388 -0.382683 0,
+                          0.92388 -0.382683 0,
+                          0.707107 -0.707107 0,
+                          1 -2.44921e-16 0,
+                          0.92388 -0.382683 0,
+                          0.92388 -0.382683 0,
+                          0.707107 -0.707107 0,
+                          0.707107 -0.707107 0,
+                          0.382683 -0.92388 0,
+                          0.92388 -0.382683 0,
+                          0.707107 -0.707107 0,
+                          0.707107 -0.707107 0,
+                          0.382683 -0.92388 0,
+                          0.382683 -0.92388 0,
+                          -1.83691e-16 -1 0,
+                          0.707107 -0.707107 0,
+                          0.382683 -0.92388 0,
+                          0.382683 -0.92388 0,
+                          -1.83691e-16 -1 0,
+                          -1.83691e-16 -1 0,
+                          -0.382683 -0.92388 0,
+                          0.382683 -0.92388 0,
+                          -1.83691e-16 -1 0,
+                          -1.83691e-16 -1 0,
+                          -0.382683 -0.92388 0,
+                          -0.382683 -0.92388 0,
+                          -0.707107 -0.707107 0,
+                          -1.83691e-16 -1 0,
+                          -0.382683 -0.92388 0,
+                          -0.382683 -0.92388 0,
+                          -0.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          -0.92388 -0.382683 0,
+                          -0.382683 -0.92388 0,
+                          -0.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          -0.92388 -0.382683 0,
+                          -0.92388 -0.382683 0,
+                          -1 5.6655e-16 0,
+                          -0.707107 -0.707107 0,
+                          -0.92388 -0.382683 0,
+                          -0.92388 -0.382683 0,
+                          -1 5.6655e-16 0,
+                          -1 5.6655e-16 0,
+                          -0.92388 0.382683 0,
+                          -0.92388 -0.382683 0,
+                          -1 5.6655e-16 0,
+                          -1 5.6655e-16 0,
+                          -0.92388 0.382683 0,
+                          -0.92388 0.382683 0,
+                          -0.707107 0.707107 0,
+                          -1 5.6655e-16 0,
+                          -0.92388 0.382683 0,
+                          -0.92388 0.382683 0,
+                          -0.707107 0.707107 0,
+                          -0.707107 0.707107 0,
+                          -0.382683 0.92388 0,
+                          -0.92388 0.382683 0,
+                          -0.707107 0.707107 0,
+                          -0.707107 0.707107 0,
+                          -0.707107 0.707107 0,
+                          -0.382683 0.92388 0,
+                          -0.382683 0.92388 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 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -45 -6.23541e-14 7,
+                          -49.5 -49.5 7,
+                          -49.5 49.5 7,
+                          -49.5 49.5 33,
+                          -49.5 49.5 7,
+                          -49.5 -49.5 7,
+                          -2.75536e-15 45 7,
+                          -49.5 49.5 7,
+                          49.5 49.5 7,
+                          49.5 49.5 33,
+                          49.5 49.5 7,
+                          -49.5 49.5 7,
+                          -17.2226 41.5736 7,
+                          -49.5 49.5 7,
+                          -2.75536e-15 45 7,
+                          -41.5736 17.2226 7,
+                          -45 -6.23541e-14 7,
+                          -49.5 49.5 7,
+                          -31.8195 31.8195 7,
+                          -41.5736 17.2226 7,
+                          -49.5 49.5 7,
+                          -17.2226 41.5736 7,
+                          -31.8195 31.8195 7,
+                          -49.5 49.5 7,
+                          49.5 49.5 33,
+                          -49.5 49.5 7,
+                          -49.5 49.5 33,
+                          2.75536e-15 -45 7,
+                          49.5 -49.5 7,
+                          -49.5 -49.5 7,
+                          -49.5 -49.5 33,
+                          -49.5 -49.5 7,
+                          49.5 -49.5 7,
+                          -17.2226 -41.5736 7,
+                          2.75536e-15 -45 7,
+                          -49.5 -49.5 7,
+                          -31.8195 -31.8195 7,
+                          -17.2226 -41.5736 7,
+                          -49.5 -49.5 7,
+                          -41.5736 -17.2226 7,
+                          -31.8195 -31.8195 7,
+                          -49.5 -49.5 7,
+                          -45 -6.23541e-14 7,
+                          -41.5736 -17.2226 7,
+                          -49.5 -49.5 7,
+                          -49.5 -49.5 33,
+                          -49.5 49.5 33,
+                          -49.5 -49.5 7,
+                          45 -5.68434e-14 7,
+                          49.5 49.5 7,
+                          49.5 -49.5 7,
+                          49.5 -49.5 33,
+                          49.5 -49.5 7,
+                          49.5 49.5 7,
+                          41.5736 -17.2226 7,
+                          45 -5.68434e-14 7,
+                          49.5 -49.5 7,
+                          31.8195 -31.8195 7,
+                          41.5736 -17.2226 7,
+                          49.5 -49.5 7,
+                          17.2226 -41.5736 7,
+                          31.8195 -31.8195 7,
+                          49.5 -49.5 7,
+                          2.75536e-15 -45 7,
+                          17.2226 -41.5736 7,
+                          49.5 -49.5 7,
+                          -49.5 -49.5 33,
+                          49.5 -49.5 7,
+                          49.5 -49.5 33,
+                          17.2226 41.5736 7,
+                          -2.75536e-15 45 7,
+                          49.5 49.5 7,
+                          31.8195 31.8195 7,
+                          17.2226 41.5736 7,
+                          49.5 49.5 7,
+                          41.5736 17.2226 7,
+                          31.8195 31.8195 7,
+                          49.5 49.5 7,
+                          45 -5.68434e-14 7,
+                          41.5736 17.2226 7,
+                          49.5 49.5 7,
+                          49.5 -49.5 33,
+                          49.5 49.5 7,
+                          49.5 49.5 33,
+                          -2.75536e-15 45 30,
+                          -2.75536e-15 45 7,
+                          17.2226 41.5736 7,
+                          -17.2219 41.5736 30,
+                          -17.2226 41.5736 7,
+                          -2.75536e-15 45 7,
+                          -17.2219 41.5736 30,
+                          -2.75536e-15 45 7,
+                          -2.75536e-15 45 30,
+                          17.2219 41.5736 30,
+                          17.2226 41.5736 7,
+                          31.8195 31.8195 7,
+                          17.2219 41.5736 30,
+                          -2.75536e-15 45 30,
+                          17.2226 41.5736 7,
+                          31.8179 31.8213 30,
+                          31.8195 31.8195 7,
+                          41.5736 17.2226 7,
+                          17.2219 41.5736 30,
+                          31.8195 31.8195 7,
+                          31.8179 31.8213 30,
+                          41.5753 17.2188 30,
+                          41.5736 17.2226 7,
+                          45 -5.68434e-14 7,
+                          31.8179 31.8213 30,
+                          41.5736 17.2226 7,
+                          41.5753 17.2188 30,
+                          44.9995 -5.69342e-14 30,
+                          45 -5.68434e-14 7,
+                          41.5736 -17.2226 7,
+                          41.5753 17.2188 30,
+                          45 -5.68434e-14 7,
+                          44.9995 -5.69342e-14 30,
+                          41.5753 -17.2188 30,
+                          41.5736 -17.2226 7,
+                          31.8195 -31.8195 7,
+                          44.9995 -5.69342e-14 30,
+                          41.5736 -17.2226 7,
+                          41.5753 -17.2188 30,
+                          31.8179 -31.8213 30,
+                          31.8195 -31.8195 7,
+                          17.2226 -41.5736 7,
+                          41.5753 -17.2188 30,
+                          31.8195 -31.8195 7,
+                          31.8179 -31.8213 30,
+                          17.2219 -41.5736 30,
+                          17.2226 -41.5736 7,
+                          2.75536e-15 -45 7,
+                          31.8179 -31.8213 30,
+                          17.2226 -41.5736 7,
+                          17.2219 -41.5736 30,
+                          2.75536e-15 -45 30,
+                          2.75536e-15 -45 7,
+                          -17.2226 -41.5736 7,
+                          17.2219 -41.5736 30,
+                          2.75536e-15 -45 7,
+                          2.75536e-15 -45 30,
+                          -17.2219 -41.5736 30,
+                          -17.2226 -41.5736 7,
+                          -31.8195 -31.8195 7,
+                          2.75536e-15 -45 30,
+                          -17.2226 -41.5736 7,
+                          -17.2219 -41.5736 30,
+                          -31.8179 -31.8213 30,
+                          -31.8195 -31.8195 7,
+                          -41.5736 -17.2226 7,
+                          -17.2219 -41.5736 30,
+                          -31.8195 -31.8195 7,
+                          -31.8179 -31.8213 30,
+                          -41.5753 -17.2188 30,
+                          -41.5736 -17.2226 7,
+                          -45 -6.23541e-14 7,
+                          -31.8179 -31.8213 30,
+                          -41.5736 -17.2226 7,
+                          -41.5753 -17.2188 30,
+                          -44.9995 -6.23037e-14 30,
+                          -45 -6.23541e-14 7,
+                          -41.5736 17.2226 7,
+                          -41.5753 -17.2188 30,
+                          -45 -6.23541e-14 7,
+                          -44.9995 -6.23037e-14 30,
+                          -41.5753 17.2188 30,
+                          -41.5736 17.2226 7,
+                          -31.8195 31.8195 7,
+                          -44.9995 -6.23037e-14 30,
+                          -41.5736 17.2226 7,
+                          -41.5753 17.2188 30,
+                          -31.8179 31.8213 30,
+                          -31.8195 31.8195 7,
+                          -17.2226 41.5736 7,
+                          -41.5753 17.2188 30,
+                          -31.8195 31.8195 7,
+                          -31.8179 31.8213 30,
+                          -31.8179 31.8213 30,
+                          -17.2226 41.5736 7,
+                          -17.2219 41.5736 30,
+                          -15.6917 37.8781 30,
+                          -17.2219 41.5736 30,
+                          -2.75536e-15 45 30,
+                          7.53133e-15 41 30,
+                          -2.75536e-15 45 30,
+                          17.2219 41.5736 30,
+                          7.53133e-15 41 30,
+                          -15.6917 37.8781 30,
+                          -2.75536e-15 45 30,
+                          -28.9911 28.9911 30,
+                          -31.8179 31.8213 30,
+                          -17.2219 41.5736 30,
+                          -15.6917 37.8781 30,
+                          -28.9911 28.9911 30,
+                          -17.2219 41.5736 30,
+                          -37.8781 15.6917 30,
+                          -41.5753 17.2188 30,
+                          -31.8179 31.8213 30,
+                          -28.9911 28.9911 30,
+                          -37.8781 15.6917 30,
+                          -31.8179 31.8213 30,
+                          -41.5753 -17.2188 30,
+                          -44.9995 -6.23037e-14 30,
+                          -41.5753 17.2188 30,
+                          -41 -4.68016e-14 30,
+                          -41.5753 -17.2188 30,
+                          -41.5753 17.2188 30,
+                          -37.8781 15.6917 30,
+                          -41 -4.68016e-14 30,
+                          -41.5753 17.2188 30,
+                          -37.8781 -15.6917 30,
+                          -31.8179 -31.8213 30,
+                          -41.5753 -17.2188 30,
+                          -41 -4.68016e-14 30,
+                          -37.8781 -15.6917 30,
+                          -41.5753 -17.2188 30,
+                          -28.9911 -28.9911 30,
+                          -17.2219 -41.5736 30,
+                          -31.8179 -31.8213 30,
+                          -37.8781 -15.6917 30,
+                          -28.9911 -28.9911 30,
+                          -31.8179 -31.8213 30,
+                          -7.53133e-15 -41 30,
+                          2.75536e-15 -45 30,
+                          -17.2219 -41.5736 30,
+                          -15.6917 -37.8781 30,
+                          -7.53133e-15 -41 30,
+                          -17.2219 -41.5736 30,
+                          -28.9911 -28.9911 30,
+                          -15.6917 -37.8781 30,
+                          -17.2219 -41.5736 30,
+                          15.6917 -37.8781 30,
+                          17.2219 -41.5736 30,
+                          2.75536e-15 -45 30,
+                          15.6917 -37.8781 30,
+                          2.75536e-15 -45 30,
+                          -7.53133e-15 -41 30,
+                          28.9911 -28.9911 30,
+                          31.8179 -31.8213 30,
+                          17.2219 -41.5736 30,
+                          15.6917 -37.8781 30,
+                          28.9911 -28.9911 30,
+                          17.2219 -41.5736 30,
+                          37.8781 -15.6917 30,
+                          41.5753 -17.2188 30,
+                          31.8179 -31.8213 30,
+                          28.9911 -28.9911 30,
+                          37.8781 -15.6917 30,
+                          31.8179 -31.8213 30,
+                          41.5753 17.2188 30,
+                          44.9995 -5.69342e-14 30,
+                          41.5753 -17.2188 30,
+                          41 -8.0072e-14 30,
+                          41.5753 17.2188 30,
+                          41.5753 -17.2188 30,
+                          37.8781 -15.6917 30,
+                          41 -8.0072e-14 30,
+                          41.5753 -17.2188 30,
+                          37.8781 15.6917 30,
+                          31.8179 31.8213 30,
+                          41.5753 17.2188 30,
+                          41 -8.0072e-14 30,
+                          37.8781 15.6917 30,
+                          41.5753 17.2188 30,
+                          28.9911 28.9911 30,
+                          17.2219 41.5736 30,
+                          31.8179 31.8213 30,
+                          37.8781 15.6917 30,
+                          28.9911 28.9911 30,
+                          31.8179 31.8213 30,
+                          15.6917 37.8781 30,
+                          7.53133e-15 41 30,
+                          17.2219 41.5736 30,
+                          28.9911 28.9911 30,
+                          15.6917 37.8781 30,
+                          17.2219 41.5736 30,
+                          -2.51044e-15 -41 33,
+                          -7.53133e-15 -41 30,
+                          -15.6917 -37.8781 30,
+                          15.6917 -37.8781 33,
+                          15.6917 -37.8781 30,
+                          -7.53133e-15 -41 30,
+                          15.6917 -37.8781 33,
+                          -7.53133e-15 -41 30,
+                          -2.51044e-15 -41 33,
+                          -15.6917 -37.8781 33,
+                          -15.6917 -37.8781 30,
+                          -28.9911 -28.9911 30,
+                          -15.6917 -37.8781 33,
+                          -2.51044e-15 -41 33,
+                          -15.6917 -37.8781 30,
+                          -28.9911 -28.9911 33,
+                          -28.9911 -28.9911 30,
+                          -37.8781 -15.6917 30,
+                          -15.6917 -37.8781 33,
+                          -28.9911 -28.9911 30,
+                          -28.9911 -28.9911 33,
+                          -37.8781 -15.6917 33,
+                          -37.8781 -15.6917 30,
+                          -41 -4.68016e-14 30,
+                          -28.9911 -28.9911 33,
+                          -37.8781 -15.6917 30,
+                          -37.8781 -15.6917 33,
+                          -41 -5.4333e-14 33,
+                          -41 -4.68016e-14 30,
+                          -37.8781 15.6917 30,
+                          -37.8781 -15.6917 33,
+                          -41 -4.68016e-14 30,
+                          -41 -5.4333e-14 33,
+                          -37.8781 15.6917 33,
+                          -37.8781 15.6917 30,
+                          -28.9911 28.9911 30,
+                          -41 -5.4333e-14 33,
+                          -37.8781 15.6917 30,
+                          -37.8781 15.6917 33,
+                          -28.9911 28.9911 33,
+                          -28.9911 28.9911 30,
+                          -15.6917 37.8781 30,
+                          -37.8781 15.6917 33,
+                          -28.9911 28.9911 30,
+                          -28.9911 28.9911 33,
+                          -15.6917 37.8781 33,
+                          -15.6917 37.8781 30,
+                          7.53133e-15 41 30,
+                          -28.9911 28.9911 33,
+                          -15.6917 37.8781 30,
+                          -15.6917 37.8781 33,
+                          9.61587e-15 41 33,
+                          7.53133e-15 41 30,
+                          15.6917 37.8781 30,
+                          -15.6917 37.8781 33,
+                          7.53133e-15 41 30,
+                          9.61587e-15 41 33,
+                          15.6917 37.8781 33,
+                          15.6917 37.8781 30,
+                          28.9911 28.9911 30,
+                          9.61587e-15 41 33,
+                          15.6917 37.8781 30,
+                          15.6917 37.8781 33,
+                          28.9911 28.9911 33,
+                          28.9911 28.9911 30,
+                          37.8781 15.6917 30,
+                          15.6917 37.8781 33,
+                          28.9911 28.9911 30,
+                          28.9911 28.9911 33,
+                          37.8781 15.6917 33,
+                          37.8781 15.6917 30,
+                          41 -8.0072e-14 30,
+                          28.9911 28.9911 33,
+                          37.8781 15.6917 30,
+                          37.8781 15.6917 33,
+                          41 -8.06701e-14 33,
+                          41 -8.0072e-14 30,
+                          37.8781 -15.6917 30,
+                          37.8781 15.6917 33,
+                          41 -8.0072e-14 30,
+                          41 -8.06701e-14 33,
+                          37.8781 -15.6917 33,
+                          37.8781 -15.6917 30,
+                          28.9911 -28.9911 30,
+                          41 -8.06701e-14 33,
+                          37.8781 -15.6917 30,
+                          37.8781 -15.6917 33,
+                          28.9911 -28.9911 33,
+                          28.9911 -28.9911 30,
+                          15.6917 -37.8781 30,
+                          37.8781 -15.6917 33,
+                          28.9911 -28.9911 30,
+                          28.9911 -28.9911 33,
+                          28.9911 -28.9911 33,
+                          15.6917 -37.8781 30,
+                          15.6917 -37.8781 33,
+                          9.61587e-15 41 33,
+                          49.5 49.5 33,
+                          -49.5 49.5 33,
+                          -41 -5.4333e-14 33,
+                          -49.5 49.5 33,
+                          -49.5 -49.5 33,
+                          -15.6917 37.8781 33,
+                          9.61587e-15 41 33,
+                          -49.5 49.5 33,
+                          -28.9911 28.9911 33,
+                          -15.6917 37.8781 33,
+                          -49.5 49.5 33,
+                          -37.8781 15.6917 33,
+                          -28.9911 28.9911 33,
+                          -49.5 49.5 33,
+                          -41 -5.4333e-14 33,
+                          -37.8781 15.6917 33,
+                          -49.5 49.5 33,
+                          41 -8.06701e-14 33,
+                          49.5 -49.5 33,
+                          49.5 49.5 33,
+                          37.8781 15.6917 33,
+                          41 -8.06701e-14 33,
+                          49.5 49.5 33,
+                          28.9911 28.9911 33,
+                          37.8781 15.6917 33,
+                          49.5 49.5 33,
+                          15.6917 37.8781 33,
+                          28.9911 28.9911 33,
+                          49.5 49.5 33,
+                          9.61587e-15 41 33,
+                          15.6917 37.8781 33,
+                          49.5 49.5 33,
+                          -2.51044e-15 -41 33,
+                          -49.5 -49.5 33,
+                          49.5 -49.5 33,
+                          15.6917 -37.8781 33,
+                          -2.51044e-15 -41 33,
+                          49.5 -49.5 33,
+                          28.9911 -28.9911 33,
+                          15.6917 -37.8781 33,
+                          49.5 -49.5 33,
+                          37.8781 -15.6917 33,
+                          28.9911 -28.9911 33,
+                          49.5 -49.5 33,
+                          41 -8.06701e-14 33,
+                          37.8781 -15.6917 33,
+                          49.5 -49.5 33,
+                          -15.6917 -37.8781 33,
+                          -49.5 -49.5 33,
+                          -2.51044e-15 -41 33,
+                          -37.8781 -15.6917 33,
+                          -41 -5.4333e-14 33,
+                          -49.5 -49.5 33,
+                          -28.9911 -28.9911 33,
+                          -37.8781 -15.6917 33,
+                          -49.5 -49.5 33,
+                          -15.6917 -37.8781 33,
+                          -28.9911 -28.9911 33,
+                          -49.5 -49.5 33 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -1 6.12303e-17 -2.44921e-16,
+                          -1 6.12303e-17 -2.44921e-16,
+                          -0.809017 4.95364e-17 -0.587785,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -0.809017 4.95364e-17 0.587785,
+                          -0.809017 4.95364e-17 0.587785,
+                          -1 6.12303e-17 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -0.809017 4.95364e-17 0.587785,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 3.21629e-16,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -0.809017 4.95364e-17 -0.587785,
+                          -0.809017 4.95364e-17 -0.587785,
+                          -0.309017 1.89212e-17 -0.951057,
+                          -0.809017 4.95364e-17 -0.587785,
+                          -1 6.12303e-17 -2.44921e-16,
+                          -0.809017 4.95364e-17 -0.587785,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -0.309017 1.89212e-17 -0.951057,
+                          -0.309017 1.89212e-17 -0.951057,
+                          0.309017 -1.89212e-17 -0.951057,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -0.809017 4.95364e-17 -0.587785,
+                          -0.309017 1.89212e-17 -0.951057,
+                          -0.309017 1.89212e-17 -0.951057,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          0.309017 -1.89212e-17 -0.951057,
+                          0.309017 -1.89212e-17 -0.951057,
+                          0.809017 -4.95364e-17 -0.587785,
+                          -0.309017 1.89212e-17 -0.951057,
+                          0.309017 -1.89212e-17 -0.951057,
+                          0.309017 -1.89212e-17 -0.951057,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          0.809017 -4.95364e-17 -0.587785,
+                          0.809017 -4.95364e-17 -0.587785,
+                          1 -6.12303e-17 1.22461e-16,
+                          0.309017 -1.89212e-17 -0.951057,
+                          0.809017 -4.95364e-17 -0.587785,
+                          0.809017 -4.95364e-17 -0.587785,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          1 -6.12303e-17 1.22461e-16,
+                          1 -6.12303e-17 1.22461e-16,
+                          0.809017 -4.95364e-17 0.587785,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          0.809017 -4.95364e-17 -0.587785,
+                          1 -6.12303e-17 1.22461e-16,
+                          1 -6.12303e-17 1.22461e-16,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          0.809017 -4.95364e-17 0.587785,
+                          0.809017 -4.95364e-17 0.587785,
+                          0.309017 -1.89212e-17 0.951057,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          1 -6.12303e-17 1.22461e-16,
+                          0.809017 -4.95364e-17 0.587785,
+                          0.809017 -4.95364e-17 0.587785,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          0.309017 -1.89212e-17 0.951057,
+                          0.309017 -1.89212e-17 0.951057,
+                          -0.309017 1.89212e-17 0.951057,
+                          0.809017 -4.95364e-17 0.587785,
+                          0.309017 -1.89212e-17 0.951057,
+                          0.309017 -1.89212e-17 0.951057,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -0.309017 1.89212e-17 0.951057,
+                          -0.309017 1.89212e-17 0.951057,
+                          -0.809017 4.95364e-17 0.587785,
+                          0.309017 -1.89212e-17 0.951057,
+                          -0.309017 1.89212e-17 0.951057,
+                          -0.309017 1.89212e-17 0.951057,
+                          -0.309017 1.89212e-17 0.951057,
+                          -0.809017 4.95364e-17 0.587785,
+                          -0.809017 4.95364e-17 0.587785,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          0.611162 -3.74217e-17 0.791505,
+                          0.611162 -3.74217e-17 0.791505,
+                          0.611162 -3.74217e-17 0.791505,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          0.611162 -3.74217e-17 0.791505,
+                          0.611162 -3.74217e-17 0.791505,
+                          0.611162 -3.74217e-17 0.791505,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.994522 6.08949e-17 0.104528,
+                          -0.994522 6.08949e-17 0.104528,
+                          -0.994522 6.08949e-17 0.104528,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.994522 6.08949e-17 0.104528,
+                          -0.994522 6.08949e-17 0.104528,
+                          -0.994522 6.08949e-17 0.104528,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 21.5 49.5 155.5,
+                          12.9452 49.5 136.403,
+                          16 49.5 127,
+                          16 54.5 127,
+                          16 49.5 127,
+                          12.9452 49.5 136.403,
+                          32 49.5 55,
+                          16 49.5 127,
+                          12.9452 49.5 117.597,
+                          12.9452 54.5 117.597,
+                          12.9452 49.5 117.597,
+                          16 49.5 127,
+                          21.5 49.5 155.5,
+                          16 49.5 127,
+                          32 49.5 55,
+                          12.9452 54.5 117.597,
+                          16 49.5 127,
+                          16 54.5 127,
+                          21.5 49.5 155.5,
+                          4.94504 49.5 142.216,
+                          12.9452 49.5 136.403,
+                          12.9452 54.5 136.403,
+                          12.9452 49.5 136.403,
+                          4.94504 49.5 142.216,
+                          12.9452 54.5 136.403,
+                          16 54.5 127,
+                          12.9452 49.5 136.403,
+                          -21.5 49.5 155.5,
+                          -4.94504 49.5 142.216,
+                          4.94504 49.5 142.216,
+                          4.94504 54.5 142.216,
+                          4.94504 49.5 142.216,
+                          -4.94504 49.5 142.216,
+                          -21.5 49.5 155.5,
+                          4.94504 49.5 142.216,
+                          21.5 49.5 155.5,
+                          12.9452 54.5 136.403,
+                          4.94504 49.5 142.216,
+                          4.94504 54.5 142.216,
+                          -21.5 49.5 155.5,
+                          -12.9452 49.5 136.403,
+                          -4.94504 49.5 142.216,
+                          -4.94504 54.5 142.216,
+                          -4.94504 49.5 142.216,
+                          -12.9452 49.5 136.403,
+                          4.94504 54.5 142.216,
+                          -4.94504 49.5 142.216,
+                          -4.94504 54.5 142.216,
+                          -21.5 49.5 155.5,
+                          -16 49.5 127,
+                          -12.9452 49.5 136.403,
+                          -12.9452 54.5 136.403,
+                          -12.9452 49.5 136.403,
+                          -16 49.5 127,
+                          -4.94504 54.5 142.216,
+                          -12.9452 49.5 136.403,
+                          -12.9452 54.5 136.403,
+                          -32 49.5 55,
+                          -12.9452 49.5 117.597,
+                          -16 49.5 127,
+                          -16 54.5 127,
+                          -16 49.5 127,
+                          -12.9452 49.5 117.597,
+                          -21.5 49.5 155.5,
+                          -32 49.5 55,
+                          -16 49.5 127,
+                          -12.9452 54.5 136.403,
+                          -16 49.5 127,
+                          -16 54.5 127,
+                          32 49.5 55,
+                          -4.94504 49.5 111.784,
+                          -12.9452 49.5 117.597,
+                          -12.9452 54.5 117.597,
+                          -12.9452 49.5 117.597,
+                          -4.94504 49.5 111.784,
+                          -32 49.5 55,
+                          32 49.5 55,
+                          -12.9452 49.5 117.597,
+                          -16 54.5 127,
+                          -12.9452 49.5 117.597,
+                          -12.9452 54.5 117.597,
+                          32 49.5 55,
+                          4.94504 49.5 111.784,
+                          -4.94504 49.5 111.784,
+                          -4.94504 54.5 111.784,
+                          -4.94504 49.5 111.784,
+                          4.94504 49.5 111.784,
+                          -12.9452 54.5 117.597,
+                          -4.94504 49.5 111.784,
+                          -4.94504 54.5 111.784,
+                          32 49.5 55,
+                          12.9452 49.5 117.597,
+                          4.94504 49.5 111.784,
+                          4.94504 54.5 111.784,
+                          4.94504 49.5 111.784,
+                          12.9452 49.5 117.597,
+                          -4.94504 54.5 111.784,
+                          4.94504 49.5 111.784,
+                          4.94504 54.5 111.784,
+                          4.94504 54.5 111.784,
+                          12.9452 49.5 117.597,
+                          12.9452 54.5 117.597,
+                          117 49.5 7,
+                          32 49.5 35,
+                          -32 49.5 35,
+                          -32 54.5 35,
+                          -32 49.5 35,
+                          32 49.5 35,
+                          -36.2165 49.5 140.783,
+                          -32 49.5 35,
+                          -32 49.5 55,
+                          -32 54.5 55,
+                          -32 49.5 55,
+                          -32 49.5 35,
+                          -42.5 49.5 7,
+                          117 49.5 7,
+                          -32 49.5 35,
+                          -42.5 49.5 81,
+                          -42.5 49.5 7,
+                          -32 49.5 35,
+                          -36.2165 49.5 140.783,
+                          -42.5 49.5 81,
+                          -32 49.5 35,
+                          -32 54.5 55,
+                          -32 49.5 35,
+                          -32 54.5 35,
+                          117 49.5 7,
+                          32 49.5 55,
+                          32 49.5 35,
+                          32 54.5 35,
+                          32 49.5 35,
+                          32 49.5 55,
+                          32 54.5 35,
+                          -32 54.5 35,
+                          32 49.5 35,
+                          32 54.5 55,
+                          32 49.5 55,
+                          -32 49.5 55,
+                          38 49.5 102,
+                          21.5 49.5 155.5,
+                          32 49.5 55,
+                          117 49.5 7,
+                          38 49.5 102,
+                          32 49.5 55,
+                          32 54.5 35,
+                          32 49.5 55,
+                          32 54.5 55,
+                          -21.5 49.5 155.5,
+                          -36.2165 49.5 140.783,
+                          -32 49.5 55,
+                          32 54.5 55,
+                          -32 49.5 55,
+                          -32 54.5 55,
+                          38 49.5 102,
+                          38 49.5 139,
+                          21.5 49.5 155.5,
+                          21.5 54.5 155.5,
+                          21.5 49.5 155.5,
+                          38 49.5 139,
+                          -21.5 54.5 155.5,
+                          -21.5 49.5 155.5,
+                          21.5 49.5 155.5,
+                          -21.5 54.5 155.5,
+                          21.5 49.5 155.5,
+                          21.5 54.5 155.5,
+                          38 54.5 139,
+                          38 49.5 139,
+                          38 49.5 102,
+                          38 54.5 139,
+                          21.5 54.5 155.5,
+                          38 49.5 139,
+                          117 49.5 7,
+                          117 49.5 41,
+                          38 49.5 102,
+                          38 54.5 102,
+                          38 49.5 102,
+                          117 49.5 41,
+                          38 54.5 139,
+                          38 49.5 102,
+                          38 54.5 102,
+                          117 54.5 41,
+                          117 49.5 41,
+                          117 49.5 7,
+                          38 54.5 102,
+                          117 49.5 41,
+                          117 54.5 41,
+                          117 54.5 7,
+                          117 49.5 7,
+                          -42.5 49.5 7,
+                          117 54.5 41,
+                          117 49.5 7,
+                          117 54.5 7,
+                          -42.5 54.5 7,
+                          -42.5 49.5 7,
+                          -42.5 49.5 81,
+                          117 54.5 7,
+                          -42.5 49.5 7,
+                          -42.5 54.5 7,
+                          -42.5 54.5 81,
+                          -42.5 49.5 81,
+                          -36.2165 49.5 140.783,
+                          -42.5 54.5 7,
+                          -42.5 49.5 81,
+                          -42.5 54.5 81,
+                          -36.2165 54.5 140.783,
+                          -36.2165 49.5 140.783,
+                          -21.5 49.5 155.5,
+                          -42.5 54.5 81,
+                          -36.2165 49.5 140.783,
+                          -36.2165 54.5 140.783,
+                          -36.2165 54.5 140.783,
+                          -21.5 49.5 155.5,
+                          -21.5 54.5 155.5,
+                          32 54.5 55,
+                          12.9452 54.5 117.597,
+                          16 54.5 127,
+                          21.5 54.5 155.5,
+                          16 54.5 127,
+                          12.9452 54.5 136.403,
+                          21.5 54.5 155.5,
+                          32 54.5 55,
+                          16 54.5 127,
+                          -32 54.5 55,
+                          4.94504 54.5 111.784,
+                          12.9452 54.5 117.597,
+                          32 54.5 55,
+                          -32 54.5 55,
+                          12.9452 54.5 117.597,
+                          -32 54.5 55,
+                          -4.94504 54.5 111.784,
+                          4.94504 54.5 111.784,
+                          -32 54.5 55,
+                          -12.9452 54.5 117.597,
+                          -4.94504 54.5 111.784,
+                          -32 54.5 55,
+                          -16 54.5 127,
+                          -12.9452 54.5 117.597,
+                          -21.5 54.5 155.5,
+                          -12.9452 54.5 136.403,
+                          -16 54.5 127,
+                          -21.5 54.5 155.5,
+                          -16 54.5 127,
+                          -32 54.5 55,
+                          -21.5 54.5 155.5,
+                          -4.94504 54.5 142.216,
+                          -12.9452 54.5 136.403,
+                          21.5 54.5 155.5,
+                          4.94504 54.5 142.216,
+                          -4.94504 54.5 142.216,
+                          -21.5 54.5 155.5,
+                          21.5 54.5 155.5,
+                          -4.94504 54.5 142.216,
+                          21.5 54.5 155.5,
+                          12.9452 54.5 136.403,
+                          4.94504 54.5 142.216,
+                          -42.5 54.5 7,
+                          -32 54.5 55,
+                          -32 54.5 35,
+                          -42.5 54.5 7,
+                          -32 54.5 35,
+                          32 54.5 35,
+                          -36.2165 54.5 140.783,
+                          -21.5 54.5 155.5,
+                          -32 54.5 55,
+                          -42.5 54.5 7,
+                          -36.2165 54.5 140.783,
+                          -32 54.5 55,
+                          38 54.5 139,
+                          32 54.5 35,
+                          32 54.5 55,
+                          38 54.5 139,
+                          32 54.5 55,
+                          21.5 54.5 155.5,
+                          117 54.5 41,
+                          -42.5 54.5 7,
+                          32 54.5 35,
+                          38 54.5 102,
+                          117 54.5 41,
+                          32 54.5 35,
+                          38 54.5 139,
+                          38 54.5 102,
+                          32 54.5 35,
+                          -42.5 54.5 7,
+                          -42.5 54.5 81,
+                          -36.2165 54.5 140.783,
+                          117 54.5 41,
+                          117 54.5 7,
+                          -42.5 54.5 7 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.011 0.012 1
+    }
+    Separator {
+        Normal {
+            vector      [ 0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.990806 0.135294 0,
+                          0.990806 0.135294 0,
+                          0.911973 0.410249 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.990806 0.135294 0,
+                          0.990806 0.135294 0,
+                          0.990806 0.135294 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.990806 0.135294 0,
+                          0.990806 0.135294 0,
+                          0.990806 0.135294 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.911973 0.410249 0,
+                          0.911973 0.410249 0,
+                          0.758528 0.65164 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.911973 0.410249 0,
+                          0.990806 0.135294 0,
+                          0.911973 0.410249 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.758528 0.65164 0,
+                          0.758528 0.65164 0,
+                          0.543024 0.839717 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.911973 0.410249 0,
+                          0.758528 0.65164 0,
+                          0.758528 0.65164 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.543024 0.839717 0,
+                          0.543024 0.839717 0,
+                          0.283093 0.959093 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.758528 0.65164 0,
+                          0.543024 0.839717 0,
+                          0.543024 0.839717 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.283093 0.959093 0,
+                          0.283093 0.959093 0,
+                          2.3115e-15 1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.543024 0.839717 0,
+                          0.283093 0.959093 0,
+                          0.283093 0.959093 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          2.3115e-15 1 0,
+                          2.3115e-15 1 0,
+                          -0.283093 0.959093 0,
+                          0.283093 0.959093 0,
+                          2.3115e-15 1 0,
+                          2.3115e-15 1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.283093 0.959093 0,
+                          -0.283093 0.959093 0,
+                          -0.543024 0.839717 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          2.3115e-15 1 0,
+                          -0.283093 0.959093 0,
+                          -0.283093 0.959093 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.543024 0.839717 0,
+                          -0.543024 0.839717 0,
+                          -0.758528 0.65164 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.283093 0.959093 0,
+                          -0.543024 0.839717 0,
+                          -0.543024 0.839717 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.758528 0.65164 0,
+                          -0.758528 0.65164 0,
+                          -0.911973 0.410249 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.543024 0.839717 0,
+                          -0.758528 0.65164 0,
+                          -0.758528 0.65164 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.911973 0.410249 0,
+                          -0.911973 0.410249 0,
+                          -0.990806 0.135294 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.758528 0.65164 0,
+                          -0.911973 0.410249 0,
+                          -0.911973 0.410249 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.990806 0.135294 0,
+                          -0.990806 0.135294 0,
+                          -0.990806 0.135294 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.911973 0.410249 0,
+                          -0.990806 0.135294 0,
+                          -0.990806 0.135294 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.990806 0.135294 0,
+                          -0.990806 0.135294 0,
+                          -0.957981 -0.28683 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.990806 0.135294 0,
+                          -0.990806 0.135294 0,
+                          -0.990806 0.135294 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.957981 -0.28683 0,
+                          -0.957981 -0.28683 0,
+                          -0.753424 -0.657535 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.990806 0.135294 0,
+                          -0.957981 -0.28683 0,
+                          -0.957981 -0.28683 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.753424 -0.657535 0,
+                          -0.753424 -0.657535 0,
+                          -0.413802 -0.910367 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.957981 -0.28683 0,
+                          -0.753424 -0.657535 0,
+                          -0.753424 -0.657535 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.413802 -0.910367 0,
+                          -0.413802 -0.910367 0,
+                          -2.18904e-15 -1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.753424 -0.657535 0,
+                          -0.413802 -0.910367 0,
+                          -0.413802 -0.910367 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -2.18904e-15 -1 0,
+                          -2.18904e-15 -1 0,
+                          0.413802 -0.910367 0,
+                          -0.413802 -0.910367 0,
+                          -2.18904e-15 -1 0,
+                          -2.18904e-15 -1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.413802 -0.910367 0,
+                          0.413802 -0.910367 0,
+                          0.753424 -0.657535 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -2.18904e-15 -1 0,
+                          0.413802 -0.910367 0,
+                          0.413802 -0.910367 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.753424 -0.657535 0,
+                          0.753424 -0.657535 0,
+                          0.957981 -0.28683 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.413802 -0.910367 0,
+                          0.753424 -0.657535 0,
+                          0.753424 -0.657535 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.957981 -0.28683 0,
+                          0.957981 -0.28683 0,
+                          0.990806 0.135294 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.753424 -0.657535 0,
+                          0.957981 -0.28683 0,
+                          0.957981 -0.28683 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.957981 -0.28683 0,
+                          0.990806 0.135294 0,
+                          0.990806 0.135294 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 20.8573 93.9584 36,
+                          21.4305 94.6416 36,
+                          23.2839 88.1794 36,
+                          23.2839 88.1794 52,
+                          23.2839 88.1794 36,
+                          21.4305 94.6416 36,
+                          22.5514 87.5921 36,
+                          23.2839 88.1794 36,
+                          34.6782 4.73529 36,
+                          34.6782 4.73529 52,
+                          34.6782 4.73529 36,
+                          23.2839 88.1794 36,
+                          22.5514 87.5921 36,
+                          20.8573 93.9584 36,
+                          23.2839 88.1794 36,
+                          34.6782 4.73529 52,
+                          23.2839 88.1794 36,
+                          23.2839 88.1794 52,
+                          17.4069 99.5697 36,
+                          17.8267 100.312 36,
+                          21.4305 94.6416 36,
+                          21.4305 94.6416 52,
+                          21.4305 94.6416 36,
+                          17.8267 100.312 36,
+                          20.8573 93.9584 36,
+                          17.4069 99.5697 36,
+                          21.4305 94.6416 36,
+                          21.4305 94.6416 52,
+                          23.2839 88.1794 52,
+                          21.4305 94.6416 36,
+                          12.4905 103.954 36,
+                          12.7591 104.734 36,
+                          17.8267 100.312 36,
+                          17.8267 100.312 52,
+                          17.8267 100.312 36,
+                          12.7591 104.734 36,
+                          17.4069 99.5697 36,
+                          12.4905 103.954 36,
+                          17.8267 100.312 36,
+                          21.4305 94.6416 52,
+                          17.8267 100.312 36,
+                          17.8267 100.312 52,
+                          6.52109 106.743 36,
+                          6.65357 107.538 36,
+                          12.7591 104.734 36,
+                          12.7591 104.734 52,
+                          12.7591 104.734 36,
+                          6.65357 107.538 36,
+                          12.4905 103.954 36,
+                          6.52109 106.743 36,
+                          12.7591 104.734 36,
+                          17.8267 100.312 52,
+                          12.7591 104.734 36,
+                          12.7591 104.734 52,
+                          2.35577e-13 107.7 36,
+                          2.48897e-13 108.5 36,
+                          6.65357 107.538 36,
+                          6.65357 107.538 52,
+                          6.65357 107.538 36,
+                          2.48897e-13 108.5 36,
+                          6.52109 106.743 36,
+                          2.35577e-13 107.7 36,
+                          6.65357 107.538 36,
+                          12.7591 104.734 52,
+                          6.65357 107.538 36,
+                          6.65357 107.538 52,
+                          2.35577e-13 107.7 36,
+                          -6.65357 107.538 36,
+                          2.48897e-13 108.5 36,
+                          2.48897e-13 108.5 52,
+                          2.48897e-13 108.5 36,
+                          -6.65357 107.538 36,
+                          6.65357 107.538 52,
+                          2.48897e-13 108.5 36,
+                          2.48897e-13 108.5 52,
+                          -6.52109 106.743 36,
+                          -12.7591 104.734 36,
+                          -6.65357 107.538 36,
+                          -6.65357 107.538 52,
+                          -6.65357 107.538 36,
+                          -12.7591 104.734 36,
+                          2.35577e-13 107.7 36,
+                          -6.52109 106.743 36,
+                          -6.65357 107.538 36,
+                          2.48897e-13 108.5 52,
+                          -6.65357 107.538 36,
+                          -6.65357 107.538 52,
+                          -12.4905 103.954 36,
+                          -17.8267 100.312 36,
+                          -12.7591 104.734 36,
+                          -12.7591 104.734 52,
+                          -12.7591 104.734 36,
+                          -17.8267 100.312 36,
+                          -6.52109 106.743 36,
+                          -12.4905 103.954 36,
+                          -12.7591 104.734 36,
+                          -6.65357 107.538 52,
+                          -12.7591 104.734 36,
+                          -12.7591 104.734 52,
+                          -17.4069 99.5697 36,
+                          -21.4305 94.6416 36,
+                          -17.8267 100.312 36,
+                          -17.8267 100.312 52,
+                          -17.8267 100.312 36,
+                          -21.4305 94.6416 36,
+                          -12.4905 103.954 36,
+                          -17.4069 99.5697 36,
+                          -17.8267 100.312 36,
+                          -12.7591 104.734 52,
+                          -17.8267 100.312 36,
+                          -17.8267 100.312 52,
+                          -20.8573 93.9584 36,
+                          -23.2839 88.1794 36,
+                          -21.4305 94.6416 36,
+                          -21.4305 94.6416 52,
+                          -21.4305 94.6416 36,
+                          -23.2839 88.1794 36,
+                          -17.4069 99.5697 36,
+                          -20.8573 93.9584 36,
+                          -21.4305 94.6416 36,
+                          -17.8267 100.312 52,
+                          -21.4305 94.6416 36,
+                          -21.4305 94.6416 52,
+                          -31.6478 12.8843 36,
+                          -34.6782 4.73529 36,
+                          -23.2839 88.1794 36,
+                          -23.2839 88.1794 52,
+                          -23.2839 88.1794 36,
+                          -34.6782 4.73529 36,
+                          -22.3458 81.0059 36,
+                          -31.6478 12.8843 36,
+                          -23.2839 88.1794 36,
+                          -22.5514 87.5921 36,
+                          -22.3458 81.0059 36,
+                          -23.2839 88.1794 36,
+                          -20.8573 93.9584 36,
+                          -22.5514 87.5921 36,
+                          -23.2839 88.1794 36,
+                          -21.4305 94.6416 52,
+                          -23.2839 88.1794 36,
+                          -23.2839 88.1794 52,
+                          -34.1695 -0.168321 36,
+                          -33.5284 -10.0403 36,
+                          -34.6782 4.73529 36,
+                          -34.6782 4.73529 52,
+                          -34.6782 4.73529 36,
+                          -33.5284 -10.0403 36,
+                          -31.6478 12.8843 36,
+                          -34.1695 -0.168321 36,
+                          -34.6782 4.73529 36,
+                          -23.2839 88.1794 52,
+                          -34.6782 4.73529 36,
+                          -34.6782 4.73529 52,
+                          -31.5206 -13.1916 36,
+                          -26.3711 -23.0118 36,
+                          -33.5284 -10.0403 36,
+                          -33.5284 -10.0403 52,
+                          -33.5284 -10.0403 36,
+                          -26.3711 -23.0118 36,
+                          -34.1695 -0.168321 36,
+                          -31.5206 -13.1916 36,
+                          -33.5284 -10.0403 36,
+                          -34.6782 4.73529 52,
+                          -33.5284 -10.0403 36,
+                          -33.5284 -10.0403 52,
+                          -13.0412 -31.5834 36,
+                          -14.4812 -31.8636 36,
+                          -26.3711 -23.0118 36,
+                          -26.3711 -23.0118 52,
+                          -26.3711 -23.0118 36,
+                          -14.4812 -31.8636 36,
+                          -24.1046 -24.2186 36,
+                          -13.0412 -31.5834 36,
+                          -26.3711 -23.0118 36,
+                          -31.5206 -13.1916 36,
+                          -24.1046 -24.2186 36,
+                          -26.3711 -23.0118 36,
+                          -33.5284 -10.0403 52,
+                          -26.3711 -23.0118 36,
+                          -26.3711 -23.0118 52,
+                          -6.88227e-14 -34.17 36,
+                          -1.01252e-13 -34.9994 36,
+                          -14.4812 -31.8636 36,
+                          -14.4812 -31.8636 52,
+                          -14.4812 -31.8636 36,
+                          -1.01252e-13 -34.9994 36,
+                          -13.0412 -31.5834 36,
+                          -6.88227e-14 -34.17 36,
+                          -14.4812 -31.8636 36,
+                          -26.3711 -23.0118 52,
+                          -14.4812 -31.8636 36,
+                          -14.4812 -31.8636 52,
+                          -6.88227e-14 -34.17 36,
+                          14.4812 -31.8636 36,
+                          -1.01252e-13 -34.9994 36,
+                          -1.01252e-13 -34.9994 52,
+                          -1.01252e-13 -34.9994 36,
+                          14.4812 -31.8636 36,
+                          -14.4812 -31.8636 52,
+                          -1.01252e-13 -34.9994 36,
+                          -1.01252e-13 -34.9994 52,
+                          24.1046 -24.2186 36,
+                          26.3711 -23.0118 36,
+                          14.4812 -31.8636 36,
+                          14.4812 -31.8636 52,
+                          14.4812 -31.8636 36,
+                          26.3711 -23.0118 36,
+                          13.0412 -31.5834 36,
+                          14.4812 -31.8636 36,
+                          -6.88227e-14 -34.17 36,
+                          13.0412 -31.5834 36,
+                          24.1046 -24.2186 36,
+                          14.4812 -31.8636 36,
+                          -1.01252e-13 -34.9994 52,
+                          14.4812 -31.8636 36,
+                          14.4812 -31.8636 52,
+                          31.5206 -13.1916 36,
+                          33.5284 -10.0403 36,
+                          26.3711 -23.0118 36,
+                          26.3711 -23.0118 52,
+                          26.3711 -23.0118 36,
+                          33.5284 -10.0403 36,
+                          24.1046 -24.2186 36,
+                          31.5206 -13.1916 36,
+                          26.3711 -23.0118 36,
+                          14.4812 -31.8636 52,
+                          26.3711 -23.0118 36,
+                          26.3711 -23.0118 52,
+                          34.1695 -0.168321 36,
+                          34.6782 4.73529 36,
+                          33.5284 -10.0403 36,
+                          33.5284 -10.0403 52,
+                          33.5284 -10.0403 36,
+                          34.6782 4.73529 36,
+                          31.5206 -13.1916 36,
+                          34.1695 -0.168321 36,
+                          33.5284 -10.0403 36,
+                          26.3711 -23.0118 52,
+                          33.5284 -10.0403 36,
+                          33.5284 -10.0403 52,
+                          22.3458 81.0059 36,
+                          22.5514 87.5921 36,
+                          34.6782 4.73529 36,
+                          31.6478 12.8843 36,
+                          22.3458 81.0059 36,
+                          34.6782 4.73529 36,
+                          34.1695 -0.168321 36,
+                          31.6478 12.8843 36,
+                          34.6782 4.73529 36,
+                          33.5284 -10.0403 52,
+                          34.6782 4.73529 36,
+                          34.6782 4.73529 52 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.71 0.426 0
+    }
+    Separator {
+        Normal {
+            vector      [ -2.37273e-15 -1 0,
+                          -1.80618e-15 -1 0,
+                          -0.381616 -0.924321 0,
+                          0.433884 -0.900969 0,
+                          0.381616 -0.924321 0,
+                          -2.12781e-15 -1 0,
+                          0.433884 -0.900969 0,
+                          -2.12781e-15 -1 0,
+                          -2.12781e-15 -1 0,
+                          -0.433884 -0.900969 0,
+                          -0.381616 -0.924321 0,
+                          -0.705421 -0.708788 0,
+                          -0.433884 -0.900969 0,
+                          -2.37273e-15 -1 0,
+                          -0.381616 -0.924321 0,
+                          -0.781832 -0.62349 0,
+                          -0.705421 -0.708788 0,
+                          -0.922482 -0.386041 0,
+                          -0.433884 -0.900969 0,
+                          -0.705421 -0.708788 0,
+                          -0.781832 -0.62349 0,
+                          -0.974928 -0.222521 0,
+                          -0.922482 -0.386041 0,
+                          -0.999988 -0.00488224 0,
+                          -0.781832 -0.62349 0,
+                          -0.922482 -0.386041 0,
+                          -0.974928 -0.222521 0,
+                          -0.974928 0.222521 0,
+                          -0.999988 -0.00488224 0,
+                          -0.926187 0.377064 0,
+                          -0.974928 -0.222521 0,
+                          -0.999988 -0.00488224 0,
+                          -0.974928 0.222521 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -8.39972e-14 -34.17 34,
+                          -6.88227e-14 -34.17 36,
+                          -13.0412 -31.5834 36,
+                          14.8275 -30.7852 34,
+                          13.0412 -31.5834 36,
+                          -6.88227e-14 -34.17 36,
+                          14.8275 -30.7852 34,
+                          -6.88227e-14 -34.17 36,
+                          -8.39972e-14 -34.17 34,
+                          -14.8275 -30.7852 34,
+                          -13.0412 -31.5834 36,
+                          -24.1046 -24.2186 36,
+                          -14.8275 -30.7852 34,
+                          -8.39972e-14 -34.17 34,
+                          -13.0412 -31.5834 36,
+                          -26.7161 -21.3029 34,
+                          -24.1046 -24.2186 36,
+                          -31.5206 -13.1916 36,
+                          -14.8275 -30.7852 34,
+                          -24.1046 -24.2186 36,
+                          -26.7161 -21.3029 34,
+                          -33.313 -7.60268 34,
+                          -31.5206 -13.1916 36,
+                          -34.1695 -0.168321 36,
+                          -26.7161 -21.3029 34,
+                          -31.5206 -13.1916 36,
+                          -33.313 -7.60268 34,
+                          -33.313 7.60268 34,
+                          -34.1695 -0.168321 36,
+                          -31.6478 12.8843 36,
+                          -33.313 -7.60268 34,
+                          -34.1695 -0.168321 36,
+                          -33.313 7.60268 34 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.011 0.012 1
+    }
+    Separator {
+        Normal {
+            vector      [ 0.990806 -0.135294 0,
+                          0.990806 -0.135294 0,
+                          0.990806 -0.135294 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -31.6478 12.8843 52,
+                          -31.6478 12.8843 36,
+                          -22.3458 81.0059 36 ]
+        }
+        FaceSet {
+            numVertices [ 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.71 0.426 0
+    }
+    Separator {
+        Normal {
+            vector      [ -0.781832 0.62349 0,
+                          -0.926187 0.377064 0,
+                          -0.926187 0.377064 0,
+                          -0.781832 0.62349 0,
+                          -0.926187 0.377064 0,
+                          -0.781832 0.62349 0,
+                          -0.974928 0.222521 0,
+                          -0.926187 0.377064 0,
+                          -0.781832 0.62349 0,
+                          -1 2.3115e-15 0,
+                          -0.984398 -0.175954 0,
+                          -0.993466 0.114127 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -26.7161 21.3029 54,
+                          -31.6478 12.8843 36,
+                          -31.6478 12.8843 52,
+                          -26.7161 21.3029 34,
+                          -31.6478 12.8843 36,
+                          -26.7161 21.3029 54,
+                          -33.313 7.60268 34,
+                          -31.6478 12.8843 36,
+                          -26.7161 21.3029 34,
+                          -22.7 85 34,
+                          -22.3458 81.0059 36,
+                          -22.5514 87.5921 36 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.011 0.012 1
+    }
+    Separator {
+        Normal {
+            vector      [ 0.990806 -0.135294 0,
+                          0.990806 -0.135294 0,
+                          0.990806 -0.135294 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -31.6478 12.8843 52,
+                          -22.3458 81.0059 36,
+                          -22.3458 81.0059 52 ]
+        }
+        FaceSet {
+            numVertices [ 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.71 0.426 0
+    }
+    Separator {
+        Normal {
+            vector      [ -0.866025 -0.5 0,
+                          -0.984398 -0.175954 0,
+                          -0.984398 -0.175954 0,
+                          -0.866025 -0.5 0,
+                          -0.984398 -0.175954 0,
+                          -1 2.3115e-15 0,
+                          -1 2.3115e-15 0,
+                          -0.993466 0.114127 0,
+                          -0.918853 0.394601 0,
+                          -0.866025 0.5 0,
+                          -0.918853 0.394601 0,
+                          -0.766835 0.641845 0,
+                          -1 2.3115e-15 0,
+                          -0.918853 0.394601 0,
+                          -0.866025 0.5 0,
+                          -0.866025 0.5 0,
+                          -0.766835 0.641845 0,
+                          -0.550209 0.835027 0,
+                          -0.5 0.866025 0,
+                          -0.550209 0.835027 0,
+                          -0.287215 0.957866 0,
+                          -0.866025 0.5 0,
+                          -0.550209 0.835027 0,
+                          -0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          -0.287215 0.957866 0,
+                          1.80618e-15 1 0,
+                          2.25027e-15 1 0,
+                          1.80618e-15 1 0,
+                          0.287215 0.957866 0,
+                          -0.5 0.866025 0,
+                          1.80618e-15 1 0,
+                          2.25027e-15 1 0,
+                          0.5 0.866025 0,
+                          0.287215 0.957866 0,
+                          0.550209 0.835027 0,
+                          2.25027e-15 1 0,
+                          0.287215 0.957866 0,
+                          0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          0.550209 0.835027 0,
+                          0.766835 0.641845 0,
+                          0.866025 0.5 0,
+                          0.766835 0.641845 0,
+                          0.918853 0.394601 0,
+                          0.5 0.866025 0,
+                          0.766835 0.641845 0,
+                          0.866025 0.5 0,
+                          0.866025 0.5 0,
+                          0.918853 0.394601 0,
+                          0.993466 0.114127 0,
+                          1 -2.18904e-15 0,
+                          0.993466 0.114127 0,
+                          0.984398 -0.175954 0,
+                          0.866025 0.5 0,
+                          0.993466 0.114127 0,
+                          1 -2.18904e-15 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -19.6588 73.65 34,
+                          -22.3458 81.0059 52,
+                          -22.3458 81.0059 36,
+                          -19.6588 73.65 34,
+                          -22.3458 81.0059 36,
+                          -22.7 85 34,
+                          -22.7 85 34,
+                          -22.5514 87.5921 36,
+                          -20.8573 93.9584 36,
+                          -19.6588 96.35 34,
+                          -20.8573 93.9584 36,
+                          -17.4069 99.5697 36,
+                          -22.7 85 34,
+                          -20.8573 93.9584 36,
+                          -19.6588 96.35 34,
+                          -19.6588 96.35 34,
+                          -17.4069 99.5697 36,
+                          -12.4905 103.954 36,
+                          -11.35 104.659 34,
+                          -12.4905 103.954 36,
+                          -6.52109 106.743 36,
+                          -19.6588 96.35 34,
+                          -12.4905 103.954 36,
+                          -11.35 104.659 34,
+                          -11.35 104.659 34,
+                          -6.52109 106.743 36,
+                          2.35577e-13 107.7 36,
+                          2.45658e-13 107.7 34,
+                          2.35577e-13 107.7 36,
+                          6.52109 106.743 36,
+                          -11.35 104.659 34,
+                          2.35577e-13 107.7 36,
+                          2.45658e-13 107.7 34,
+                          11.35 104.659 34,
+                          6.52109 106.743 36,
+                          12.4905 103.954 36,
+                          2.45658e-13 107.7 34,
+                          6.52109 106.743 36,
+                          11.35 104.659 34,
+                          11.35 104.659 34,
+                          12.4905 103.954 36,
+                          17.4069 99.5697 36,
+                          19.6588 96.35 34,
+                          17.4069 99.5697 36,
+                          20.8573 93.9584 36,
+                          11.35 104.659 34,
+                          17.4069 99.5697 36,
+                          19.6588 96.35 34,
+                          19.6588 96.35 34,
+                          20.8573 93.9584 36,
+                          22.5514 87.5921 36,
+                          22.7 85 34,
+                          22.5514 87.5921 36,
+                          22.3458 81.0059 36,
+                          19.6588 96.35 34,
+                          22.5514 87.5921 36,
+                          22.7 85 34 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.011 0.012 1
+    }
+    Separator {
+        Normal {
+            vector      [ -0.990806 -0.135294 0,
+                          -0.990806 -0.135294 0,
+                          -0.990806 -0.135294 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 22.3458 81.0059 52,
+                          22.3458 81.0059 36,
+                          31.6478 12.8843 36 ]
+        }
+        FaceSet {
+            numVertices [ 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.71 0.426 0
+    }
+    Separator {
+        Normal {
+            vector      [ 0.866025 -0.5 0,
+                          0.984398 -0.175954 0,
+                          0.984398 -0.175954 0,
+                          0.866025 -0.5 0,
+                          0.984398 -0.175954 0,
+                          0.866025 -0.5 0,
+                          1 -2.18904e-15 0,
+                          0.984398 -0.175954 0,
+                          0.866025 -0.5 0,
+                          0.974928 0.222521 0,
+                          0.926187 0.377064 0,
+                          0.999988 -0.00488224 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 19.6588 73.65 54,
+                          22.3458 81.0059 36,
+                          22.3458 81.0059 52,
+                          19.6588 73.65 34,
+                          22.3458 81.0059 36,
+                          19.6588 73.65 54,
+                          22.7 85 34,
+                          22.3458 81.0059 36,
+                          19.6588 73.65 34,
+                          33.313 7.60268 34,
+                          31.6478 12.8843 36,
+                          34.1695 -0.168321 36 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.011 0.012 1
+    }
+    Separator {
+        Normal {
+            vector      [ -0.990806 -0.135294 0,
+                          -0.990806 -0.135294 0,
+                          -0.990806 -0.135294 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 22.3458 81.0059 52,
+                          31.6478 12.8843 36,
+                          31.6478 12.8843 52 ]
+        }
+        FaceSet {
+            numVertices [ 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.71 0.426 0
+    }
+    Separator {
+        Normal {
+            vector      [ 0.781832 0.62349 0,
+                          0.926187 0.377064 0,
+                          0.926187 0.377064 0,
+                          0.781832 0.62349 0,
+                          0.926187 0.377064 0,
+                          0.974928 0.222521 0,
+                          0.974928 -0.222521 0,
+                          0.999988 -0.00488224 0,
+                          0.922482 -0.386041 0,
+                          0.974928 0.222521 0,
+                          0.999988 -0.00488224 0,
+                          0.974928 -0.222521 0,
+                          0.781832 -0.62349 0,
+                          0.922482 -0.386041 0,
+                          0.705421 -0.708788 0,
+                          0.974928 -0.222521 0,
+                          0.922482 -0.386041 0,
+                          0.781832 -0.62349 0,
+                          0.433884 -0.900969 0,
+                          0.705421 -0.708788 0,
+                          0.381616 -0.924321 0,
+                          0.781832 -0.62349 0,
+                          0.705421 -0.708788 0,
+                          0.433884 -0.900969 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 26.7161 21.3029 34,
+                          31.6478 12.8843 52,
+                          31.6478 12.8843 36,
+                          26.7161 21.3029 34,
+                          31.6478 12.8843 36,
+                          33.313 7.60268 34,
+                          33.313 -7.60268 34,
+                          34.1695 -0.168321 36,
+                          31.5206 -13.1916 36,
+                          33.313 7.60268 34,
+                          34.1695 -0.168321 36,
+                          33.313 -7.60268 34,
+                          26.7161 -21.3029 34,
+                          31.5206 -13.1916 36,
+                          24.1046 -24.2186 36,
+                          33.313 -7.60268 34,
+                          31.5206 -13.1916 36,
+                          26.7161 -21.3029 34,
+                          14.8275 -30.7852 34,
+                          24.1046 -24.2186 36,
+                          13.0412 -31.5834 36,
+                          26.7161 -21.3029 34,
+                          24.1046 -24.2186 36,
+                          14.8275 -30.7852 34 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.011 0.012 1
+    }
+    Separator {
+        Normal {
+            vector      [ 0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 31.6478 12.8843 52,
+                          34.6782 4.73529 52,
+                          23.2839 88.1794 52,
+                          20.8573 93.9584 52,
+                          23.2839 88.1794 52,
+                          21.4305 94.6416 52,
+                          22.3458 81.0059 52,
+                          31.6478 12.8843 52,
+                          23.2839 88.1794 52,
+                          22.5514 87.5921 52,
+                          22.3458 81.0059 52,
+                          23.2839 88.1794 52,
+                          20.8573 93.9584 52,
+                          22.5514 87.5921 52,
+                          23.2839 88.1794 52,
+                          34.1695 -0.168321 52,
+                          33.5284 -10.0403 52,
+                          34.6782 4.73529 52,
+                          31.6478 12.8843 52,
+                          34.1695 -0.168321 52,
+                          34.6782 4.73529 52,
+                          31.5206 -13.1916 52,
+                          26.3711 -23.0118 52,
+                          33.5284 -10.0403 52,
+                          34.1695 -0.168321 52,
+                          31.5206 -13.1916 52,
+                          33.5284 -10.0403 52,
+                          13.0412 -31.5834 52,
+                          14.4812 -31.8636 52,
+                          26.3711 -23.0118 52,
+                          24.1046 -24.2186 52,
+                          13.0412 -31.5834 52,
+                          26.3711 -23.0118 52,
+                          31.5206 -13.1916 52,
+                          24.1046 -24.2186 52,
+                          26.3711 -23.0118 52,
+                          -8.39972e-14 -34.17 52,
+                          -1.01252e-13 -34.9994 52,
+                          14.4812 -31.8636 52,
+                          13.0412 -31.5834 52,
+                          -8.39972e-14 -34.17 52,
+                          14.4812 -31.8636 52,
+                          -8.39972e-14 -34.17 52,
+                          -14.4812 -31.8636 52,
+                          -1.01252e-13 -34.9994 52,
+                          -24.1046 -24.2186 52,
+                          -26.3711 -23.0118 52,
+                          -14.4812 -31.8636 52,
+                          -13.0412 -31.5834 52,
+                          -14.4812 -31.8636 52,
+                          -8.39972e-14 -34.17 52,
+                          -13.0412 -31.5834 52,
+                          -24.1046 -24.2186 52,
+                          -14.4812 -31.8636 52,
+                          -31.5206 -13.1916 52,
+                          -33.5284 -10.0403 52,
+                          -26.3711 -23.0118 52,
+                          -24.1046 -24.2186 52,
+                          -31.5206 -13.1916 52,
+                          -26.3711 -23.0118 52,
+                          -34.1695 -0.168321 52,
+                          -34.6782 4.73529 52,
+                          -33.5284 -10.0403 52,
+                          -31.5206 -13.1916 52,
+                          -34.1695 -0.168321 52,
+                          -33.5284 -10.0403 52,
+                          -22.5514 87.5921 52,
+                          -23.2839 88.1794 52,
+                          -34.6782 4.73529 52,
+                          -22.3458 81.0059 52,
+                          -22.5514 87.5921 52,
+                          -34.6782 4.73529 52,
+                          -31.6478 12.8843 52,
+                          -22.3458 81.0059 52,
+                          -34.6782 4.73529 52,
+                          -34.1695 -0.168321 52,
+                          -31.6478 12.8843 52,
+                          -34.6782 4.73529 52,
+                          -20.8573 93.9584 52,
+                          -21.4305 94.6416 52,
+                          -23.2839 88.1794 52,
+                          -22.5514 87.5921 52,
+                          -20.8573 93.9584 52,
+                          -23.2839 88.1794 52,
+                          -17.4069 99.5697 52,
+                          -17.8267 100.312 52,
+                          -21.4305 94.6416 52,
+                          -20.8573 93.9584 52,
+                          -17.4069 99.5697 52,
+                          -21.4305 94.6416 52,
+                          -12.4905 103.954 52,
+                          -12.7591 104.734 52,
+                          -17.8267 100.312 52,
+                          -17.4069 99.5697 52,
+                          -12.4905 103.954 52,
+                          -17.8267 100.312 52,
+                          -6.52109 106.743 52,
+                          -6.65357 107.538 52,
+                          -12.7591 104.734 52,
+                          -12.4905 103.954 52,
+                          -6.52109 106.743 52,
+                          -12.7591 104.734 52,
+                          2.45658e-13 107.7 52,
+                          2.48897e-13 108.5 52,
+                          -6.65357 107.538 52,
+                          -6.52109 106.743 52,
+                          2.45658e-13 107.7 52,
+                          -6.65357 107.538 52,
+                          2.45658e-13 107.7 52,
+                          6.65357 107.538 52,
+                          2.48897e-13 108.5 52,
+                          6.52109 106.743 52,
+                          12.7591 104.734 52,
+                          6.65357 107.538 52,
+                          2.45658e-13 107.7 52,
+                          6.52109 106.743 52,
+                          6.65357 107.538 52,
+                          12.4905 103.954 52,
+                          17.8267 100.312 52,
+                          12.7591 104.734 52,
+                          6.52109 106.743 52,
+                          12.4905 103.954 52,
+                          12.7591 104.734 52,
+                          17.4069 99.5697 52,
+                          21.4305 94.6416 52,
+                          17.8267 100.312 52,
+                          12.4905 103.954 52,
+                          17.4069 99.5697 52,
+                          17.8267 100.312 52,
+                          17.4069 99.5697 52,
+                          20.8573 93.9584 52,
+                          21.4305 94.6416 52 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.71 0.426 0
+    }
+    Separator {
+        Normal {
+            vector      [ -2.12781e-15 -1 0,
+                          -2.12781e-15 -1 0,
+                          0.381616 -0.924321 0,
+                          -0.433884 -0.900969 0,
+                          -0.381616 -0.924321 0,
+                          -2.25027e-15 -1 0,
+                          -0.433884 -0.900969 0,
+                          -2.25027e-15 -1 0,
+                          -2.37273e-15 -1 0,
+                          0.433884 -0.900969 0,
+                          0.381616 -0.924321 0,
+                          0.705421 -0.708788 0,
+                          0.433884 -0.900969 0,
+                          -2.12781e-15 -1 0,
+                          0.381616 -0.924321 0,
+                          0.781832 -0.62349 0,
+                          0.705421 -0.708788 0,
+                          0.922482 -0.386041 0,
+                          0.433884 -0.900969 0,
+                          0.705421 -0.708788 0,
+                          0.781832 -0.62349 0,
+                          0.974928 -0.222521 0,
+                          0.922482 -0.386041 0,
+                          0.999988 -0.00488224 0,
+                          0.781832 -0.62349 0,
+                          0.922482 -0.386041 0,
+                          0.974928 -0.222521 0,
+                          0.974928 0.222521 0,
+                          0.999988 -0.00488224 0,
+                          0.926187 0.377064 0,
+                          0.974928 -0.222521 0,
+                          0.999988 -0.00488224 0,
+                          0.974928 0.222521 0,
+                          0.974928 0.222521 0,
+                          0.926187 0.377064 0,
+                          0.781832 0.62349 0,
+                          0.781832 0.62349 0,
+                          0.781832 0.62349 0,
+                          0.926187 0.377064 0,
+                          1 -2.18904e-15 0,
+                          0.984398 -0.175954 0,
+                          0.993466 0.114127 0,
+                          0.866025 -0.5 0,
+                          0.984398 -0.175954 0,
+                          1 -2.18904e-15 0,
+                          1 -2.18904e-15 0,
+                          0.993466 0.114127 0,
+                          0.918853 0.394601 0,
+                          0.866025 0.5 0,
+                          0.918853 0.394601 0,
+                          0.766835 0.641845 0,
+                          1 -2.18904e-15 0,
+                          0.918853 0.394601 0,
+                          0.866025 0.5 0,
+                          0.866025 0.5 0,
+                          0.766835 0.641845 0,
+                          0.550209 0.835027 0,
+                          0.5 0.866025 0,
+                          0.550209 0.835027 0,
+                          0.287215 0.957866 0,
+                          0.866025 0.5 0,
+                          0.550209 0.835027 0,
+                          0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          0.287215 0.957866 0,
+                          2.25027e-15 1 0,
+                          2.25027e-15 1 0,
+                          2.25027e-15 1 0,
+                          -0.287215 0.957866 0,
+                          0.5 0.866025 0,
+                          2.25027e-15 1 0,
+                          2.25027e-15 1 0,
+                          -0.5 0.866025 0,
+                          -0.287215 0.957866 0,
+                          -0.550209 0.835027 0,
+                          2.25027e-15 1 0,
+                          -0.287215 0.957866 0,
+                          -0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          -0.550209 0.835027 0,
+                          -0.766835 0.641845 0,
+                          -0.866025 0.5 0,
+                          -0.766835 0.641845 0,
+                          -0.918853 0.394601 0,
+                          -0.5 0.866025 0,
+                          -0.766835 0.641845 0,
+                          -0.866025 0.5 0,
+                          -0.866025 0.5 0,
+                          -0.918853 0.394601 0,
+                          -0.993466 0.114127 0,
+                          -1 2.3115e-15 0,
+                          -0.993466 0.114127 0,
+                          -0.984398 -0.175954 0,
+                          -0.866025 0.5 0,
+                          -0.993466 0.114127 0,
+                          -1 2.3115e-15 0,
+                          -1 2.3115e-15 0,
+                          -0.984398 -0.175954 0,
+                          -0.866025 -0.5 0,
+                          -0.866025 -0.5 0,
+                          -0.866025 -0.5 0,
+                          -0.984398 -0.175954 0,
+                          -0.974928 0.222521 0,
+                          -0.926187 0.377064 0,
+                          -0.999988 -0.00488224 0,
+                          -0.781832 0.62349 0,
+                          -0.926187 0.377064 0,
+                          -0.974928 0.222521 0,
+                          -0.974928 -0.222521 0,
+                          -0.999988 -0.00488224 0,
+                          -0.922482 -0.386041 0,
+                          -0.974928 0.222521 0,
+                          -0.999988 -0.00488224 0,
+                          -0.974928 -0.222521 0,
+                          -0.781832 -0.62349 0,
+                          -0.922482 -0.386041 0,
+                          -0.705421 -0.708788 0,
+                          -0.974928 -0.222521 0,
+                          -0.922482 -0.386041 0,
+                          -0.781832 -0.62349 0,
+                          -0.433884 -0.900969 0,
+                          -0.705421 -0.708788 0,
+                          -0.381616 -0.924321 0,
+                          -0.781832 -0.62349 0,
+                          -0.705421 -0.708788 0,
+                          -0.433884 -0.900969 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.781832 0.62349 0,
+                          -0.781832 0.62349 0,
+                          -0.433884 0.900969 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.433884 0.900969 0,
+                          -0.433884 0.900969 0,
+                          2.25027e-15 1 0,
+                          -0.781832 0.62349 0,
+                          -0.433884 0.900969 0,
+                          -0.433884 0.900969 0,
+                          2.25027e-15 1 0,
+                          2.25027e-15 1 0,
+                          0.433884 0.900969 0,
+                          -0.433884 0.900969 0,
+                          2.25027e-15 1 0,
+                          2.25027e-15 1 0,
+                          0.433884 0.900969 0,
+                          0.433884 0.900969 0,
+                          0.781832 0.62349 0,
+                          2.25027e-15 1 0,
+                          0.433884 0.900969 0,
+                          0.433884 0.900969 0,
+                          0.433884 0.900969 0,
+                          0.781832 0.62349 0,
+                          0.781832 0.62349 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -2.37273e-15 -1 0,
+                          -2.37273e-15 -1 0,
+                          -0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          -2.12781e-15 -1 0,
+                          0.5 -0.866025 0,
+                          -2.12781e-15 -1 0,
+                          -2.12781e-15 -1 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -0.866025 -0.5 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.5 -0.866025 0,
+                          -2.37273e-15 -1 0,
+                          -0.5 -0.866025 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.5 -0.866025 0,
+                          -0.866025 -0.5 0,
+                          -0.866025 -0.5 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.866025 -0.5 0,
+                          0.866025 -0.5 0,
+                          0.5 -0.866025 0,
+                          0.866025 -0.5 0,
+                          0.5 -0.866025 0,
+                          0.5 -0.866025 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 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -8.39972e-14 -34.17 54,
+                          -8.39972e-14 -34.17 52,
+                          13.0412 -31.5834 52,
+                          -14.8275 -30.7852 54,
+                          -13.0412 -31.5834 52,
+                          -8.39972e-14 -34.17 52,
+                          -14.8275 -30.7852 54,
+                          -8.39972e-14 -34.17 52,
+                          -8.39972e-14 -34.17 54,
+                          14.8275 -30.7852 54,
+                          13.0412 -31.5834 52,
+                          24.1046 -24.2186 52,
+                          14.8275 -30.7852 54,
+                          -8.39972e-14 -34.17 54,
+                          13.0412 -31.5834 52,
+                          26.7161 -21.3029 54,
+                          24.1046 -24.2186 52,
+                          31.5206 -13.1916 52,
+                          14.8275 -30.7852 54,
+                          24.1046 -24.2186 52,
+                          26.7161 -21.3029 54,
+                          33.313 -7.60268 54,
+                          31.5206 -13.1916 52,
+                          34.1695 -0.168321 52,
+                          26.7161 -21.3029 54,
+                          31.5206 -13.1916 52,
+                          33.313 -7.60268 54,
+                          33.313 7.60268 54,
+                          34.1695 -0.168321 52,
+                          31.6478 12.8843 52,
+                          33.313 -7.60268 54,
+                          34.1695 -0.168321 52,
+                          33.313 7.60268 54,
+                          33.313 7.60268 54,
+                          31.6478 12.8843 52,
+                          26.7161 21.3029 54,
+                          26.7161 21.3029 34,
+                          26.7161 21.3029 54,
+                          31.6478 12.8843 52,
+                          22.7 85 54,
+                          22.3458 81.0059 52,
+                          22.5514 87.5921 52,
+                          19.6588 73.65 54,
+                          22.3458 81.0059 52,
+                          22.7 85 54,
+                          22.7 85 54,
+                          22.5514 87.5921 52,
+                          20.8573 93.9584 52,
+                          19.6588 96.35 54,
+                          20.8573 93.9584 52,
+                          17.4069 99.5697 52,
+                          22.7 85 54,
+                          20.8573 93.9584 52,
+                          19.6588 96.35 54,
+                          19.6588 96.35 54,
+                          17.4069 99.5697 52,
+                          12.4905 103.954 52,
+                          11.35 104.659 54,
+                          12.4905 103.954 52,
+                          6.52109 106.743 52,
+                          19.6588 96.35 54,
+                          12.4905 103.954 52,
+                          11.35 104.659 54,
+                          11.35 104.659 54,
+                          6.52109 106.743 52,
+                          2.45658e-13 107.7 52,
+                          2.45658e-13 107.7 54,
+                          2.45658e-13 107.7 52,
+                          -6.52109 106.743 52,
+                          11.35 104.659 54,
+                          2.45658e-13 107.7 52,
+                          2.45658e-13 107.7 54,
+                          -11.35 104.659 54,
+                          -6.52109 106.743 52,
+                          -12.4905 103.954 52,
+                          2.45658e-13 107.7 54,
+                          -6.52109 106.743 52,
+                          -11.35 104.659 54,
+                          -11.35 104.659 54,
+                          -12.4905 103.954 52,
+                          -17.4069 99.5697 52,
+                          -19.6588 96.35 54,
+                          -17.4069 99.5697 52,
+                          -20.8573 93.9584 52,
+                          -11.35 104.659 54,
+                          -17.4069 99.5697 52,
+                          -19.6588 96.35 54,
+                          -19.6588 96.35 54,
+                          -20.8573 93.9584 52,
+                          -22.5514 87.5921 52,
+                          -22.7 85 54,
+                          -22.5514 87.5921 52,
+                          -22.3458 81.0059 52,
+                          -19.6588 96.35 54,
+                          -22.5514 87.5921 52,
+                          -22.7 85 54,
+                          -22.7 85 54,
+                          -22.3458 81.0059 52,
+                          -19.6588 73.65 54,
+                          -19.6588 73.65 34,
+                          -19.6588 73.65 54,
+                          -22.3458 81.0059 52,
+                          -33.313 7.60268 54,
+                          -31.6478 12.8843 52,
+                          -34.1695 -0.168321 52,
+                          -26.7161 21.3029 54,
+                          -31.6478 12.8843 52,
+                          -33.313 7.60268 54,
+                          -33.313 -7.60268 54,
+                          -34.1695 -0.168321 52,
+                          -31.5206 -13.1916 52,
+                          -33.313 7.60268 54,
+                          -34.1695 -0.168321 52,
+                          -33.313 -7.60268 54,
+                          -26.7161 -21.3029 54,
+                          -31.5206 -13.1916 52,
+                          -24.1046 -24.2186 52,
+                          -33.313 -7.60268 54,
+                          -31.5206 -13.1916 52,
+                          -26.7161 -21.3029 54,
+                          -14.8275 -30.7852 54,
+                          -24.1046 -24.2186 52,
+                          -13.0412 -31.5834 52,
+                          -26.7161 -21.3029 54,
+                          -24.1046 -24.2186 52,
+                          -14.8275 -30.7852 54,
+                          14.8275 -30.7852 54,
+                          -14.8275 -30.7852 54,
+                          -8.39972e-14 -34.17 54,
+                          26.7161 -21.3029 54,
+                          -26.7161 -21.3029 54,
+                          -14.8275 -30.7852 54,
+                          14.8275 -30.7852 54,
+                          26.7161 -21.3029 54,
+                          -14.8275 -30.7852 54,
+                          33.313 -7.60268 54,
+                          -33.313 -7.60268 54,
+                          -26.7161 -21.3029 54,
+                          26.7161 -21.3029 54,
+                          33.313 -7.60268 54,
+                          -26.7161 -21.3029 54,
+                          33.313 7.60268 54,
+                          -33.313 7.60268 54,
+                          -33.313 -7.60268 54,
+                          33.313 -7.60268 54,
+                          33.313 7.60268 54,
+                          -33.313 -7.60268 54,
+                          26.7161 21.3029 54,
+                          -26.7161 21.3029 54,
+                          -33.313 7.60268 54,
+                          33.313 7.60268 54,
+                          26.7161 21.3029 54,
+                          -33.313 7.60268 54,
+                          14.8275 30.7852 54,
+                          -14.8275 30.7852 54,
+                          -26.7161 21.3029 54,
+                          -26.7161 21.3029 34,
+                          -26.7161 21.3029 54,
+                          -14.8275 30.7852 54,
+                          26.7161 21.3029 54,
+                          14.8275 30.7852 54,
+                          -26.7161 21.3029 54,
+                          14.8275 30.7852 54,
+                          6.97863e-14 34.17 54,
+                          -14.8275 30.7852 54,
+                          -14.8275 30.7852 34,
+                          -14.8275 30.7852 54,
+                          6.97863e-14 34.17 54,
+                          -26.7161 21.3029 34,
+                          -14.8275 30.7852 54,
+                          -14.8275 30.7852 34,
+                          6.97863e-14 34.17 34,
+                          6.97863e-14 34.17 54,
+                          14.8275 30.7852 54,
+                          -14.8275 30.7852 34,
+                          6.97863e-14 34.17 54,
+                          6.97863e-14 34.17 34,
+                          14.8275 30.7852 34,
+                          14.8275 30.7852 54,
+                          26.7161 21.3029 54,
+                          6.97863e-14 34.17 34,
+                          14.8275 30.7852 54,
+                          14.8275 30.7852 34,
+                          14.8275 30.7852 34,
+                          26.7161 21.3029 54,
+                          26.7161 21.3029 34,
+                          11.35 65.3412 54,
+                          -11.35 65.3412 54,
+                          1.43496e-13 62.3 54,
+                          1.43496e-13 62.3 34,
+                          1.43496e-13 62.3 54,
+                          -11.35 65.3412 54,
+                          11.35 65.3412 34,
+                          11.35 65.3412 54,
+                          1.43496e-13 62.3 54,
+                          11.35 65.3412 34,
+                          1.43496e-13 62.3 54,
+                          1.43496e-13 62.3 34,
+                          19.6588 73.65 54,
+                          -19.6588 73.65 54,
+                          -11.35 65.3412 54,
+                          -11.35 65.3412 34,
+                          -11.35 65.3412 54,
+                          -19.6588 73.65 54,
+                          11.35 65.3412 54,
+                          19.6588 73.65 54,
+                          -11.35 65.3412 54,
+                          -11.35 65.3412 34,
+                          1.43496e-13 62.3 34,
+                          -11.35 65.3412 54,
+                          22.7 85 54,
+                          -22.7 85 54,
+                          -19.6588 73.65 54,
+                          19.6588 73.65 54,
+                          22.7 85 54,
+                          -19.6588 73.65 54,
+                          -11.35 65.3412 34,
+                          -19.6588 73.65 54,
+                          -19.6588 73.65 34,
+                          19.6588 96.35 54,
+                          -19.6588 96.35 54,
+                          -22.7 85 54,
+                          22.7 85 54,
+                          19.6588 96.35 54,
+                          -22.7 85 54,
+                          11.35 104.659 54,
+                          -11.35 104.659 54,
+                          -19.6588 96.35 54,
+                          19.6588 96.35 54,
+                          11.35 104.659 54,
+                          -19.6588 96.35 54,
+                          11.35 104.659 54,
+                          2.45658e-13 107.7 54,
+                          -11.35 104.659 54,
+                          19.6588 73.65 34,
+                          19.6588 73.65 54,
+                          11.35 65.3412 54,
+                          19.6588 73.65 34,
+                          11.35 65.3412 54,
+                          11.35 65.3412 34,
+                          -14.8275 -30.7852 34,
+                          14.8275 -30.7852 34,
+                          -8.39972e-14 -34.17 34,
+                          -26.7161 -21.3029 34,
+                          26.7161 -21.3029 34,
+                          14.8275 -30.7852 34,
+                          -14.8275 -30.7852 34,
+                          -26.7161 -21.3029 34,
+                          14.8275 -30.7852 34,
+                          -33.313 -7.60268 34,
+                          33.313 -7.60268 34,
+                          26.7161 -21.3029 34,
+                          -26.7161 -21.3029 34,
+                          -33.313 -7.60268 34,
+                          26.7161 -21.3029 34,
+                          -33.313 7.60268 34,
+                          33.313 7.60268 34,
+                          33.313 -7.60268 34,
+                          -33.313 -7.60268 34,
+                          -33.313 7.60268 34,
+                          33.313 -7.60268 34,
+                          -26.7161 21.3029 34,
+                          26.7161 21.3029 34,
+                          33.313 7.60268 34,
+                          -33.313 7.60268 34,
+                          -26.7161 21.3029 34,
+                          33.313 7.60268 34,
+                          -14.8275 30.7852 34,
+                          14.8275 30.7852 34,
+                          26.7161 21.3029 34,
+                          -26.7161 21.3029 34,
+                          -14.8275 30.7852 34,
+                          26.7161 21.3029 34,
+                          -14.8275 30.7852 34,
+                          6.97863e-14 34.17 34,
+                          14.8275 30.7852 34,
+                          -11.35 65.3412 34,
+                          11.35 65.3412 34,
+                          1.43496e-13 62.3 34,
+                          -19.6588 73.65 34,
+                          19.6588 73.65 34,
+                          11.35 65.3412 34,
+                          -11.35 65.3412 34,
+                          -19.6588 73.65 34,
+                          11.35 65.3412 34,
+                          -22.7 85 34,
+                          22.7 85 34,
+                          19.6588 73.65 34,
+                          -19.6588 73.65 34,
+                          -22.7 85 34,
+                          19.6588 73.65 34,
+                          -19.6588 96.35 34,
+                          19.6588 96.35 34,
+                          22.7 85 34,
+                          -22.7 85 34,
+                          -19.6588 96.35 34,
+                          22.7 85 34,
+                          -11.35 104.659 34,
+                          11.35 104.659 34,
+                          19.6588 96.35 34,
+                          -19.6588 96.35 34,
+                          -11.35 104.659 34,
+                          19.6588 96.35 34,
+                          -11.35 104.659 34,
+                          2.45658e-13 107.7 34,
+                          11.35 104.659 34 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.85 0.9 0.47
+    }
+    Separator {
+        Normal {
+            vector      [ 0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -3.06152e-16 -1 0,
+                          -3.06152e-16 -1 0,
+                          -0.587785 -0.809017 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.587785 -0.809017 0,
+                          0.587785 -0.809017 0,
+                          -6.12303e-17 -1 0,
+                          0.587785 -0.809017 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.587785 -0.809017 0,
+                          -0.587785 -0.809017 0,
+                          -0.951057 -0.309017 0,
+                          -0.587785 -0.809017 0,
+                          -3.06152e-16 -1 0,
+                          -0.587785 -0.809017 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.951057 -0.309017 0,
+                          -0.951057 -0.309017 0,
+                          -0.951057 0.309017 0,
+                          -0.587785 -0.809017 0,
+                          -0.951057 -0.309017 0,
+                          -0.951057 -0.309017 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.951057 0.309017 0,
+                          -0.951057 0.309017 0,
+                          -0.587785 0.809017 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.951057 -0.309017 0,
+                          -0.951057 0.309017 0,
+                          -0.951057 0.309017 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.587785 0.809017 0,
+                          -0.587785 0.809017 0,
+                          1.83691e-16 1 0,
+                          -0.951057 0.309017 0,
+                          -0.587785 0.809017 0,
+                          -0.587785 0.809017 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          0.587785 0.809017 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.587785 0.809017 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.587785 0.809017 0,
+                          0.587785 0.809017 0,
+                          0.951057 0.309017 0,
+                          1.83691e-16 1 0,
+                          0.587785 0.809017 0,
+                          0.587785 0.809017 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.951057 0.309017 0,
+                          0.951057 0.309017 0,
+                          0.951057 -0.309017 0,
+                          0.587785 0.809017 0,
+                          0.951057 0.309017 0,
+                          0.951057 0.309017 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.951057 -0.309017 0,
+                          0.951057 -0.309017 0,
+                          0.587785 -0.809017 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.951057 0.309017 0,
+                          0.951057 -0.309017 0,
+                          0.951057 -0.309017 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.951057 -0.309017 0,
+                          0.587785 -0.809017 0,
+                          0.587785 -0.809017 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -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,
+                          1 -1.83691e-16 0,
+                          1 -1.83691e-16 0,
+                          0.809017 -0.587785 0,
+                          0.809017 0.587785 0,
+                          0.809017 0.587785 0,
+                          1 -1.83691e-16 0,
+                          0.809017 0.587785 0,
+                          1 -1.83691e-16 0,
+                          1 -1.83691e-16 0,
+                          0.809017 -0.587785 0,
+                          0.809017 -0.587785 0,
+                          0.309017 -0.951057 0,
+                          1 -1.83691e-16 0,
+                          0.809017 -0.587785 0,
+                          0.809017 -0.587785 0,
+                          0.309017 -0.951057 0,
+                          0.309017 -0.951057 0,
+                          -0.309017 -0.951057 0,
+                          0.809017 -0.587785 0,
+                          0.309017 -0.951057 0,
+                          0.309017 -0.951057 0,
+                          -0.309017 -0.951057 0,
+                          -0.309017 -0.951057 0,
+                          -0.809017 -0.587785 0,
+                          0.309017 -0.951057 0,
+                          -0.309017 -0.951057 0,
+                          -0.309017 -0.951057 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.809017 -0.587785 0,
+                          -0.809017 -0.587785 0,
+                          -1 6.12303e-17 0,
+                          -0.309017 -0.951057 0,
+                          -0.809017 -0.587785 0,
+                          -0.809017 -0.587785 0,
+                          -1 3.06152e-16 0,
+                          -1 3.06152e-16 0,
+                          -0.809017 0.587785 0,
+                          -0.809017 -0.587785 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -0.809017 0.587785 0,
+                          -0.809017 0.587785 0,
+                          -0.309017 0.951057 0,
+                          -0.809017 0.587785 0,
+                          -1 3.06152e-16 0,
+                          -0.809017 0.587785 0,
+                          -0.309017 0.951057 0,
+                          -0.309017 0.951057 0,
+                          0.309017 0.951057 0,
+                          -0.809017 0.587785 0,
+                          -0.309017 0.951057 0,
+                          -0.309017 0.951057 0,
+                          0.309017 0.951057 0,
+                          0.309017 0.951057 0,
+                          0.809017 0.587785 0,
+                          -0.309017 0.951057 0,
+                          0.309017 0.951057 0,
+                          0.309017 0.951057 0,
+                          0.309017 0.951057 0,
+                          0.809017 0.587785 0,
+                          0.809017 0.587785 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.866025 -0.5 0,
+                          -0.6 -0.8 0,
+                          -0.5 -0.866025 0,
+                          -0.212859 -0.977083 0,
+                          -0.5 -0.866025 0,
+                          -0.6 -0.8 0,
+                          -0.894388 -0.447292 0,
+                          -0.6 -0.8 0,
+                          -0.866025 -0.5 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.5 -0.866025 0,
+                          0.6 -0.8 0,
+                          0.866025 -0.5 0,
+                          0.894388 -0.447292 0,
+                          0.866025 -0.5 0,
+                          0.6 -0.8 0,
+                          0.212859 -0.977083 0,
+                          0.6 -0.8 0,
+                          0.5 -0.866025 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,
+                          1 -3.06152e-16 0,
+                          1 -3.06152e-16 0,
+                          0.866025 -0.5 0,
+                          0.86603 0.499993 0,
+                          0.866025 0.5 0,
+                          1 -6.12303e-17 0,
+                          0.86603 0.499993 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          0.894388 -0.447292 0,
+                          1 -3.06152e-16 0,
+                          0.866025 -0.5 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.212859 -0.977083 0,
+                          0.5 -0.866025 0,
+                          -2.44921e-16 -1 0,
+                          -0.212859 -0.977083 0,
+                          -2.44921e-16 -1 0,
+                          -0.5 -0.866025 0,
+                          0.212859 -0.977083 0,
+                          -2.44921e-16 -1 0,
+                          -0.212859 -0.977083 0,
+                          -0.894388 -0.447292 0,
+                          -0.866025 -0.5 0,
+                          -1 1.83691e-16 0,
+                          -1 1.83691e-16 0,
+                          -1 1.83691e-16 0,
+                          -0.866025 0.5 0,
+                          -0.894388 -0.447292 0,
+                          -1 1.83691e-16 0,
+                          -1 1.83691e-16 0,
+                          -0.500006 0.866022 0,
+                          -0.866025 0.5 0,
+                          -0.5 0.866025 0,
+                          -0.86603 0.499993 0,
+                          -1 1.83691e-16 0,
+                          -0.866025 0.5 0,
+                          -0.500006 0.866022 0,
+                          -0.86603 0.499993 0,
+                          -0.866025 0.5 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.500006 0.866022 0,
+                          -0.5 0.866025 0,
+                          1.22461e-16 1 0,
+                          -3.21629e-16 1 0,
+                          1.22461e-16 1 0,
+                          0.5 0.866025 0,
+                          -3.21629e-16 1 0,
+                          -0.500006 0.866022 0,
+                          1.22461e-16 1 0,
+                          0.500006 0.866022 0,
+                          0.5 0.866025 0,
+                          0.866025 0.5 0,
+                          0.500006 0.866022 0,
+                          -3.21629e-16 1 0,
+                          0.5 0.866025 0,
+                          0.86603 0.499993 0,
+                          0.500006 0.866022 0,
+                          0.866025 0.5 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 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 25 112.726 57,
+                          9.11067 97.2654 57,
+                          3.97501e-13 100.226 57,
+                          3.97501e-13 100.226 68,
+                          3.97501e-13 100.226 57,
+                          9.11067 97.2654 57,
+                          25 112.726 57,
+                          3.97501e-13 100.226 57,
+                          -9.11067 97.2654 57,
+                          -9.11067 97.2654 68,
+                          -9.11067 97.2654 57,
+                          3.97501e-13 100.226 57,
+                          -9.11067 97.2654 68,
+                          3.97501e-13 100.226 57,
+                          3.97501e-13 100.226 68,
+                          25 112.726 57,
+                          14.7414 89.5154 57,
+                          9.11067 97.2654 57,
+                          9.11067 97.2654 68,
+                          9.11067 97.2654 57,
+                          14.7414 89.5154 57,
+                          9.11067 97.2654 68,
+                          3.97501e-13 100.226 68,
+                          9.11067 97.2654 57,
+                          25 112.726 57,
+                          14.7414 79.9358 57,
+                          14.7414 89.5154 57,
+                          14.7414 89.5154 68,
+                          14.7414 89.5154 57,
+                          14.7414 79.9358 57,
+                          9.11067 97.2654 68,
+                          14.7414 89.5154 57,
+                          14.7414 89.5154 68,
+                          25 64.7256 57,
+                          9.11067 72.1858 57,
+                          14.7414 79.9358 57,
+                          14.7414 79.9358 68,
+                          14.7414 79.9358 57,
+                          9.11067 72.1858 57,
+                          25 64.7256 57,
+                          14.7414 79.9358 57,
+                          25 112.726 57,
+                          14.7414 89.5154 68,
+                          14.7414 79.9358 57,
+                          14.7414 79.9358 68,
+                          25 64.7256 57,
+                          3.91807e-13 69.2256 57,
+                          9.11067 72.1858 57,
+                          9.11067 72.1858 68,
+                          9.11067 72.1858 57,
+                          3.91807e-13 69.2256 57,
+                          14.7414 79.9358 68,
+                          9.11067 72.1858 57,
+                          9.11067 72.1858 68,
+                          -25 64.7256 57,
+                          -9.11067 72.1858 57,
+                          3.91807e-13 69.2256 57,
+                          3.91807e-13 69.2256 68,
+                          3.91807e-13 69.2256 57,
+                          -9.11067 72.1858 57,
+                          25 64.7256 57,
+                          -25 64.7256 57,
+                          3.91807e-13 69.2256 57,
+                          9.11067 72.1858 68,
+                          3.91807e-13 69.2256 57,
+                          3.91807e-13 69.2256 68,
+                          -25 64.7256 57,
+                          -14.7414 79.9358 57,
+                          -9.11067 72.1858 57,
+                          -9.11067 72.1858 68,
+                          -9.11067 72.1858 57,
+                          -14.7414 79.9358 57,
+                          3.91807e-13 69.2256 68,
+                          -9.11067 72.1858 57,
+                          -9.11067 72.1858 68,
+                          -25 64.7256 57,
+                          -14.7414 89.5154 57,
+                          -14.7414 79.9358 57,
+                          -14.7414 79.9358 68,
+                          -14.7414 79.9358 57,
+                          -14.7414 89.5154 57,
+                          -9.11067 72.1858 68,
+                          -14.7414 79.9358 57,
+                          -14.7414 79.9358 68,
+                          -25 112.726 57,
+                          -9.11067 97.2654 57,
+                          -14.7414 89.5154 57,
+                          -14.7414 89.5154 68,
+                          -14.7414 89.5154 57,
+                          -9.11067 97.2654 57,
+                          -25 64.7256 57,
+                          -25 112.726 57,
+                          -14.7414 89.5154 57,
+                          -14.7414 79.9358 68,
+                          -14.7414 89.5154 57,
+                          -14.7414 89.5154 68,
+                          -25 112.726 57,
+                          25 112.726 57,
+                          -9.11067 97.2654 57,
+                          -14.7414 89.5154 68,
+                          -9.11067 97.2654 57,
+                          -9.11067 97.2654 68,
+                          25 112.726 74,
+                          25 112.726 57,
+                          -25 112.726 57,
+                          25 64.7256 74,
+                          25 64.7256 57,
+                          25 112.726 57,
+                          25 84.7256 74,
+                          25 64.7256 74,
+                          25 112.726 57,
+                          25 112.726 74,
+                          25 84.7256 74,
+                          25 112.726 57,
+                          -25 112.726 74,
+                          -25 112.726 57,
+                          -25 64.7256 57,
+                          -25 112.726 74,
+                          25 112.726 74,
+                          -25 112.726 57,
+                          -25 64.7256 74,
+                          -25 64.7256 57,
+                          25 64.7256 57,
+                          -25 84.7256 74,
+                          -25 64.7256 57,
+                          -25 64.7256 74,
+                          -25 112.726 74,
+                          -25 64.7256 57,
+                          -25 84.7256 74,
+                          -15 64.7256 74,
+                          -25 64.7256 74,
+                          25 64.7256 57,
+                          15 64.7256 74,
+                          -15 64.7256 74,
+                          25 64.7256 57,
+                          25 64.7256 74,
+                          15 64.7256 74,
+                          25 64.7256 57,
+                          -5.87046 102.796 68,
+                          -9.11067 97.2654 68,
+                          3.97501e-13 100.226 68,
+                          5.87046 102.796 68,
+                          3.97501e-13 100.226 68,
+                          9.11067 97.2654 68,
+                          5.87046 102.796 68,
+                          -5.87046 102.796 68,
+                          3.97501e-13 100.226 68,
+                          -15.3714 95.893 68,
+                          -14.7414 89.5154 68,
+                          -9.11067 97.2654 68,
+                          -5.87046 102.796 68,
+                          -15.3714 95.893 68,
+                          -9.11067 97.2654 68,
+                          -15.3714 95.893 68,
+                          -14.7414 79.9358 68,
+                          -14.7414 89.5154 68,
+                          -5.87046 66.6553 68,
+                          -9.11067 72.1858 68,
+                          -14.7414 79.9358 68,
+                          -15.3714 73.5581 68,
+                          -14.7414 79.9358 68,
+                          -15.3714 95.893 68,
+                          -15.3714 73.5581 68,
+                          -5.87046 66.6553 68,
+                          -14.7414 79.9358 68,
+                          -5.87046 66.6553 68,
+                          3.91807e-13 69.2256 68,
+                          -9.11067 72.1858 68,
+                          5.87046 66.6553 68,
+                          9.11067 72.1858 68,
+                          3.91807e-13 69.2256 68,
+                          -5.87046 66.6553 68,
+                          5.87046 66.6553 68,
+                          3.91807e-13 69.2256 68,
+                          15.3714 73.5581 68,
+                          14.7414 79.9358 68,
+                          9.11067 72.1858 68,
+                          5.87046 66.6553 68,
+                          15.3714 73.5581 68,
+                          9.11067 72.1858 68,
+                          15.3714 73.5581 68,
+                          14.7414 89.5154 68,
+                          14.7414 79.9358 68,
+                          5.87046 102.796 68,
+                          9.11067 97.2654 68,
+                          14.7414 89.5154 68,
+                          15.3714 95.893 68,
+                          5.87046 102.796 68,
+                          14.7414 89.5154 68,
+                          15.3714 73.5581 68,
+                          15.3714 95.893 68,
+                          14.7414 89.5154 68,
+                          -15.3714 73.5581 68,
+                          -15.3714 95.893 68,
+                          -19 84.7256 68,
+                          -19 84.7256 92,
+                          -19 84.7256 68,
+                          -15.3714 95.893 68,
+                          -15.3718 73.5585 92,
+                          -15.3714 73.5581 68,
+                          -19 84.7256 68,
+                          -15.3718 73.5585 92,
+                          -19 84.7256 68,
+                          -19 84.7256 92,
+                          -15.3718 95.8926 92,
+                          -15.3714 95.893 68,
+                          -5.87046 102.796 68,
+                          -19 84.7256 92,
+                          -15.3714 95.893 68,
+                          -15.3718 95.8926 92,
+                          -5.87174 102.795 92,
+                          -5.87046 102.796 68,
+                          5.87046 102.796 68,
+                          -15.3718 95.8926 92,
+                          -5.87046 102.796 68,
+                          -5.87174 102.795 92,
+                          5.87174 102.795 92,
+                          5.87046 102.796 68,
+                          15.3714 95.893 68,
+                          -5.87174 102.795 92,
+                          5.87046 102.796 68,
+                          5.87174 102.795 92,
+                          15.3714 73.5581 68,
+                          19 84.7256 68,
+                          15.3714 95.893 68,
+                          15.3718 95.8926 92,
+                          15.3714 95.893 68,
+                          19 84.7256 68,
+                          5.87174 102.795 92,
+                          15.3714 95.893 68,
+                          15.3718 95.8926 92,
+                          19 84.7256 92,
+                          19 84.7256 68,
+                          15.3714 73.5581 68,
+                          15.3718 95.8926 92,
+                          19 84.7256 68,
+                          19 84.7256 92,
+                          15.3718 73.5585 92,
+                          15.3714 73.5581 68,
+                          5.87046 66.6553 68,
+                          15.3718 73.5585 92,
+                          19 84.7256 92,
+                          15.3714 73.5581 68,
+                          5.87174 66.6559 92,
+                          5.87046 66.6553 68,
+                          -5.87046 66.6553 68,
+                          15.3718 73.5585 92,
+                          5.87046 66.6553 68,
+                          5.87174 66.6559 92,
+                          -5.87174 66.6559 92,
+                          -5.87046 66.6553 68,
+                          -15.3714 73.5581 68,
+                          5.87174 66.6559 92,
+                          -5.87046 66.6553 68,
+                          -5.87174 66.6559 92,
+                          -5.87174 66.6559 92,
+                          -15.3714 73.5581 68,
+                          -15.3718 73.5585 92,
+                          -22.3597 73.5433 74,
+                          -25 64.7256 74,
+                          -15 64.7256 74,
+                          -22.3597 73.5433 74,
+                          -25 84.7256 74,
+                          -25 64.7256 74,
+                          -5.3221 60.2988 74,
+                          -15 64.7256 74,
+                          15 64.7256 74,
+                          -21.6501 72.2248 92,
+                          -15 64.7256 74,
+                          -12.4992 63.0747 92,
+                          -5.3221 60.2988 74,
+                          -12.4992 63.0747 92,
+                          -15 64.7256 74,
+                          -22.3597 73.5433 74,
+                          -15 64.7256 74,
+                          -21.6501 72.2248 92,
+                          22.3597 73.5433 74,
+                          15 64.7256 74,
+                          25 64.7256 74,
+                          12.4992 63.0747 92,
+                          15 64.7256 74,
+                          21.6501 72.2248 92,
+                          22.3597 73.5433 74,
+                          21.6501 72.2248 92,
+                          15 64.7256 74,
+                          5.3221 60.2988 74,
+                          15 64.7256 74,
+                          12.4992 63.0747 92,
+                          5.3221 60.2988 74,
+                          -5.3221 60.2988 74,
+                          15 64.7256 74,
+                          22.3597 73.5433 74,
+                          25 64.7256 74,
+                          25 84.7256 74,
+                          21.6501 97.2264 92,
+                          15.3718 95.8926 92,
+                          19 84.7256 92,
+                          25 84.7256 92,
+                          19 84.7256 92,
+                          15.3718 73.5585 92,
+                          21.6501 97.2264 92,
+                          19 84.7256 92,
+                          25 84.7256 92,
+                          21.6501 97.2264 92,
+                          5.87174 102.795 92,
+                          15.3718 95.8926 92,
+                          12.4992 106.376 92,
+                          -5.87174 102.795 92,
+                          5.87174 102.795 92,
+                          21.6501 97.2264 92,
+                          12.4992 106.376 92,
+                          5.87174 102.795 92,
+                          -21.6501 97.2264 92,
+                          -15.3718 95.8926 92,
+                          -5.87174 102.795 92,
+                          -12.4992 106.376 92,
+                          -21.6501 97.2264 92,
+                          -5.87174 102.795 92,
+                          12.4992 106.376 92,
+                          -12.4992 106.376 92,
+                          -5.87174 102.795 92,
+                          -25 84.7256 92,
+                          -19 84.7256 92,
+                          -15.3718 95.8926 92,
+                          -21.6501 97.2264 92,
+                          -25 84.7256 92,
+                          -15.3718 95.8926 92,
+                          -21.6501 72.2248 92,
+                          -15.3718 73.5585 92,
+                          -19 84.7256 92,
+                          -25 84.7256 92,
+                          -21.6501 72.2248 92,
+                          -19 84.7256 92,
+                          -21.6501 72.2248 92,
+                          -5.87174 66.6559 92,
+                          -15.3718 73.5585 92,
+                          -12.4992 63.0747 92,
+                          5.87174 66.6559 92,
+                          -5.87174 66.6559 92,
+                          -21.6501 72.2248 92,
+                          -12.4992 63.0747 92,
+                          -5.87174 66.6559 92,
+                          21.6501 72.2248 92,
+                          15.3718 73.5585 92,
+                          5.87174 66.6559 92,
+                          12.4992 63.0747 92,
+                          21.6501 72.2248 92,
+                          5.87174 66.6559 92,
+                          -12.4992 63.0747 92,
+                          12.4992 63.0747 92,
+                          5.87174 66.6559 92,
+                          21.6501 72.2248 92,
+                          25 84.7256 92,
+                          15.3718 73.5585 92,
+                          25 84.7256 74,
+                          25 84.7256 92,
+                          21.6501 72.2248 92,
+                          21.6502 97.2262 74,
+                          21.6501 97.2264 92,
+                          25 84.7256 92,
+                          21.6502 97.2262 74,
+                          25 84.7256 92,
+                          25 84.7256 74,
+                          22.3597 73.5433 74,
+                          25 84.7256 74,
+                          21.6501 72.2248 92,
+                          -12.4992 63.0747 92,
+                          3.88571e-13 59.7258 92,
+                          12.4992 63.0747 92,
+                          5.3221 60.2988 74,
+                          12.4992 63.0747 92,
+                          3.88571e-13 59.7258 92,
+                          -5.3221 60.2988 74,
+                          3.88571e-13 59.7258 92,
+                          -12.4992 63.0747 92,
+                          5.3221 60.2988 74,
+                          3.88571e-13 59.7258 92,
+                          -5.3221 60.2988 74,
+                          -22.3597 73.5433 74,
+                          -21.6501 72.2248 92,
+                          -25 84.7256 92,
+                          -25 84.7256 74,
+                          -25 84.7256 92,
+                          -21.6501 97.2264 92,
+                          -22.3597 73.5433 74,
+                          -25 84.7256 92,
+                          -25 84.7256 74,
+                          -12.4994 106.376 74,
+                          -21.6501 97.2264 92,
+                          -12.4992 106.376 92,
+                          -21.6502 97.2262 74,
+                          -25 84.7256 74,
+                          -21.6501 97.2264 92,
+                          -12.4994 106.376 74,
+                          -21.6502 97.2262 74,
+                          -21.6501 97.2264 92,
+                          12.4992 106.376 92,
+                          3.97295e-13 109.725 92,
+                          -12.4992 106.376 92,
+                          -12.4994 106.376 74,
+                          -12.4992 106.376 92,
+                          3.97295e-13 109.725 92,
+                          3.86526e-13 109.725 74,
+                          3.97295e-13 109.725 92,
+                          12.4992 106.376 92,
+                          3.86526e-13 109.725 74,
+                          -12.4994 106.376 74,
+                          3.97295e-13 109.725 92,
+                          12.4994 106.376 74,
+                          12.4992 106.376 92,
+                          21.6501 97.2264 92,
+                          12.4994 106.376 74,
+                          3.86526e-13 109.725 74,
+                          12.4992 106.376 92,
+                          21.6502 97.2262 74,
+                          12.4994 106.376 74,
+                          21.6501 97.2264 92,
+                          25 112.726 74,
+                          21.6502 97.2262 74,
+                          25 84.7256 74,
+                          -25 112.726 74,
+                          -25 84.7256 74,
+                          -21.6502 97.2262 74,
+                          -25 112.726 74,
+                          -21.6502 97.2262 74,
+                          -12.4994 106.376 74,
+                          -25 112.726 74,
+                          -12.4994 106.376 74,
+                          3.86526e-13 109.725 74,
+                          25 112.726 74,
+                          3.86526e-13 109.725 74,
+                          12.4994 106.376 74,
+                          -25 112.726 74,
+                          3.86526e-13 109.725 74,
+                          25 112.726 74,
+                          25 112.726 74,
+                          12.4994 106.376 74,
+                          21.6502 97.2262 74 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          6.12303e-17 -1 0,
+                          6.12303e-17 -1 0,
+                          -0.866025 -0.5 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.866025 -0.5 0,
+                          0.866025 -0.5 0,
+                          6.12303e-17 -1 0,
+                          0.866025 -0.5 0,
+                          6.12303e-17 -1 0,
+                          6.12303e-17 -1 0,
+                          -0.866025 -0.5 0,
+                          -0.866025 -0.5 0,
+                          -0.866025 0.5 0,
+                          -0.866025 -0.5 0,
+                          6.12303e-17 -1 0,
+                          -0.866025 -0.5 0,
+                          -0.866025 0.5 0,
+                          -0.866025 0.5 0,
+                          -1.83691e-16 1 0,
+                          -0.866025 -0.5 0,
+                          -0.866025 0.5 0,
+                          -0.866025 0.5 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.866025 0.5 0,
+                          -0.866025 0.5 0,
+                          -1.83691e-16 1 0,
+                          -1.83691e-16 1 0,
+                          0.866025 0.5 0,
+                          0.866025 0.5 0,
+                          0.866025 -0.5 0,
+                          6.12303e-17 1 0,
+                          0.866025 0.5 0,
+                          0.866025 0.5 0,
+                          0.866025 0.5 0,
+                          0.866025 -0.5 0,
+                          0.866025 -0.5 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          6.12303e-17 -1 0,
+                          6.12303e-17 -1 0,
+                          -0.707107 -0.707107 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.707107 -0.707107 0,
+                          0.707107 -0.707107 0,
+                          6.12303e-17 -1 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.707107 -0.707107 0,
+                          6.12303e-17 -1 0,
+                          6.12303e-17 -1 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          -1 -1.22461e-16 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.707107 -0.707107 0,
+                          6.12303e-17 -1 0,
+                          -0.707107 -0.707107 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -0.707107 0.707107 0,
+                          -0.707107 -0.707107 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.707107 0.707107 0,
+                          -0.707107 0.707107 0,
+                          -1.83691e-16 1 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -1 -1.22461e-16 0,
+                          -0.707107 0.707107 0,
+                          -0.707107 0.707107 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.707107 0.707107 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.707107 0.707107 0,
+                          -1.83691e-16 1 0,
+                          -1.83691e-16 1 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.707107 0.707107 0,
+                          0.707107 0.707107 0,
+                          1 0 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          6.12303e-17 1 0,
+                          0.707107 0.707107 0,
+                          0.707107 0.707107 0,
+                          1 0 0,
+                          1 0 0,
+                          0.707107 -0.707107 0,
+                          0.707107 0.707107 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          1 0 0,
+                          0.707107 -0.707107 0,
+                          0.707107 -0.707107 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          6.12303e-17 -1 0,
+                          6.12303e-17 -1 0,
+                          -0.866025 -0.5 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.866025 -0.5 0,
+                          0.866025 -0.5 0,
+                          6.12303e-17 -1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.866025 -0.5 0,
+                          6.12303e-17 -1 0,
+                          6.12303e-17 -1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.866025 -0.5 0,
+                          -0.866025 -0.5 0,
+                          -0.866025 0.5 0,
+                          -0.866025 -0.5 0,
+                          6.12303e-17 -1 0,
+                          -0.866025 -0.5 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.866025 0.5 0,
+                          -0.866025 0.5 0,
+                          -1.83691e-16 1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.866025 -0.5 0,
+                          -0.866025 0.5 0,
+                          -0.866025 0.5 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.866025 0.5 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.866025 0.5 0,
+                          -1.83691e-16 1 0,
+                          -1.83691e-16 1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.866025 0.5 0,
+                          0.866025 0.5 0,
+                          0.866025 -0.5 0,
+                          6.12303e-17 1 0,
+                          0.866025 0.5 0,
+                          0.866025 0.5 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.866025 0.5 0,
+                          0.866025 -0.5 0,
+                          0.866025 -0.5 0,
+                          6.12303e-17 -1 0,
+                          6.12303e-17 -1 0,
+                          0.866025 -0.5 0,
+                          -0.866025 -0.5 0,
+                          -0.866025 -0.5 0,
+                          6.12303e-17 -1 0,
+                          -0.866025 -0.5 0,
+                          6.12303e-17 -1 0,
+                          6.12303e-17 -1 0,
+                          0.866025 -0.5 0,
+                          0.866025 -0.5 0,
+                          0.866025 0.5 0,
+                          0.866025 -0.5 0,
+                          6.12303e-17 -1 0,
+                          0.866025 -0.5 0,
+                          0.866025 0.5 0,
+                          0.866025 0.5 0,
+                          6.12303e-17 1 0,
+                          0.866025 -0.5 0,
+                          0.866025 0.5 0,
+                          0.866025 0.5 0,
+                          -1.83691e-16 1 0,
+                          -1.83691e-16 1 0,
+                          -0.866025 0.5 0,
+                          0.866025 0.5 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.866025 0.5 0,
+                          -0.866025 0.5 0,
+                          -0.866025 -0.5 0,
+                          -1.83691e-16 1 0,
+                          -0.866025 0.5 0,
+                          -0.866025 0.5 0,
+                          -0.866025 0.5 0,
+                          -0.866025 -0.5 0,
+                          -0.866025 -0.5 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          6.12303e-17 -1 0,
+                          6.12303e-17 -1 0,
+                          -0.866025 -0.5 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.866025 -0.5 0,
+                          0.866025 -0.5 0,
+                          6.12303e-17 -1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.866025 -0.5 0,
+                          6.12303e-17 -1 0,
+                          6.12303e-17 -1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.866025 -0.5 0,
+                          -0.866025 -0.5 0,
+                          -0.866025 0.5 0,
+                          -0.866025 -0.5 0,
+                          6.12303e-17 -1 0,
+                          -0.866025 -0.5 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.866025 0.5 0,
+                          -0.866025 0.5 0,
+                          -1.83691e-16 1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.866025 -0.5 0,
+                          -0.866025 0.5 0,
+                          -0.866025 0.5 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.866025 0.5 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.866025 0.5 0,
+                          -1.83691e-16 1 0,
+                          -1.83691e-16 1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.866025 0.5 0,
+                          0.866025 0.5 0,
+                          0.866025 -0.5 0,
+                          6.12303e-17 1 0,
+                          0.866025 0.5 0,
+                          0.866025 0.5 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.866025 0.5 0,
+                          0.866025 -0.5 0,
+                          0.866025 -0.5 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          6.12303e-17 -1 0,
+                          6.12303e-17 -1 0,
+                          -0.866025 -0.5 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.866025 -0.5 0,
+                          0.866025 -0.5 0,
+                          6.12303e-17 -1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.866025 -0.5 0,
+                          6.12303e-17 -1 0,
+                          6.12303e-17 -1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.866025 -0.5 0,
+                          -0.866025 -0.5 0,
+                          -0.866025 0.5 0,
+                          -0.866025 -0.5 0,
+                          6.12303e-17 -1 0,
+                          -0.866025 -0.5 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.866025 0.5 0,
+                          -0.866025 0.5 0,
+                          -1.83691e-16 1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.866025 -0.5 0,
+                          -0.866025 0.5 0,
+                          -0.866025 0.5 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.866025 0.5 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.866025 0.5 0,
+                          -1.83691e-16 1 0,
+                          -1.83691e-16 1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.866025 0.5 0,
+                          0.866025 0.5 0,
+                          0.866025 -0.5 0,
+                          6.12303e-17 1 0,
+                          0.866025 0.5 0,
+                          0.866025 0.5 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.866025 0.5 0,
+                          0.866025 -0.5 0,
+                          0.866025 -0.5 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,
+                          6.12303e-17 -1 0,
+                          6.12303e-17 -1 0,
+                          0.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          6.12303e-17 -1 0,
+                          -0.707107 -0.707107 0,
+                          6.12303e-17 -1 0,
+                          6.12303e-17 -1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.707107 -0.707107 0,
+                          0.707107 -0.707107 0,
+                          1 0 0,
+                          0.707107 -0.707107 0,
+                          6.12303e-17 -1 0,
+                          0.707107 -0.707107 0,
+                          1 0 0,
+                          1 0 0,
+                          0.707107 0.707107 0,
+                          0.707107 -0.707107 0,
+                          1 0 0,
+                          1 0 0,
+                          0.707107 0.707107 0,
+                          0.707107 0.707107 0,
+                          6.12303e-17 1 0,
+                          1 0 0,
+                          0.707107 0.707107 0,
+                          0.707107 0.707107 0,
+                          -1.83691e-16 1 0,
+                          -1.83691e-16 1 0,
+                          -0.707107 0.707107 0,
+                          0.707107 0.707107 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.707107 0.707107 0,
+                          -0.707107 0.707107 0,
+                          -1 -1.22461e-16 0,
+                          -1.83691e-16 1 0,
+                          -0.707107 0.707107 0,
+                          -0.707107 0.707107 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -0.707107 -0.707107 0,
+                          -0.707107 0.707107 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -0.707107 -0.707107 0,
+                          -0.707107 -0.707107 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 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -4.76314 87.4756 76.5,
+                          -4.76314 81.9756 76.5,
+                          4.20074e-13 79.2256 76.5,
+                          4.20074e-13 79.2256 74.5,
+                          4.20074e-13 79.2256 76.5,
+                          -4.76314 81.9756 76.5,
+                          4.20748e-13 90.2256 76.5,
+                          -4.76314 87.4756 76.5,
+                          4.20074e-13 79.2256 76.5,
+                          4.76314 81.9756 76.5,
+                          4.20748e-13 90.2256 76.5,
+                          4.20074e-13 79.2256 76.5,
+                          4.76314 81.9756 74.5,
+                          4.76314 81.9756 76.5,
+                          4.20074e-13 79.2256 76.5,
+                          4.76314 81.9756 74.5,
+                          4.20074e-13 79.2256 76.5,
+                          4.20074e-13 79.2256 74.5,
+                          -4.76314 81.9756 74.5,
+                          -4.76314 81.9756 76.5,
+                          -4.76314 87.4756 76.5,
+                          -4.76314 81.9756 74.5,
+                          4.20074e-13 79.2256 74.5,
+                          -4.76314 81.9756 76.5,
+                          -4.76314 87.4756 74.5,
+                          -4.76314 87.4756 76.5,
+                          4.20748e-13 90.2256 76.5,
+                          -4.76314 81.9756 74.5,
+                          -4.76314 87.4756 76.5,
+                          -4.76314 87.4756 74.5,
+                          4.76314 81.9756 76.5,
+                          4.76314 87.4756 76.5,
+                          4.20748e-13 90.2256 76.5,
+                          4.20748e-13 90.2256 74.5,
+                          4.20748e-13 90.2256 76.5,
+                          4.76314 87.4756 76.5,
+                          -4.76314 87.4756 74.5,
+                          4.20748e-13 90.2256 76.5,
+                          4.20748e-13 90.2256 74.5,
+                          4.76314 87.4756 74.5,
+                          4.76314 87.4756 76.5,
+                          4.76314 81.9756 76.5,
+                          4.20748e-13 90.2256 74.5,
+                          4.76314 87.4756 76.5,
+                          4.76314 87.4756 74.5,
+                          4.76314 87.4756 74.5,
+                          4.76314 81.9756 76.5,
+                          4.76314 81.9756 74.5,
+                          -4.76314 81.9756 74.5,
+                          -8.13155 76.594 74.5,
+                          4.19707e-13 73.2256 74.5,
+                          4.19707e-13 73.2256 68,
+                          4.19707e-13 73.2256 74.5,
+                          -8.13155 76.594 74.5,
+                          4.20074e-13 79.2256 74.5,
+                          4.19707e-13 73.2256 74.5,
+                          8.13155 76.594 74.5,
+                          8.13155 76.594 68,
+                          8.13155 76.594 74.5,
+                          4.19707e-13 73.2256 74.5,
+                          -4.76314 81.9756 74.5,
+                          4.19707e-13 73.2256 74.5,
+                          4.20074e-13 79.2256 74.5,
+                          8.13155 76.594 68,
+                          4.19707e-13 73.2256 74.5,
+                          4.19707e-13 73.2256 68,
+                          -8.13155 92.8571 74.5,
+                          -11.5 84.7256 74.5,
+                          -8.13155 76.594 74.5,
+                          -8.13155 76.594 68,
+                          -8.13155 76.594 74.5,
+                          -11.5 84.7256 74.5,
+                          -4.76314 81.9756 74.5,
+                          -8.13155 92.8571 74.5,
+                          -8.13155 76.594 74.5,
+                          -8.13155 76.594 68,
+                          4.19707e-13 73.2256 68,
+                          -8.13155 76.594 74.5,
+                          -11.5 84.7256 68,
+                          -11.5 84.7256 74.5,
+                          -8.13155 92.8571 74.5,
+                          -8.13155 76.594 68,
+                          -11.5 84.7256 74.5,
+                          -11.5 84.7256 68,
+                          4.20748e-13 90.2256 74.5,
+                          4.21115e-13 96.2256 74.5,
+                          -8.13155 92.8571 74.5,
+                          -8.13155 92.8571 68,
+                          -8.13155 92.8571 74.5,
+                          4.21115e-13 96.2256 74.5,
+                          -4.76314 87.4756 74.5,
+                          4.20748e-13 90.2256 74.5,
+                          -8.13155 92.8571 74.5,
+                          -4.76314 81.9756 74.5,
+                          -4.76314 87.4756 74.5,
+                          -8.13155 92.8571 74.5,
+                          -11.5 84.7256 68,
+                          -8.13155 92.8571 74.5,
+                          -8.13155 92.8571 68,
+                          4.76314 87.4756 74.5,
+                          8.13155 92.8571 74.5,
+                          4.21115e-13 96.2256 74.5,
+                          4.21115e-13 96.2256 68,
+                          4.21115e-13 96.2256 74.5,
+                          8.13155 92.8571 74.5,
+                          4.20748e-13 90.2256 74.5,
+                          4.76314 87.4756 74.5,
+                          4.21115e-13 96.2256 74.5,
+                          -8.13155 92.8571 68,
+                          4.21115e-13 96.2256 74.5,
+                          4.21115e-13 96.2256 68,
+                          8.13155 76.594 74.5,
+                          11.5 84.7256 74.5,
+                          8.13155 92.8571 74.5,
+                          8.13155 92.8571 68,
+                          8.13155 92.8571 74.5,
+                          11.5 84.7256 74.5,
+                          4.76314 87.4756 74.5,
+                          8.13155 76.594 74.5,
+                          8.13155 92.8571 74.5,
+                          4.21115e-13 96.2256 68,
+                          8.13155 92.8571 74.5,
+                          8.13155 92.8571 68,
+                          11.5 84.7256 68,
+                          11.5 84.7256 74.5,
+                          8.13155 76.594 74.5,
+                          8.13155 92.8571 68,
+                          11.5 84.7256 74.5,
+                          11.5 84.7256 68,
+                          4.76314 81.9756 74.5,
+                          4.20074e-13 79.2256 74.5,
+                          8.13155 76.594 74.5,
+                          4.76314 87.4756 74.5,
+                          4.76314 81.9756 74.5,
+                          8.13155 76.594 74.5,
+                          11.5 84.7256 68,
+                          8.13155 76.594 74.5,
+                          8.13155 76.594 68,
+                          -5.19573 81.7252 58,
+                          -4.33013 82.2256 58,
+                          4.20105e-13 79.7256 58,
+                          4.20105e-13 79.7256 31,
+                          4.20105e-13 79.7256 58,
+                          -4.33013 82.2256 58,
+                          4.20044e-13 78.7256 58,
+                          4.20105e-13 79.7256 58,
+                          4.33013 82.2256 58,
+                          4.33013 82.2256 31,
+                          4.33013 82.2256 58,
+                          4.20105e-13 79.7256 58,
+                          -5.19573 81.7252 58,
+                          4.20105e-13 79.7256 58,
+                          4.20044e-13 78.7256 58,
+                          4.33013 82.2256 31,
+                          4.20105e-13 79.7256 58,
+                          4.20105e-13 79.7256 31,
+                          -5.19573 81.7252 58,
+                          -4.33013 87.2256 58,
+                          -4.33013 82.2256 58,
+                          -4.33013 82.2256 31,
+                          -4.33013 82.2256 58,
+                          -4.33013 87.2256 58,
+                          -4.33013 82.2256 31,
+                          4.20105e-13 79.7256 31,
+                          -4.33013 82.2256 58,
+                          4.20779e-13 90.7256 58,
+                          4.20717e-13 89.7256 58,
+                          -4.33013 87.2256 58,
+                          -4.33013 87.2256 31,
+                          -4.33013 87.2256 58,
+                          4.20717e-13 89.7256 58,
+                          -5.19573 87.726 58,
+                          4.20779e-13 90.7256 58,
+                          -4.33013 87.2256 58,
+                          -5.19573 81.7252 58,
+                          -5.19573 87.726 58,
+                          -4.33013 87.2256 58,
+                          -4.33013 82.2256 31,
+                          -4.33013 87.2256 58,
+                          -4.33013 87.2256 31,
+                          5.19573 87.726 58,
+                          4.33013 87.2256 58,
+                          4.20717e-13 89.7256 58,
+                          4.20717e-13 89.7256 31,
+                          4.20717e-13 89.7256 58,
+                          4.33013 87.2256 58,
+                          4.20779e-13 90.7256 58,
+                          5.19573 87.726 58,
+                          4.20717e-13 89.7256 58,
+                          -4.33013 87.2256 31,
+                          4.20717e-13 89.7256 58,
+                          4.20717e-13 89.7256 31,
+                          5.19573 87.726 58,
+                          4.33013 82.2256 58,
+                          4.33013 87.2256 58,
+                          4.33013 87.2256 31,
+                          4.33013 87.2256 58,
+                          4.33013 82.2256 58,
+                          4.20717e-13 89.7256 31,
+                          4.33013 87.2256 58,
+                          4.33013 87.2256 31,
+                          5.19573 81.7252 58,
+                          4.20044e-13 78.7256 58,
+                          4.33013 82.2256 58,
+                          5.19573 87.726 58,
+                          5.19573 81.7252 58,
+                          4.33013 82.2256 58,
+                          4.33013 87.2256 31,
+                          4.33013 82.2256 58,
+                          4.33013 82.2256 31,
+                          4.20044e-13 78.7256 67,
+                          4.20044e-13 78.7256 58,
+                          5.19573 81.7252 58,
+                          -5.19573 81.7252 67,
+                          -5.19573 81.7252 58,
+                          4.20044e-13 78.7256 58,
+                          -5.19573 81.7252 67,
+                          4.20044e-13 78.7256 58,
+                          4.20044e-13 78.7256 67,
+                          5.19573 81.7252 67,
+                          5.19573 81.7252 58,
+                          5.19573 87.726 58,
+                          5.19573 81.7252 67,
+                          4.20044e-13 78.7256 67,
+                          5.19573 81.7252 58,
+                          5.19573 87.726 67,
+                          5.19573 87.726 58,
+                          4.20779e-13 90.7256 58,
+                          5.19573 81.7252 67,
+                          5.19573 87.726 58,
+                          5.19573 87.726 67,
+                          4.20779e-13 90.7256 67,
+                          4.20779e-13 90.7256 58,
+                          -5.19573 87.726 58,
+                          5.19573 87.726 67,
+                          4.20779e-13 90.7256 58,
+                          4.20779e-13 90.7256 67,
+                          -5.19573 87.726 67,
+                          -5.19573 87.726 58,
+                          -5.19573 81.7252 58,
+                          4.20779e-13 90.7256 67,
+                          -5.19573 87.726 58,
+                          -5.19573 87.726 67,
+                          -5.19573 87.726 67,
+                          -5.19573 81.7252 58,
+                          -5.19573 81.7252 67,
+                          -4.33013 82.2256 31,
+                          -3.46422 82.7262 31,
+                          4.20166e-13 80.7256 31,
+                          4.20166e-13 80.7256 24,
+                          4.20166e-13 80.7256 31,
+                          -3.46422 82.7262 31,
+                          4.20105e-13 79.7256 31,
+                          4.20166e-13 80.7256 31,
+                          3.46422 82.7262 31,
+                          3.46422 82.7262 24,
+                          3.46422 82.7262 31,
+                          4.20166e-13 80.7256 31,
+                          -4.33013 82.2256 31,
+                          4.20166e-13 80.7256 31,
+                          4.20105e-13 79.7256 31,
+                          3.46422 82.7262 24,
+                          4.20166e-13 80.7256 31,
+                          4.20166e-13 80.7256 24,
+                          -4.33013 82.2256 31,
+                          -3.46422 86.725 31,
+                          -3.46422 82.7262 31,
+                          -3.46422 82.7262 24,
+                          -3.46422 82.7262 31,
+                          -3.46422 86.725 31,
+                          -3.46422 82.7262 24,
+                          4.20166e-13 80.7256 24,
+                          -3.46422 82.7262 31,
+                          4.20717e-13 89.7256 31,
+                          4.20656e-13 88.7256 31,
+                          -3.46422 86.725 31,
+                          -3.46422 86.725 24,
+                          -3.46422 86.725 31,
+                          4.20656e-13 88.7256 31,
+                          -4.33013 87.2256 31,
+                          4.20717e-13 89.7256 31,
+                          -3.46422 86.725 31,
+                          -4.33013 82.2256 31,
+                          -4.33013 87.2256 31,
+                          -3.46422 86.725 31,
+                          -3.46422 82.7262 24,
+                          -3.46422 86.725 31,
+                          -3.46422 86.725 24,
+                          4.33013 87.2256 31,
+                          3.46422 86.725 31,
+                          4.20656e-13 88.7256 31,
+                          4.20656e-13 88.7256 24,
+                          4.20656e-13 88.7256 31,
+                          3.46422 86.725 31,
+                          4.20717e-13 89.7256 31,
+                          4.33013 87.2256 31,
+                          4.20656e-13 88.7256 31,
+                          -3.46422 86.725 24,
+                          4.20656e-13 88.7256 31,
+                          4.20656e-13 88.7256 24,
+                          4.33013 87.2256 31,
+                          3.46422 82.7262 31,
+                          3.46422 86.725 31,
+                          3.46422 86.725 24,
+                          3.46422 86.725 31,
+                          3.46422 82.7262 31,
+                          4.20656e-13 88.7256 24,
+                          3.46422 86.725 31,
+                          3.46422 86.725 24,
+                          4.33013 82.2256 31,
+                          4.20105e-13 79.7256 31,
+                          3.46422 82.7262 31,
+                          4.33013 87.2256 31,
+                          4.33013 82.2256 31,
+                          3.46422 82.7262 31,
+                          3.46422 86.725 24,
+                          3.46422 82.7262 31,
+                          3.46422 82.7262 24,
+                          -3.46422 82.7262 24,
+                          -2.59765 83.2252 24,
+                          4.20228e-13 81.7256 24,
+                          4.20228e-13 81.7256 15,
+                          4.20228e-13 81.7256 24,
+                          -2.59765 83.2252 24,
+                          4.20166e-13 80.7256 24,
+                          4.20228e-13 81.7256 24,
+                          2.59765 83.2252 24,
+                          2.59765 83.2252 15,
+                          2.59765 83.2252 24,
+                          4.20228e-13 81.7256 24,
+                          -3.46422 82.7262 24,
+                          4.20228e-13 81.7256 24,
+                          4.20166e-13 80.7256 24,
+                          2.59765 83.2252 15,
+                          4.20228e-13 81.7256 24,
+                          4.20228e-13 81.7256 15,
+                          -3.46422 82.7262 24,
+                          -2.59765 86.2259 24,
+                          -2.59765 83.2252 24,
+                          -2.59765 83.2252 15,
+                          -2.59765 83.2252 24,
+                          -2.59765 86.2259 24,
+                          -2.59765 83.2252 15,
+                          4.20228e-13 81.7256 15,
+                          -2.59765 83.2252 24,
+                          4.20656e-13 88.7256 24,
+                          4.20595e-13 87.7256 24,
+                          -2.59765 86.2259 24,
+                          -2.59765 86.2259 15,
+                          -2.59765 86.2259 24,
+                          4.20595e-13 87.7256 24,
+                          -3.46422 86.725 24,
+                          4.20656e-13 88.7256 24,
+                          -2.59765 86.2259 24,
+                          -3.46422 82.7262 24,
+                          -3.46422 86.725 24,
+                          -2.59765 86.2259 24,
+                          -2.59765 83.2252 15,
+                          -2.59765 86.2259 24,
+                          -2.59765 86.2259 15,
+                          3.46422 86.725 24,
+                          2.59765 86.2259 24,
+                          4.20595e-13 87.7256 24,
+                          4.20595e-13 87.7256 15,
+                          4.20595e-13 87.7256 24,
+                          2.59765 86.2259 24,
+                          4.20656e-13 88.7256 24,
+                          3.46422 86.725 24,
+                          4.20595e-13 87.7256 24,
+                          -2.59765 86.2259 15,
+                          4.20595e-13 87.7256 24,
+                          4.20595e-13 87.7256 15,
+                          3.46422 86.725 24,
+                          2.59765 83.2252 24,
+                          2.59765 86.2259 24,
+                          2.59765 86.2259 15,
+                          2.59765 86.2259 24,
+                          2.59765 83.2252 24,
+                          4.20595e-13 87.7256 15,
+                          2.59765 86.2259 24,
+                          2.59765 86.2259 15,
+                          3.46422 82.7262 24,
+                          4.20166e-13 80.7256 24,
+                          2.59765 83.2252 24,
+                          3.46422 86.725 24,
+                          3.46422 82.7262 24,
+                          2.59765 83.2252 24,
+                          2.59765 86.2259 15,
+                          2.59765 83.2252 24,
+                          2.59765 83.2252 15,
+                          2.59765 86.2259 15,
+                          2.59765 83.2252 15,
+                          4.20228e-13 81.7256 15,
+                          4.20595e-13 87.7256 15,
+                          2.59765 86.2259 15,
+                          4.20228e-13 81.7256 15,
+                          -2.59765 83.2252 15,
+                          4.20595e-13 87.7256 15,
+                          4.20228e-13 81.7256 15,
+                          -2.59765 83.2252 15,
+                          -2.59765 86.2259 15,
+                          4.20595e-13 87.7256 15,
+                          -5.65621 79.0683 67,
+                          -5.19573 81.7252 67,
+                          4.20044e-13 78.7256 67,
+                          4.19921e-13 76.7256 67,
+                          4.20044e-13 78.7256 67,
+                          5.19573 81.7252 67,
+                          -5.65621 79.0683 67,
+                          4.20044e-13 78.7256 67,
+                          4.19921e-13 76.7256 67,
+                          -5.65621 79.0683 67,
+                          -5.19573 87.726 67,
+                          -5.19573 81.7252 67,
+                          4.20901e-13 92.7256 67,
+                          4.20779e-13 90.7256 67,
+                          -5.19573 87.726 67,
+                          -5.65621 90.3829 67,
+                          4.20901e-13 92.7256 67,
+                          -5.19573 87.726 67,
+                          -5.65621 79.0683 67,
+                          -5.65621 90.3829 67,
+                          -5.19573 87.726 67,
+                          5.65621 90.3829 67,
+                          5.19573 87.726 67,
+                          4.20779e-13 90.7256 67,
+                          4.20901e-13 92.7256 67,
+                          5.65621 90.3829 67,
+                          4.20779e-13 90.7256 67,
+                          5.65621 90.3829 67,
+                          5.19573 81.7252 67,
+                          5.19573 87.726 67,
+                          5.65621 79.0683 67,
+                          4.19921e-13 76.7256 67,
+                          5.19573 81.7252 67,
+                          5.65621 90.3829 67,
+                          5.65621 79.0683 67,
+                          5.19573 81.7252 67,
+                          4.19921e-13 76.7256 68,
+                          4.19921e-13 76.7256 67,
+                          5.65621 79.0683 67,
+                          -5.65621 79.0683 68,
+                          -5.65621 79.0683 67,
+                          4.19921e-13 76.7256 67,
+                          -5.65621 79.0683 68,
+                          4.19921e-13 76.7256 67,
+                          4.19921e-13 76.7256 68,
+                          5.65621 90.3829 67,
+                          7.99978 84.7256 67,
+                          5.65621 79.0683 67,
+                          5.65621 79.0683 68,
+                          5.65621 79.0683 67,
+                          7.99978 84.7256 67,
+                          5.65621 79.0683 68,
+                          4.19921e-13 76.7256 68,
+                          5.65621 79.0683 67,
+                          7.99978 84.7256 68,
+                          7.99978 84.7256 67,
+                          5.65621 90.3829 67,
+                          5.65621 79.0683 68,
+                          7.99978 84.7256 67,
+                          7.99978 84.7256 68,
+                          5.65621 90.3829 68,
+                          5.65621 90.3829 67,
+                          4.20901e-13 92.7256 67,
+                          7.99978 84.7256 68,
+                          5.65621 90.3829 67,
+                          5.65621 90.3829 68,
+                          4.20901e-13 92.7256 68,
+                          4.20901e-13 92.7256 67,
+                          -5.65621 90.3829 67,
+                          5.65621 90.3829 68,
+                          4.20901e-13 92.7256 67,
+                          4.20901e-13 92.7256 68,
+                          -5.65621 79.0683 67,
+                          -7.99978 84.7256 67,
+                          -5.65621 90.3829 67,
+                          -5.65621 90.3829 68,
+                          -5.65621 90.3829 67,
+                          -7.99978 84.7256 67,
+                          4.20901e-13 92.7256 68,
+                          -5.65621 90.3829 67,
+                          -5.65621 90.3829 68,
+                          -7.99978 84.7256 68,
+                          -7.99978 84.7256 67,
+                          -5.65621 79.0683 67,
+                          -5.65621 90.3829 68,
+                          -7.99978 84.7256 67,
+                          -7.99978 84.7256 68,
+                          -7.99978 84.7256 68,
+                          -5.65621 79.0683 67,
+                          -5.65621 79.0683 68,
+                          -8.13155 76.594 68,
+                          -5.65621 79.0683 68,
+                          4.19921e-13 76.7256 68,
+                          4.19707e-13 73.2256 68,
+                          4.19921e-13 76.7256 68,
+                          5.65621 79.0683 68,
+                          -8.13155 76.594 68,
+                          4.19921e-13 76.7256 68,
+                          4.19707e-13 73.2256 68,
+                          -8.13155 76.594 68,
+                          -7.99978 84.7256 68,
+                          -5.65621 79.0683 68,
+                          -8.13155 92.8571 68,
+                          -5.65621 90.3829 68,
+                          -7.99978 84.7256 68,
+                          -8.13155 76.594 68,
+                          -8.13155 92.8571 68,
+                          -7.99978 84.7256 68,
+                          4.21115e-13 96.2256 68,
+                          4.20901e-13 92.7256 68,
+                          -5.65621 90.3829 68,
+                          -8.13155 92.8571 68,
+                          4.21115e-13 96.2256 68,
+                          -5.65621 90.3829 68,
+                          8.13155 92.8571 68,
+                          5.65621 90.3829 68,
+                          4.20901e-13 92.7256 68,
+                          4.21115e-13 96.2256 68,
+                          8.13155 92.8571 68,
+                          4.20901e-13 92.7256 68,
+                          8.13155 92.8571 68,
+                          7.99978 84.7256 68,
+                          5.65621 90.3829 68,
+                          8.13155 76.594 68,
+                          5.65621 79.0683 68,
+                          7.99978 84.7256 68,
+                          8.13155 92.8571 68,
+                          8.13155 76.594 68,
+                          7.99978 84.7256 68,
+                          8.13155 76.594 68,
+                          4.19707e-13 73.2256 68,
+                          5.65621 79.0683 68,
+                          8.13155 92.8571 68,
+                          11.5 84.7256 68,
+                          8.13155 76.594 68,
+                          -8.13155 76.594 68,
+                          -11.5 84.7256 68,
+                          -8.13155 92.8571 68 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          6.12303e-17 -1 0,
+                          6.12303e-17 -1 0,
+                          -0.587785 -0.809017 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.587785 -0.809017 0,
+                          0.587785 -0.809017 0,
+                          6.12303e-17 -1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.587785 -0.809017 0,
+                          6.12303e-17 -1 0,
+                          6.12303e-17 -1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.587785 -0.809017 0,
+                          -0.587785 -0.809017 0,
+                          -0.951057 -0.309017 0,
+                          -0.587785 -0.809017 0,
+                          6.12303e-17 -1 0,
+                          -0.587785 -0.809017 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.951057 -0.309017 0,
+                          -0.951057 -0.309017 0,
+                          -0.951057 0.309017 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.587785 -0.809017 0,
+                          -0.951057 -0.309017 0,
+                          -0.951057 -0.309017 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.951057 0.309017 0,
+                          -0.951057 0.309017 0,
+                          -0.587785 0.809017 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.951057 -0.309017 0,
+                          -0.951057 0.309017 0,
+                          -0.951057 0.309017 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.587785 0.809017 0,
+                          -0.587785 0.809017 0,
+                          -1.83691e-16 1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.951057 0.309017 0,
+                          -0.587785 0.809017 0,
+                          -0.587785 0.809017 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.587785 0.809017 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.587785 0.809017 0,
+                          -1.83691e-16 1 0,
+                          -1.83691e-16 1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.587785 0.809017 0,
+                          0.587785 0.809017 0,
+                          0.951057 0.309017 0,
+                          6.12303e-17 1 0,
+                          0.587785 0.809017 0,
+                          0.587785 0.809017 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.951057 0.309017 0,
+                          0.951057 0.309017 0,
+                          0.951057 -0.309017 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.587785 0.809017 0,
+                          0.951057 0.309017 0,
+                          0.951057 0.309017 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.951057 -0.309017 0,
+                          0.951057 -0.309017 0,
+                          0.587785 -0.809017 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.951057 0.309017 0,
+                          0.951057 -0.309017 0,
+                          0.951057 -0.309017 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.951057 -0.309017 0,
+                          0.587785 -0.809017 0,
+                          0.587785 -0.809017 0,
+                          -1 -1.83691e-16 0,
+                          -1 -1.83691e-16 0,
+                          -0.86603 -0.499993 0,
+                          -0.866025 0.5 0,
+                          -0.86603 0.499993 0,
+                          -1 -6.12303e-17 0,
+                          -0.866025 0.5 0,
+                          -1 -6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.866025 -0.5 0,
+                          -0.86603 -0.499993 0,
+                          -0.500006 -0.866022 0,
+                          -0.866025 -0.5 0,
+                          -1 -1.83691e-16 0,
+                          -0.86603 -0.499993 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.5 -0.866025 0,
+                          -0.500006 -0.866022 0,
+                          1.22461e-16 -1 0,
+                          -0.866025 -0.5 0,
+                          -0.500006 -0.866022 0,
+                          -0.5 -0.866025 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          0.500006 -0.866022 0,
+                          -0.5 -0.866025 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          0.866025 -0.5 0,
+                          0.500006 -0.866022 0,
+                          0.86603 -0.499993 0,
+                          0.5 -0.866025 0,
+                          0.500006 -0.866022 0,
+                          0.866025 -0.5 0,
+                          1.22461e-16 -1 0,
+                          0.500006 -0.866022 0,
+                          0.5 -0.866025 0,
+                          0.866025 -0.5 0,
+                          0.86603 -0.499993 0,
+                          1 6.12303e-17 0,
+                          1 6.12303e-17 0,
+                          1 6.12303e-17 0,
+                          0.86603 0.499993 0,
+                          0.866025 -0.5 0,
+                          1 6.12303e-17 0,
+                          1 6.12303e-17 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.866025 0.5 0,
+                          0.86603 0.499993 0,
+                          0.500006 0.866022 0,
+                          1 6.12303e-17 0,
+                          0.86603 0.499993 0,
+                          0.866025 0.5 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.5 0.866025 0,
+                          0.500006 0.866022 0,
+                          -2.22045e-16 1 0,
+                          0.866025 0.5 0,
+                          0.500006 0.866022 0,
+                          0.5 0.866025 0,
+                          0 1 0,
+                          -2.22045e-16 1 0,
+                          -0.500006 0.866022 0,
+                          0.5 0.866025 0,
+                          -2.22045e-16 1 0,
+                          0 1 0,
+                          -0.866025 0.5 0,
+                          -0.500006 0.866022 0,
+                          -0.86603 0.499993 0,
+                          -0.5 0.866025 0,
+                          -0.500006 0.866022 0,
+                          -0.866025 0.5 0,
+                          0 1 0,
+                          -0.500006 0.866022 0,
+                          -0.5 0.866025 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          6.12303e-17 -1 0,
+                          6.12303e-17 -1 0,
+                          -0.707107 -0.707107 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.707107 -0.707107 0,
+                          0.707107 -0.707107 0,
+                          6.12303e-17 -1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.707107 -0.707107 0,
+                          6.12303e-17 -1 0,
+                          6.12303e-17 -1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          -1 -1.22461e-16 0,
+                          -0.707107 -0.707107 0,
+                          6.12303e-17 -1 0,
+                          -0.707107 -0.707107 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -0.707107 0.707107 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.707107 -0.707107 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.707107 0.707107 0,
+                          -0.707107 0.707107 0,
+                          -1.83691e-16 1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -1 -1.22461e-16 0,
+                          -0.707107 0.707107 0,
+                          -0.707107 0.707107 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.707107 0.707107 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.707107 0.707107 0,
+                          -1.83691e-16 1 0,
+                          -1.83691e-16 1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.707107 0.707107 0,
+                          0.707107 0.707107 0,
+                          1 0 0,
+                          6.12303e-17 1 0,
+                          0.707107 0.707107 0,
+                          0.707107 0.707107 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1 0 0,
+                          1 0 0,
+                          0.707107 -0.707107 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.707107 0.707107 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1 0 0,
+                          0.707107 -0.707107 0,
+                          0.707107 -0.707107 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,
+                          -6.12303e-17 1 0,
+                          -6.12303e-17 1 0,
+                          0.587785 0.809017 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.587785 0.809017 0,
+                          -0.587785 0.809017 0,
+                          -6.12303e-17 1 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.587785 0.809017 0,
+                          -6.12303e-17 1 0,
+                          -6.12303e-17 1 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.587785 0.809017 0,
+                          0.587785 0.809017 0,
+                          0.951057 0.309017 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.587785 0.809017 0,
+                          -6.12303e-17 1 0,
+                          0.587785 0.809017 0,
+                          0.951057 0.309017 0,
+                          0.951057 0.309017 0,
+                          0.951057 -0.309017 0,
+                          0.587785 0.809017 0,
+                          0.951057 0.309017 0,
+                          0.951057 0.309017 0,
+                          0.951057 -0.309017 0,
+                          0.951057 -0.309017 0,
+                          0.587785 -0.809017 0,
+                          0.951057 0.309017 0,
+                          0.951057 -0.309017 0,
+                          0.951057 -0.309017 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.587785 -0.809017 0,
+                          0.587785 -0.809017 0,
+                          1.83691e-16 -1 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.951057 -0.309017 0,
+                          0.587785 -0.809017 0,
+                          0.587785 -0.809017 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -0.587785 -0.809017 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.587785 -0.809017 0,
+                          1.83691e-16 -1 0,
+                          1.83691e-16 -1 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.587785 -0.809017 0,
+                          -0.587785 -0.809017 0,
+                          -0.951057 -0.309017 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,
+                          -6.12303e-17 -1 0,
+                          -0.587785 -0.809017 0,
+                          -0.587785 -0.809017 0,
+                          -0.951057 -0.309017 0,
+                          -0.951057 -0.309017 0,
+                          -0.951057 0.309017 0,
+                          -0.587785 -0.809017 0,
+                          -0.951057 -0.309017 0,
+                          -0.951057 -0.309017 0,
+                          -0.951057 0.309017 0,
+                          -0.951057 0.309017 0,
+                          -0.587785 0.809017 0,
+                          -0.951057 -0.309017 0,
+                          -0.951057 0.309017 0,
+                          -0.951057 0.309017 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.951057 0.309017 0,
+                          -0.587785 0.809017 0,
+                          -0.587785 0.809017 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          0.866025 -0.5 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.866025 0.5 0,
+                          0.866025 0.5 0,
+                          1 1.83691e-16 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.866025 0.5 0,
+                          1 1.83691e-16 0,
+                          1 1.83691e-16 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.866025 -0.5 0,
+                          0.866025 -0.5 0,
+                          0.5 -0.866025 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.866025 -0.5 0,
+                          1 -6.12303e-17 0,
+                          0.866025 -0.5 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          0 -1 0,
+                          0.866025 -0.5 0,
+                          0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -0.866025 -0.5 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 -1 0,
+                          -0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.866025 -0.5 0,
+                          -0.866025 -0.5 0,
+                          -1 -6.12303e-17 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.5 -0.866025 0,
+                          -0.866025 -0.5 0,
+                          -0.866025 -0.5 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -1 -6.12303e-17 0,
+                          -1 -6.12303e-17 0,
+                          -0.866025 0.5 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.866025 -0.5 0,
+                          -1 -6.12303e-17 0,
+                          -1 -6.12303e-17 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.866025 0.5 0,
+                          -0.866025 0.5 0,
+                          -0.5 0.866025 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,
+                          -1 -6.12303e-17 0,
+                          -0.866025 0.5 0,
+                          -0.866025 0.5 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          -1.22461e-16 1 0,
+                          -0.866025 0.5 0,
+                          -0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          0.866025 0.5 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -1.22461e-16 1 0,
+                          0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.5 0.866025 0,
+                          0.866025 0.5 0,
+                          0.866025 0.5 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 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 21.6502 97.2262 98,
+                          9.11048 97.2654 98,
+                          3.95603e-13 100.226 98,
+                          3.95603e-13 100.226 105,
+                          3.95603e-13 100.226 98,
+                          9.11048 97.2654 98,
+                          -12.4994 106.376 98,
+                          3.95603e-13 100.226 98,
+                          -9.11048 97.2654 98,
+                          -9.11048 97.2654 105,
+                          -9.11048 97.2654 98,
+                          3.95603e-13 100.226 98,
+                          -12.4994 106.376 98,
+                          21.6502 97.2262 98,
+                          3.95603e-13 100.226 98,
+                          -9.11048 97.2654 105,
+                          3.95603e-13 100.226 98,
+                          3.95603e-13 100.226 105,
+                          21.6502 97.2262 98,
+                          14.7415 89.515 98,
+                          9.11048 97.2654 98,
+                          9.11048 97.2654 105,
+                          9.11048 97.2654 98,
+                          14.7415 89.515 98,
+                          9.11048 97.2654 105,
+                          3.95603e-13 100.226 105,
+                          9.11048 97.2654 98,
+                          25 84.7256 98,
+                          14.7415 79.9362 98,
+                          14.7415 89.515 98,
+                          14.7415 89.515 105,
+                          14.7415 89.515 98,
+                          14.7415 79.9362 98,
+                          21.6502 97.2262 98,
+                          25 84.7256 98,
+                          14.7415 89.515 98,
+                          9.11048 97.2654 105,
+                          14.7415 89.515 98,
+                          14.7415 89.515 105,
+                          21.6502 72.225 98,
+                          9.11048 72.1858 98,
+                          14.7415 79.9362 98,
+                          14.7415 79.9362 105,
+                          14.7415 79.9362 98,
+                          9.11048 72.1858 98,
+                          21.6502 72.225 98,
+                          14.7415 79.9362 98,
+                          25 84.7256 98,
+                          14.7415 89.515 105,
+                          14.7415 79.9362 98,
+                          14.7415 79.9362 105,
+                          12.4994 63.0748 98,
+                          3.93705e-13 69.2256 98,
+                          9.11048 72.1858 98,
+                          9.11048 72.1858 105,
+                          9.11048 72.1858 98,
+                          3.93705e-13 69.2256 98,
+                          21.6502 72.225 98,
+                          12.4994 63.0748 98,
+                          9.11048 72.1858 98,
+                          14.7415 79.9362 105,
+                          9.11048 72.1858 98,
+                          9.11048 72.1858 105,
+                          -21.6502 72.225 98,
+                          -9.11048 72.1858 98,
+                          3.93705e-13 69.2256 98,
+                          3.93705e-13 69.2256 105,
+                          3.93705e-13 69.2256 98,
+                          -9.11048 72.1858 98,
+                          12.4994 63.0748 98,
+                          -21.6502 72.225 98,
+                          3.93705e-13 69.2256 98,
+                          9.11048 72.1858 105,
+                          3.93705e-13 69.2256 98,
+                          3.93705e-13 69.2256 105,
+                          -21.6502 72.225 98,
+                          -14.7415 79.9362 98,
+                          -9.11048 72.1858 98,
+                          -9.11048 72.1858 105,
+                          -9.11048 72.1858 98,
+                          -14.7415 79.9362 98,
+                          3.93705e-13 69.2256 105,
+                          -9.11048 72.1858 98,
+                          -9.11048 72.1858 105,
+                          -25 84.7256 98,
+                          -14.7415 89.515 98,
+                          -14.7415 79.9362 98,
+                          -14.7415 79.9362 105,
+                          -14.7415 79.9362 98,
+                          -14.7415 89.515 98,
+                          -21.6502 72.225 98,
+                          -25 84.7256 98,
+                          -14.7415 79.9362 98,
+                          -9.11048 72.1858 105,
+                          -14.7415 79.9362 98,
+                          -14.7415 79.9362 105,
+                          -21.6502 97.2262 98,
+                          -9.11048 97.2654 98,
+                          -14.7415 89.515 98,
+                          -14.7415 89.515 105,
+                          -14.7415 89.515 98,
+                          -9.11048 97.2654 98,
+                          -25 84.7256 98,
+                          -21.6502 97.2262 98,
+                          -14.7415 89.515 98,
+                          -14.7415 79.9362 105,
+                          -14.7415 89.515 98,
+                          -14.7415 89.515 105,
+                          -21.6502 97.2262 98,
+                          -12.4994 106.376 98,
+                          -9.11048 97.2654 98,
+                          -14.7415 89.515 105,
+                          -9.11048 97.2654 98,
+                          -9.11048 97.2654 105,
+                          25 84.7256 92,
+                          25 84.7256 98,
+                          21.6502 97.2262 98,
+                          21.65 72.2249 92,
+                          21.6502 72.225 98,
+                          25 84.7256 98,
+                          21.65 72.2249 92,
+                          25 84.7256 98,
+                          25 84.7256 92,
+                          -12.4994 106.376 98,
+                          12.4994 106.376 98,
+                          21.6502 97.2262 98,
+                          21.65 97.2263 92,
+                          21.6502 97.2262 98,
+                          12.4994 106.376 98,
+                          21.65 97.2263 92,
+                          25 84.7256 92,
+                          21.6502 97.2262 98,
+                          -12.4994 106.376 98,
+                          4.08508e-13 109.725 98,
+                          12.4994 106.376 98,
+                          12.5007 106.376 92,
+                          12.4994 106.376 98,
+                          4.08508e-13 109.725 98,
+                          21.65 97.2263 92,
+                          12.4994 106.376 98,
+                          12.5007 106.376 92,
+                          3.91593e-13 109.726 92,
+                          4.08508e-13 109.725 98,
+                          -12.4994 106.376 98,
+                          12.5007 106.376 92,
+                          4.08508e-13 109.725 98,
+                          3.91593e-13 109.726 92,
+                          -21.65 97.2263 92,
+                          -12.4994 106.376 98,
+                          -21.6502 97.2262 98,
+                          -12.5007 106.376 92,
+                          -12.4994 106.376 98,
+                          -21.65 97.2263 92,
+                          3.91593e-13 109.726 92,
+                          -12.4994 106.376 98,
+                          -12.5007 106.376 92,
+                          -21.65 97.2263 92,
+                          -21.6502 97.2262 98,
+                          -25 84.7256 98,
+                          -25 84.7256 92,
+                          -25 84.7256 98,
+                          -21.6502 72.225 98,
+                          -21.65 97.2263 92,
+                          -25 84.7256 98,
+                          -25 84.7256 92,
+                          12.4994 63.0748 98,
+                          -12.4994 63.0748 98,
+                          -21.6502 72.225 98,
+                          -21.65 72.2249 92,
+                          -21.6502 72.225 98,
+                          -12.4994 63.0748 98,
+                          -25 84.7256 92,
+                          -21.6502 72.225 98,
+                          -21.65 72.2249 92,
+                          12.4994 63.0748 98,
+                          4.00007e-13 59.7258 98,
+                          -12.4994 63.0748 98,
+                          -12.5007 63.0756 92,
+                          -12.4994 63.0748 98,
+                          4.00007e-13 59.7258 98,
+                          -21.65 72.2249 92,
+                          -12.4994 63.0748 98,
+                          -12.5007 63.0756 92,
+                          3.94654e-13 59.7256 92,
+                          4.00007e-13 59.7258 98,
+                          12.4994 63.0748 98,
+                          -12.5007 63.0756 92,
+                          4.00007e-13 59.7258 98,
+                          3.94654e-13 59.7256 92,
+                          21.65 72.2249 92,
+                          12.4994 63.0748 98,
+                          21.6502 72.225 98,
+                          12.5007 63.0756 92,
+                          12.4994 63.0748 98,
+                          21.65 72.2249 92,
+                          3.94654e-13 59.7256 92,
+                          12.4994 63.0748 98,
+                          12.5007 63.0756 92,
+                          9.11048 97.2654 105,
+                          5.65652 90.3827 105,
+                          3.95144e-13 92.7256 105,
+                          3.95144e-13 92.7256 107,
+                          3.95144e-13 92.7256 105,
+                          5.65652 90.3827 105,
+                          3.95603e-13 100.226 105,
+                          3.95144e-13 92.7256 105,
+                          -5.65652 90.3827 105,
+                          -5.65652 90.3827 107,
+                          -5.65652 90.3827 105,
+                          3.95144e-13 92.7256 105,
+                          9.11048 97.2654 105,
+                          3.95144e-13 92.7256 105,
+                          3.95603e-13 100.226 105,
+                          -5.65652 90.3827 107,
+                          3.95144e-13 92.7256 105,
+                          3.95144e-13 92.7256 107,
+                          9.11048 97.2654 105,
+                          7.99991 84.7256 105,
+                          5.65652 90.3827 105,
+                          5.65652 90.3827 107,
+                          5.65652 90.3827 105,
+                          7.99991 84.7256 105,
+                          5.65652 90.3827 107,
+                          3.95144e-13 92.7256 107,
+                          5.65652 90.3827 105,
+                          9.11048 72.1858 105,
+                          5.65652 79.0685 105,
+                          7.99991 84.7256 105,
+                          7.99991 84.7256 107,
+                          7.99991 84.7256 105,
+                          5.65652 79.0685 105,
+                          9.11048 97.2654 105,
+                          9.11048 72.1858 105,
+                          7.99991 84.7256 105,
+                          5.65652 90.3827 107,
+                          7.99991 84.7256 105,
+                          7.99991 84.7256 107,
+                          3.93705e-13 69.2256 105,
+                          3.94164e-13 76.7256 105,
+                          5.65652 79.0685 105,
+                          5.65652 79.0685 107,
+                          5.65652 79.0685 105,
+                          3.94164e-13 76.7256 105,
+                          9.11048 72.1858 105,
+                          3.93705e-13 69.2256 105,
+                          5.65652 79.0685 105,
+                          7.99991 84.7256 107,
+                          5.65652 79.0685 105,
+                          5.65652 79.0685 107,
+                          -9.11048 72.1858 105,
+                          -5.65652 79.0685 105,
+                          3.94164e-13 76.7256 105,
+                          3.94164e-13 76.7256 107,
+                          3.94164e-13 76.7256 105,
+                          -5.65652 79.0685 105,
+                          3.93705e-13 69.2256 105,
+                          -9.11048 72.1858 105,
+                          3.94164e-13 76.7256 105,
+                          5.65652 79.0685 107,
+                          3.94164e-13 76.7256 105,
+                          3.94164e-13 76.7256 107,
+                          -9.11048 72.1858 105,
+                          -7.99991 84.7256 105,
+                          -5.65652 79.0685 105,
+                          -5.65652 79.0685 107,
+                          -5.65652 79.0685 105,
+                          -7.99991 84.7256 105,
+                          3.94164e-13 76.7256 107,
+                          -5.65652 79.0685 105,
+                          -5.65652 79.0685 107,
+                          -9.11048 97.2654 105,
+                          -5.65652 90.3827 105,
+                          -7.99991 84.7256 105,
+                          -7.99991 84.7256 107,
+                          -7.99991 84.7256 105,
+                          -5.65652 90.3827 105,
+                          -9.11048 72.1858 105,
+                          -9.11048 97.2654 105,
+                          -7.99991 84.7256 105,
+                          -5.65652 79.0685 107,
+                          -7.99991 84.7256 105,
+                          -7.99991 84.7256 107,
+                          -9.11048 97.2654 105,
+                          3.95603e-13 100.226 105,
+                          -5.65652 90.3827 105,
+                          -7.99991 84.7256 107,
+                          -5.65652 90.3827 105,
+                          -5.65652 90.3827 107,
+                          -14.7415 79.9362 105,
+                          -14.7415 89.515 105,
+                          -9.11048 97.2654 105,
+                          -9.11048 72.1858 105,
+                          -14.7415 79.9362 105,
+                          -9.11048 97.2654 105,
+                          14.7415 89.515 105,
+                          14.7415 79.9362 105,
+                          9.11048 72.1858 105,
+                          9.11048 97.2654 105,
+                          14.7415 89.515 105,
+                          9.11048 72.1858 105,
+                          5.65652 90.3827 107,
+                          10.5804 99.2877 107,
+                          3.95756e-13 102.726 107,
+                          3.95756e-13 102.726 100,
+                          3.95756e-13 102.726 107,
+                          10.5804 99.2877 107,
+                          3.95144e-13 92.7256 107,
+                          3.95756e-13 102.726 107,
+                          -10.5804 99.2877 107,
+                          -10.5804 99.2877 100,
+                          -10.5804 99.2877 107,
+                          3.95756e-13 102.726 107,
+                          5.65652 90.3827 107,
+                          3.95756e-13 102.726 107,
+                          3.95144e-13 92.7256 107,
+                          -10.5804 99.2877 100,
+                          3.95756e-13 102.726 107,
+                          3.95756e-13 102.726 100,
+                          17.119 79.1635 107,
+                          17.119 90.2877 107,
+                          10.5804 99.2877 107,
+                          10.5804 99.2877 100,
+                          10.5804 99.2877 107,
+                          17.119 90.2877 107,
+                          10.5804 70.1635 107,
+                          17.119 79.1635 107,
+                          10.5804 99.2877 107,
+                          7.99991 84.7256 107,
+                          10.5804 70.1635 107,
+                          10.5804 99.2877 107,
+                          5.65652 90.3827 107,
+                          7.99991 84.7256 107,
+                          10.5804 99.2877 107,
+                          10.5804 99.2877 100,
+                          3.95756e-13 102.726 100,
+                          10.5804 99.2877 107,
+                          17.119 90.2877 100,
+                          17.119 90.2877 107,
+                          17.119 79.1635 107,
+                          10.5804 99.2877 100,
+                          17.119 90.2877 107,
+                          17.119 90.2877 100,
+                          17.119 79.1635 100,
+                          17.119 79.1635 107,
+                          10.5804 70.1635 107,
+                          17.119 90.2877 100,
+                          17.119 79.1635 107,
+                          17.119 79.1635 100,
+                          3.94164e-13 76.7256 107,
+                          3.93552e-13 66.7256 107,
+                          10.5804 70.1635 107,
+                          10.5804 70.1635 100,
+                          10.5804 70.1635 107,
+                          3.93552e-13 66.7256 107,
+                          5.65652 79.0685 107,
+                          3.94164e-13 76.7256 107,
+                          10.5804 70.1635 107,
+                          7.99991 84.7256 107,
+                          5.65652 79.0685 107,
+                          10.5804 70.1635 107,
+                          17.119 79.1635 100,
+                          10.5804 70.1635 107,
+                          10.5804 70.1635 100,
+                          -5.65652 79.0685 107,
+                          -10.5804 70.1635 107,
+                          3.93552e-13 66.7256 107,
+                          3.93552e-13 66.7256 100,
+                          3.93552e-13 66.7256 107,
+                          -10.5804 70.1635 107,
+                          3.94164e-13 76.7256 107,
+                          -5.65652 79.0685 107,
+                          3.93552e-13 66.7256 107,
+                          10.5804 70.1635 100,
+                          3.93552e-13 66.7256 107,
+                          3.93552e-13 66.7256 100,
+                          -17.119 90.2877 107,
+                          -17.119 79.1635 107,
+                          -10.5804 70.1635 107,
+                          -10.5804 70.1635 100,
+                          -10.5804 70.1635 107,
+                          -17.119 79.1635 107,
+                          -10.5804 99.2877 107,
+                          -17.119 90.2877 107,
+                          -10.5804 70.1635 107,
+                          -7.99991 84.7256 107,
+                          -10.5804 99.2877 107,
+                          -10.5804 70.1635 107,
+                          -5.65652 79.0685 107,
+                          -7.99991 84.7256 107,
+                          -10.5804 70.1635 107,
+                          3.93552e-13 66.7256 100,
+                          -10.5804 70.1635 107,
+                          -10.5804 70.1635 100,
+                          -17.119 79.1635 100,
+                          -17.119 79.1635 107,
+                          -17.119 90.2877 107,
+                          -10.5804 70.1635 100,
+                          -17.119 79.1635 107,
+                          -17.119 79.1635 100,
+                          -17.119 90.2877 100,
+                          -17.119 90.2877 107,
+                          -10.5804 99.2877 107,
+                          -17.119 79.1635 100,
+                          -17.119 90.2877 107,
+                          -17.119 90.2877 100,
+                          -5.65652 90.3827 107,
+                          3.95144e-13 92.7256 107,
+                          -10.5804 99.2877 107,
+                          -7.99991 84.7256 107,
+                          -5.65652 90.3827 107,
+                          -10.5804 99.2877 107,
+                          -17.119 90.2877 100,
+                          -10.5804 99.2877 107,
+                          -10.5804 99.2877 100,
+                          17.119 79.1635 100,
+                          23.3821 71.2247 100,
+                          27 84.7256 100,
+                          27 84.7256 92,
+                          27 84.7256 100,
+                          23.3821 71.2247 100,
+                          17.119 90.2877 100,
+                          27 84.7256 100,
+                          23.3821 98.2265 100,
+                          23.3821 98.2265 92,
+                          23.3821 98.2265 100,
+                          27 84.7256 100,
+                          17.119 90.2877 100,
+                          17.119 79.1635 100,
+                          27 84.7256 100,
+                          23.3821 98.2265 92,
+                          27 84.7256 100,
+                          27 84.7256 92,
+                          -13.4992 61.3426 100,
+                          13.4992 61.3426 100,
+                          23.3821 71.2247 100,
+                          23.3821 71.2247 92,
+                          23.3821 71.2247 100,
+                          13.4992 61.3426 100,
+                          3.93552e-13 66.7256 100,
+                          -13.4992 61.3426 100,
+                          23.3821 71.2247 100,
+                          10.5804 70.1635 100,
+                          3.93552e-13 66.7256 100,
+                          23.3821 71.2247 100,
+                          17.119 79.1635 100,
+                          10.5804 70.1635 100,
+                          23.3821 71.2247 100,
+                          23.3821 71.2247 92,
+                          27 84.7256 92,
+                          23.3821 71.2247 100,
+                          -13.4992 61.3426 100,
+                          3.94333e-13 57.7258 100,
+                          13.4992 61.3426 100,
+                          13.4992 61.3426 92,
+                          13.4992 61.3426 100,
+                          3.94333e-13 57.7258 100,
+                          23.3821 71.2247 92,
+                          13.4992 61.3426 100,
+                          13.4992 61.3426 92,
+                          3.94333e-13 57.7258 92,
+                          3.94333e-13 57.7258 100,
+                          -13.4992 61.3426 100,
+                          13.4992 61.3426 92,
+                          3.94333e-13 57.7258 100,
+                          3.94333e-13 57.7258 92,
+                          -10.5804 70.1635 100,
+                          -23.3821 71.2247 100,
+                          -13.4992 61.3426 100,
+                          -13.4992 61.3426 92,
+                          -13.4992 61.3426 100,
+                          -23.3821 71.2247 100,
+                          3.93552e-13 66.7256 100,
+                          -10.5804 70.1635 100,
+                          -13.4992 61.3426 100,
+                          3.94333e-13 57.7258 92,
+                          -13.4992 61.3426 100,
+                          -13.4992 61.3426 92,
+                          -17.119 79.1635 100,
+                          -27 84.7256 100,
+                          -23.3821 71.2247 100,
+                          -23.3821 71.2247 92,
+                          -23.3821 71.2247 100,
+                          -27 84.7256 100,
+                          -10.5804 70.1635 100,
+                          -17.119 79.1635 100,
+                          -23.3821 71.2247 100,
+                          -13.4992 61.3426 92,
+                          -23.3821 71.2247 100,
+                          -23.3821 71.2247 92,
+                          -17.119 90.2877 100,
+                          -23.3821 98.2265 100,
+                          -27 84.7256 100,
+                          -27 84.7256 92,
+                          -27 84.7256 100,
+                          -23.3821 98.2265 100,
+                          -17.119 79.1635 100,
+                          -17.119 90.2877 100,
+                          -27 84.7256 100,
+                          -23.3821 71.2247 92,
+                          -27 84.7256 100,
+                          -27 84.7256 92,
+                          13.4992 108.109 100,
+                          -13.4992 108.109 100,
+                          -23.3821 98.2265 100,
+                          -23.3821 98.2265 92,
+                          -23.3821 98.2265 100,
+                          -13.4992 108.109 100,
+                          3.95756e-13 102.726 100,
+                          13.4992 108.109 100,
+                          -23.3821 98.2265 100,
+                          -10.5804 99.2877 100,
+                          3.95756e-13 102.726 100,
+                          -23.3821 98.2265 100,
+                          -17.119 90.2877 100,
+                          -10.5804 99.2877 100,
+                          -23.3821 98.2265 100,
+                          -27 84.7256 92,
+                          -23.3821 98.2265 100,
+                          -23.3821 98.2265 92,
+                          13.4992 108.109 100,
+                          3.91311e-13 111.725 100,
+                          -13.4992 108.109 100,
+                          -13.4992 108.109 92,
+                          -13.4992 108.109 100,
+                          3.91311e-13 111.725 100,
+                          -23.3821 98.2265 92,
+                          -13.4992 108.109 100,
+                          -13.4992 108.109 92,
+                          3.91311e-13 111.725 92,
+                          3.91311e-13 111.725 100,
+                          13.4992 108.109 100,
+                          -13.4992 108.109 92,
+                          3.91311e-13 111.725 100,
+                          3.91311e-13 111.725 92,
+                          10.5804 99.2877 100,
+                          23.3821 98.2265 100,
+                          13.4992 108.109 100,
+                          13.4992 108.109 92,
+                          13.4992 108.109 100,
+                          23.3821 98.2265 100,
+                          10.5804 99.2877 100,
+                          13.4992 108.109 100,
+                          3.95756e-13 102.726 100,
+                          3.91311e-13 111.725 92,
+                          13.4992 108.109 100,
+                          13.4992 108.109 92,
+                          10.5804 99.2877 100,
+                          17.119 90.2877 100,
+                          23.3821 98.2265 100,
+                          13.4992 108.109 92,
+                          23.3821 98.2265 100,
+                          23.3821 98.2265 92,
+                          23.3821 71.2247 92,
+                          21.65 72.2249 92,
+                          25 84.7256 92,
+                          27 84.7256 92,
+                          25 84.7256 92,
+                          21.65 97.2263 92,
+                          23.3821 71.2247 92,
+                          25 84.7256 92,
+                          27 84.7256 92,
+                          23.3821 71.2247 92,
+                          12.5007 63.0756 92,
+                          21.65 72.2249 92,
+                          13.4992 61.3426 92,
+                          3.94654e-13 59.7256 92,
+                          12.5007 63.0756 92,
+                          23.3821 71.2247 92,
+                          13.4992 61.3426 92,
+                          12.5007 63.0756 92,
+                          -13.4992 61.3426 92,
+                          -12.5007 63.0756 92,
+                          3.94654e-13 59.7256 92,
+                          3.94333e-13 57.7258 92,
+                          -13.4992 61.3426 92,
+                          3.94654e-13 59.7256 92,
+                          13.4992 61.3426 92,
+                          3.94333e-13 57.7258 92,
+                          3.94654e-13 59.7256 92,
+                          -23.3821 71.2247 92,
+                          -21.65 72.2249 92,
+                          -12.5007 63.0756 92,
+                          -13.4992 61.3426 92,
+                          -23.3821 71.2247 92,
+                          -12.5007 63.0756 92,
+                          -27 84.7256 92,
+                          -25 84.7256 92,
+                          -21.65 72.2249 92,
+                          -23.3821 71.2247 92,
+                          -27 84.7256 92,
+                          -21.65 72.2249 92,
+                          -23.3821 98.2265 92,
+                          -21.65 97.2263 92,
+                          -25 84.7256 92,
+                          -27 84.7256 92,
+                          -23.3821 98.2265 92,
+                          -25 84.7256 92,
+                          -23.3821 98.2265 92,
+                          -12.5007 106.376 92,
+                          -21.65 97.2263 92,
+                          -13.4992 108.109 92,
+                          3.91593e-13 109.726 92,
+                          -12.5007 106.376 92,
+                          -23.3821 98.2265 92,
+                          -13.4992 108.109 92,
+                          -12.5007 106.376 92,
+                          13.4992 108.109 92,
+                          12.5007 106.376 92,
+                          3.91593e-13 109.726 92,
+                          3.91311e-13 111.725 92,
+                          13.4992 108.109 92,
+                          3.91593e-13 109.726 92,
+                          -13.4992 108.109 92,
+                          3.91311e-13 111.725 92,
+                          3.91593e-13 109.726 92,
+                          23.3821 98.2265 92,
+                          21.65 97.2263 92,
+                          12.5007 106.376 92,
+                          13.4992 108.109 92,
+                          23.3821 98.2265 92,
+                          12.5007 106.376 92,
+                          23.3821 98.2265 92,
+                          27 84.7256 92,
+                          21.65 97.2263 92 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.7 0.7 0.7
+    }
+    Separator {
+        Normal {
+            vector      [ 0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.707107 -1.29889e-16 -0.707107,
+                          0.707107 -1.29889e-16 -0.707107,
+                          0.353553 0.612372 -0.707107,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.353553 -0.612372 -0.707107,
+                          0.353553 -0.612372 -0.707107,
+                          0.707107 -1.29889e-16 -0.707107,
+                          0.353553 -0.612372 -0.707107,
+                          0.707107 -1.29889e-16 -0.707107,
+                          0.707107 -1.29889e-16 -0.707107,
+                          0.353553 0.612372 -0.707107,
+                          0.353553 0.612372 -0.707107,
+                          -0.353553 0.612372 -0.707107,
+                          0.353553 0.612372 -0.707107,
+                          0.707107 -1.29889e-16 -0.707107,
+                          0.353553 0.612372 -0.707107,
+                          -0.353553 0.612372 -0.707107,
+                          -0.353553 0.612372 -0.707107,
+                          -0.707107 2.16482e-16 -0.707107,
+                          0.353553 0.612372 -0.707107,
+                          -0.353553 0.612372 -0.707107,
+                          -0.353553 0.612372 -0.707107,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.353553 -0.612372 -0.707107,
+                          -0.353553 0.612372 -0.707107,
+                          -0.707107 2.16482e-16 -0.707107,
+                          -0.707107 1.47256e-15 -0.707107,
+                          -0.353553 -0.612372 -0.707107,
+                          -0.353553 -0.612372 -0.707107,
+                          0.353553 -0.612372 -0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.353553 -0.612372 -0.707107,
+                          -0.353553 -0.612372 -0.707107,
+                          -0.353553 -0.612372 -0.707107,
+                          0.353553 -0.612372 -0.707107,
+                          0.353553 -0.612372 -0.707107,
+                          -0.904633 -0.42619 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -0.5 0.866025 0,
+                          -1 3.06152e-16 0,
+                          -1 3.06152e-16 0,
+                          4.36909e-17 0.713551 -0.700604,
+                          0 -2.83275e-16 -1,
+                          0 6.04903e-16 -1,
+                          -4.36425e-17 -0.71276 -0.701408,
+                          0 6.04903e-16 -1,
+                          0 -2.83275e-16 -1,
+                          4.34926e-17 0.710311 -0.703888,
+                          0 -2.83275e-16 -1,
+                          4.36909e-17 0.713551 -0.700604,
+                          -0.903953 0.427632 0,
+                          -1 3.06152e-16 0,
+                          -0.5 0.866025 0,
+                          -0.8 -0.6 0,
+                          -0.5 -0.866025 0,
+                          -1 6.12303e-17 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -1.00049 86.4569 94,
+                          1.00049 86.4569 94,
+                          2 84.7256 94,
+                          2.5 84.7256 94.5,
+                          2 84.7256 94,
+                          1.00049 86.4569 94,
+                          -2 84.7256 94,
+                          -1.00049 86.4569 94,
+                          2 84.7256 94,
+                          1.00049 82.9942 94,
+                          -2 84.7256 94,
+                          2 84.7256 94,
+                          1.25 82.5605 94.5,
+                          1.00049 82.9942 94,
+                          2 84.7256 94,
+                          1.25 82.5605 94.5,
+                          2 84.7256 94,
+                          2.5 84.7256 94.5,
+                          1.25 86.8906 94.5,
+                          1.00049 86.4569 94,
+                          -1.00049 86.4569 94,
+                          1.25 86.8906 94.5,
+                          2.5 84.7256 94.5,
+                          1.00049 86.4569 94,
+                          -1.25 86.8906 94.5,
+                          -1.00049 86.4569 94,
+                          -2 84.7256 94,
+                          1.25 86.8906 94.5,
+                          -1.00049 86.4569 94,
+                          -1.25 86.8906 94.5,
+                          1.00049 82.9942 94,
+                          -1.00049 82.9942 94,
+                          -2 84.7256 94,
+                          -2.5 84.7256 94.5,
+                          -2 84.7256 94,
+                          -1.00049 82.9942 94,
+                          -1.25 86.8906 94.5,
+                          -2 84.7256 94,
+                          -2.5 84.7256 94.5,
+                          -1.25 82.5605 94.5,
+                          -1.00049 82.9942 94,
+                          1.00049 82.9942 94,
+                          -2.5 84.7256 94.5,
+                          -1.00049 82.9942 94,
+                          -1.25 82.5605 94.5,
+                          -1.25 82.5605 94.5,
+                          1.00049 82.9942 94,
+                          1.25 82.5605 94.5,
+                          -2.26158 83.6601 99.5557,
+                          -2.5 84.7256 104,
+                          -2.5 84.7256 100,
+                          -1.25 86.8906 104,
+                          -2.5 84.7256 100,
+                          -2.5 84.7256 104,
+                          2.25931 83.6553 99.5508,
+                          -2.5 84.7256 100,
+                          2.5 84.7256 100,
+                          -2.25988 85.7947 99.5519,
+                          2.5 84.7256 100,
+                          -2.5 84.7256 100,
+                          -2.26158 83.6601 99.5557,
+                          -2.5 84.7256 100,
+                          2.25931 83.6553 99.5508,
+                          -2.25988 85.7947 99.5519,
+                          -2.5 84.7256 100,
+                          -1.25 86.8906 104,
+                          -2 83.2256 98.5,
+                          -1.25 82.5605 104,
+                          -2.5 84.7256 104 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.83 0 0
+    }
+    Separator {
+        Normal {
+            vector      [ 0 0 -1,
+                          0 0 -1,
+                          0 0 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -4 84.7256 104,
+                          -2.5 84.7256 104,
+                          -1.25 82.5605 104 ]
+        }
+        FaceSet {
+            numVertices [ 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.7 0.7 0.7
+    }
+    Separator {
+        Normal {
+            vector      [ -0.904633 -0.42619 0,
+                          -0.8 -0.6 0,
+                          -1 6.12303e-17 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -2.26158 83.6601 99.5557,
+                          -2 83.2256 98.5,
+                          -2.5 84.7256 104 ]
+        }
+        FaceSet {
+            numVertices [ 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.83 0 0
+    }
+    Separator {
+        Normal {
+            vector      [ 0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -4 84.7256 104,
+                          -2.00048 88.1891 104,
+                          -2.5 84.7256 104,
+                          -1.25 86.8906 104,
+                          -2.5 84.7256 104,
+                          -2.00048 88.1891 104 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.7 0.7 0.7
+    }
+    Separator {
+        Normal {
+            vector      [ 0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          -0.5 -0.866025 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 1.25 82.5605 94.5,
+                          1.25 82.5605 104,
+                          -1.25 82.5605 104 ]
+        }
+        FaceSet {
+            numVertices [ 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.83 0 0
+    }
+    Separator {
+        Normal {
+            vector      [ 0 0 -1,
+                          0 0 -1,
+                          0 0 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 2.00048 81.2621 104,
+                          -1.25 82.5605 104,
+                          1.25 82.5605 104 ]
+        }
+        FaceSet {
+            numVertices [ 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.7 0.7 0.7
+    }
+    Separator {
+        Normal {
+            vector      [ -0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -0.8 -0.6 0,
+                          -0.5 -0.866025 0,
+                          -0.5 -0.866025 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -1.25 82.5605 94.5,
+                          1.25 82.5605 94.5,
+                          -1.25 82.5605 104,
+                          -2 83.2256 98.5,
+                          -1.25 82.5605 94.5,
+                          -1.25 82.5605 104 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.83 0 0
+    }
+    Separator {
+        Normal {
+            vector      [ 0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -2.00048 81.2621 104,
+                          -4 84.7256 104,
+                          -1.25 82.5605 104,
+                          2.00048 81.2621 104,
+                          -2.00048 81.2621 104,
+                          -1.25 82.5605 104 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.7 0.7 0.7
+    }
+    Separator {
+        Normal {
+            vector      [ 1 -1.83691e-16 0,
+                          1 -1.83691e-16 0,
+                          0.5 -0.866025 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 2.5 84.7256 100,
+                          2.5 84.7256 104,
+                          1.25 82.5605 104 ]
+        }
+        FaceSet {
+            numVertices [ 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.83 0 0
+    }
+    Separator {
+        Normal {
+            vector      [ 0 0 -1,
+                          0 0 -1,
+                          0 0 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 2.00048 81.2621 104,
+                          1.25 82.5605 104,
+                          2.5 84.7256 104 ]
+        }
+        FaceSet {
+            numVertices [ 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.7 0.7 0.7
+    }
+    Separator {
+        Normal {
+            vector      [ 0.903723 -0.428117 0,
+                          1 -1.83691e-16 0,
+                          0.5 -0.866025 0,
+                          0.8 -0.6 0,
+                          0.903723 -0.428117 0,
+                          0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          0.8 -0.6 0,
+                          0.5 -0.866025 0,
+                          0.904656 0.426143 0,
+                          1 -1.83691e-16 0,
+                          1 -1.83691e-16 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 2.25931 83.6553 99.5508,
+                          2.5 84.7256 100,
+                          1.25 82.5605 104,
+                          2 83.2256 98.5,
+                          2.25931 83.6553 99.5508,
+                          1.25 82.5605 104,
+                          1.25 82.5605 94.5,
+                          2 83.2256 98.5,
+                          1.25 82.5605 104,
+                          2.26164 85.7909 99.5558,
+                          2.5 84.7256 104,
+                          2.5 84.7256 100 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.83 0 0
+    }
+    Separator {
+        Normal {
+            vector      [ 0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 2.00048 81.2621 104,
+                          2.5 84.7256 104,
+                          4 84.7256 104,
+                          1.25 86.8906 104,
+                          4 84.7256 104,
+                          2.5 84.7256 104 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.7 0.7 0.7
+    }
+    Separator {
+        Normal {
+            vector      [ 0.8 0.6 0,
+                          0.5 0.866025 0,
+                          1 -1.83691e-16 0,
+                          0.8 0.6 0,
+                          1 -1.83691e-16 0,
+                          0.904656 0.426143 0,
+                          -4.36425e-17 -0.71276 -0.701408,
+                          -4.34889e-17 -0.710251 -0.703948,
+                          0 6.04903e-16 -1,
+                          4.34926e-17 0.710311 -0.703888,
+                          4.36909e-17 0.713551 -0.700604,
+                          6.12303e-17 1 -1.22461e-16,
+                          1 -1.83691e-16 0,
+                          0.904561 -0.426344 0,
+                          0.8 -0.6 0,
+                          6.12303e-17 1 -1.22461e-16,
+                          6.12303e-17 1 -1.22461e-16,
+                          4.35092e-17 0.710583 0.703613,
+                          0.5 -0.866025 0,
+                          1 -1.83691e-16 0,
+                          0.8 -0.6 0,
+                          4.34926e-17 0.710311 -0.703888,
+                          6.12303e-17 1 -1.22461e-16,
+                          6.12303e-17 1 -1.22461e-16,
+                          1 -1.83691e-16 0,
+                          1 -1.83691e-16 0,
+                          0.904561 -0.426344 0,
+                          4.36161e-17 0.712328 0.701847,
+                          4.35092e-17 0.710583 0.703613,
+                          0 1.83691e-16 1,
+                          6.12303e-17 1 -1.22461e-16,
+                          4.35092e-17 0.710583 0.703613,
+                          4.36161e-17 0.712328 0.701847,
+                          0.5 0.866025 0,
+                          1 -1.83691e-16 0,
+                          1 -1.83691e-16 0,
+                          4.36161e-17 0.712328 0.701847,
+                          0 1.83691e-16 1,
+                          0 1.83691e-16 1,
+                          -4.36875e-17 -0.713494 0.700661,
+                          0 1.83691e-16 1,
+                          0 1.83691e-16 1,
+                          0.5 0.866025 0,
+                          0.903739 0.428084 0,
+                          1 -1.83691e-16 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -0.5 -0.866025 0,
+                          -0.904076 -0.427372 0,
+                          -1 6.12303e-17 0,
+                          -0.5 -0.866025 0,
+                          -0.8 -0.6 0,
+                          -0.904076 -0.427372 0,
+                          -0.5 -0.866025 0,
+                          -0.90454 0.426389 0,
+                          -1 3.06152e-16 0,
+                          -1 3.06152e-16 0,
+                          -0.90454 0.426389 0,
+                          -0.8 0.6 0,
+                          -1 3.06152e-16 0,
+                          -0.5 0.866025 0,
+                          -1 3.06152e-16 0,
+                          -0.8 0.6 0,
+                          -4.36875e-17 -0.713494 0.700661,
+                          -4.35127e-17 -0.71064 0.703556,
+                          0 1.83691e-16 1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 2 86.2256 98.5,
+                          1.25 86.8906 104,
+                          2.5 84.7256 104,
+                          2 86.2256 98.5,
+                          2.5 84.7256 104,
+                          2.26164 85.7909 99.5558,
+                          -2.25988 85.7947 99.5519,
+                          2.26164 85.7909 99.5558,
+                          2.5 84.7256 100,
+                          -2.26158 83.6601 99.5557,
+                          2.25931 83.6553 99.5508,
+                          2 83.2256 98.5,
+                          2.5 84.7256 94.5,
+                          2.2614 83.6597 97.4447,
+                          2 83.2256 98.5,
+                          -2 83.2256 98.5,
+                          2 83.2256 98.5,
+                          2.2614 83.6597 97.4447,
+                          1.25 82.5605 94.5,
+                          2.5 84.7256 94.5,
+                          2 83.2256 98.5,
+                          -2.26158 83.6601 99.5557,
+                          2 83.2256 98.5,
+                          -2 83.2256 98.5,
+                          2.5 84.7256 94.5,
+                          2.5 84.7256 97,
+                          2.2614 83.6597 97.4447,
+                          -2.26019 83.6572 97.4474,
+                          2.2614 83.6597 97.4447,
+                          2.5 84.7256 97,
+                          -2 83.2256 98.5,
+                          2.2614 83.6597 97.4447,
+                          -2.26019 83.6572 97.4474,
+                          1.25 86.8906 94.5,
+                          2.5 84.7256 97,
+                          2.5 84.7256 94.5,
+                          -2.26019 83.6572 97.4474,
+                          2.5 84.7256 97,
+                          -2.5 84.7256 97,
+                          2.25935 85.7958 97.4491,
+                          -2.5 84.7256 97,
+                          2.5 84.7256 97,
+                          1.25 86.8906 94.5,
+                          2.25935 85.7958 97.4491,
+                          2.5 84.7256 97,
+                          -2.5 84.7256 97,
+                          -2.5 84.7256 94.5,
+                          -1.25 82.5605 94.5,
+                          -2.26019 83.6572 97.4474,
+                          -2.5 84.7256 97,
+                          -1.25 82.5605 94.5,
+                          -2 83.2256 98.5,
+                          -2.26019 83.6572 97.4474,
+                          -1.25 82.5605 94.5,
+                          -2.26135 85.7916 97.4448,
+                          -2.5 84.7256 94.5,
+                          -2.5 84.7256 97,
+                          -2.26135 85.7916 97.4448,
+                          -2 86.2256 98.5,
+                          -2.5 84.7256 94.5,
+                          -1.25 86.8906 94.5,
+                          -2.5 84.7256 94.5,
+                          -2 86.2256 98.5,
+                          2.25935 85.7958 97.4491,
+                          -2.26135 85.7916 97.4448,
+                          -2.5 84.7256 97 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.83 0 0
+    }
+    Separator {
+        Normal {
+            vector      [ 0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1 -1.83691e-16 0,
+                          1 -1.83691e-16 0,
+                          0.707107 0.707107 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.707107 -0.707107 0,
+                          0.707107 -0.707107 0,
+                          1 -1.83691e-16 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1 -1.83691e-16 0,
+                          0.707107 -0.707107 0,
+                          1 -1.83691e-16 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.707107 0.707107 0,
+                          0.707107 0.707107 0,
+                          2.44921e-16 1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.707107 0.707107 0,
+                          1 -1.83691e-16 0,
+                          0.707107 0.707107 0,
+                          2.44921e-16 1 0,
+                          2.44921e-16 1 0,
+                          -0.707107 0.707107 0,
+                          0.707107 0.707107 0,
+                          2.44921e-16 1 0,
+                          2.44921e-16 1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.707107 0.707107 0,
+                          -0.707107 0.707107 0,
+                          -1 3.06152e-16 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          2.44921e-16 1 0,
+                          -0.707107 0.707107 0,
+                          -0.707107 0.707107 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -0.707107 -0.707107 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.707107 0.707107 0,
+                          -1 3.06152e-16 0,
+                          -1 3.06152e-16 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          -1.22461e-16 -1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.707107 -0.707107 0,
+                          -1 6.12303e-17 0,
+                          -0.707107 -0.707107 0,
+                          -1.22461e-16 -1 0,
+                          -1.22461e-16 -1 0,
+                          0.707107 -0.707107 0,
+                          -1.22461e-16 -1 0,
+                          -0.707107 -0.707107 0,
+                          -1.22461e-16 -1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.707107 -0.707107 0,
+                          -1.22461e-16 -1 0,
+                          0.707107 -0.707107 0,
+                          1 -1.83691e-16 0,
+                          1 -1.83691e-16 0,
+                          0.5 -0.866025 0,
+                          0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          1 -1.83691e-16 0,
+                          0.5 0.866025 0,
+                          1 -1.83691e-16 0,
+                          1 -1.83691e-16 0,
+                          0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          1 -1.83691e-16 0,
+                          0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -1 6.12303e-17 0,
+                          0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -1 3.06152e-16 0,
+                          -1 3.06152e-16 0,
+                          -0.5 0.866025 0,
+                          -0.5 -0.866025 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          -1 3.06152e-16 0,
+                          -0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          0.5 0.866025 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.707107 -1.29889e-16 -0.707107,
+                          0.707107 -1.29889e-16 -0.707107,
+                          0.572061 0.415627 -0.707107,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.572061 -0.415627 -0.707107,
+                          0.572061 -0.415627 -0.707107,
+                          0.707107 -1.29889e-16 -0.707107,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.572061 -0.415627 -0.707107,
+                          0.707107 -1.29889e-16 -0.707107,
+                          0.707107 -1.29889e-16 -0.707107,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.572061 0.415627 -0.707107,
+                          0.572061 0.415627 -0.707107,
+                          0.218508 0.672499 -0.707107,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.572061 0.415627 -0.707107,
+                          0.707107 -1.29889e-16 -0.707107,
+                          0.572061 0.415627 -0.707107,
+                          0.218508 0.672499 -0.707107,
+                          0.218508 0.672499 -0.707107,
+                          -0.218508 0.672499 -0.707107,
+                          0.218508 0.672499 -0.707107,
+                          0.572061 0.415627 -0.707107,
+                          0.218508 0.672499 -0.707107,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.218508 0.672499 -0.707107,
+                          -0.218508 0.672499 -0.707107,
+                          -0.572061 0.415627 -0.707107,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.218508 0.672499 -0.707107,
+                          0.218508 0.672499 -0.707107,
+                          -0.218508 0.672499 -0.707107,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.572061 0.415627 -0.707107,
+                          -0.572061 0.415627 -0.707107,
+                          -0.707107 -2.9237e-15 -0.707107,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.572061 0.415627 -0.707107,
+                          -0.218508 0.672499 -0.707107,
+                          -0.572061 0.415627 -0.707107,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.572061 -0.415627 -0.707107,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.572061 0.415627 -0.707107,
+                          -0.707107 -2.9237e-15 -0.707107,
+                          -0.707107 -2.9237e-15 -0.707107,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.572061 -0.415627 -0.707107,
+                          -0.572061 -0.415627 -0.707107,
+                          -0.218508 -0.672499 -0.707107,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.572061 -0.415627 -0.707107,
+                          -0.572061 -0.415627 -0.707107,
+                          -0.218508 -0.672499 -0.707107,
+                          -0.218508 -0.672499 -0.707107,
+                          0.218508 -0.672499 -0.707107,
+                          -0.572061 -0.415627 -0.707107,
+                          -0.218508 -0.672499 -0.707107,
+                          -0.218508 -0.672499 -0.707107,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.218508 -0.672499 -0.707107,
+                          0.218508 -0.672499 -0.707107,
+                          0.572061 -0.415627 -0.707107,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.218508 -0.672499 -0.707107,
+                          0.218508 -0.672499 -0.707107,
+                          0.218508 -0.672499 -0.707107,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.218508 -0.672499 -0.707107,
+                          0.572061 -0.415627 -0.707107,
+                          0.572061 -0.415627 -0.707107,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          0.5 -0.866025 0,
+                          0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          1 1.83691e-16 0,
+                          0.5 0.866025 0,
+                          1 1.83691e-16 0,
+                          1 1.83691e-16 0,
+                          0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          1 -6.12303e-17 0,
+                          0.5 -0.866025 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -1 -6.12303e-17 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -1 -6.12303e-17 0,
+                          -1 -6.12303e-17 0,
+                          -0.5 0.866025 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.5 -0.866025 0,
+                          -1 -6.12303e-17 0,
+                          -1 -6.12303e-17 0,
+                          -0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          -1 -6.12303e-17 0,
+                          -0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          0.5 -0.866025 0,
+                          0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          1 1.83691e-16 0,
+                          0.5 0.866025 0,
+                          1 1.83691e-16 0,
+                          1 1.83691e-16 0,
+                          0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          1 -6.12303e-17 0,
+                          0.5 -0.866025 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -1 -6.12303e-17 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -1 -6.12303e-17 0,
+                          -1 -6.12303e-17 0,
+                          -0.5 0.866025 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.5 -0.866025 0,
+                          -1 -6.12303e-17 0,
+                          -1 -6.12303e-17 0,
+                          -0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          -1 -6.12303e-17 0,
+                          -0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          0.5 -0.866025 0,
+                          0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          1 1.83691e-16 0,
+                          0.5 0.866025 0,
+                          1 1.83691e-16 0,
+                          1 1.83691e-16 0,
+                          0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          1 -6.12303e-17 0,
+                          0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -1 -6.12303e-17 0,
+                          -0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -1 -6.12303e-17 0,
+                          -1 -6.12303e-17 0,
+                          -0.5 0.866025 0,
+                          -1 -6.12303e-17 0,
+                          -0.5 -0.866025 0,
+                          -1 -6.12303e-17 0,
+                          -0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          -1 -6.12303e-17 0,
+                          -0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          0.5 -0.866025 0,
+                          0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          1 1.83691e-16 0,
+                          0.5 0.866025 0,
+                          1 1.83691e-16 0,
+                          1 1.83691e-16 0,
+                          0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          1 -6.12303e-17 0,
+                          0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -1 -6.12303e-17 0,
+                          -0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -1 -6.12303e-17 0,
+                          -1 -6.12303e-17 0,
+                          -0.5 0.866025 0,
+                          -1 -6.12303e-17 0,
+                          -0.5 -0.866025 0,
+                          -1 -6.12303e-17 0,
+                          -0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          -1 -6.12303e-17 0,
+                          -0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          0.5 -0.866025 0,
+                          0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          1 1.83691e-16 0,
+                          0.5 0.866025 0,
+                          1 1.83691e-16 0,
+                          1 1.83691e-16 0,
+                          0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          1 -6.12303e-17 0,
+                          0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -1 -6.12303e-17 0,
+                          0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -1 -6.12303e-17 0,
+                          -1 -6.12303e-17 0,
+                          -0.5 0.866025 0,
+                          -0.5 -0.866025 0,
+                          -1 -6.12303e-17 0,
+                          -1 -6.12303e-17 0,
+                          -0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          -1 -6.12303e-17 0,
+                          -0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          0.5 -0.866025 0,
+                          0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          1 1.83691e-16 0,
+                          0.5 0.866025 0,
+                          1 1.83691e-16 0,
+                          1 1.83691e-16 0,
+                          0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          1 -6.12303e-17 0,
+                          0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -1 -6.12303e-17 0,
+                          -0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -1 -6.12303e-17 0,
+                          -1 -6.12303e-17 0,
+                          -0.5 0.866025 0,
+                          -1 -6.12303e-17 0,
+                          -0.5 -0.866025 0,
+                          -1 -6.12303e-17 0,
+                          -0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          -1 -6.12303e-17 0,
+                          -0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          0.5 0.866025 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 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 2.00048 88.1891 105.5,
+                          5.65685 90.3824 105.5,
+                          8 84.7256 105.5,
+                          8 84.7256 107,
+                          8 84.7256 105.5,
+                          5.65685 90.3824 105.5,
+                          4 84.7256 105.5,
+                          8 84.7256 105.5,
+                          5.65685 79.0687 105.5,
+                          5.65685 79.0687 107,
+                          5.65685 79.0687 105.5,
+                          8 84.7256 105.5,
+                          2.00048 88.1891 105.5,
+                          8 84.7256 105.5,
+                          4 84.7256 105.5,
+                          8 84.7256 107,
+                          5.65685 79.0687 107,
+                          8 84.7256 105.5,
+                          -5.65685 90.3824 105.5,
+                          3.95144e-13 92.7256 105.5,
+                          5.65685 90.3824 105.5,
+                          5.65685 90.3824 107,
+                          5.65685 90.3824 105.5,
+                          3.95144e-13 92.7256 105.5,
+                          2.00048 88.1891 105.5,
+                          -5.65685 90.3824 105.5,
+                          5.65685 90.3824 105.5,
+                          5.65685 90.3824 107,
+                          8 84.7256 107,
+                          5.65685 90.3824 105.5,
+                          3.95144e-13 92.7256 107,
+                          3.95144e-13 92.7256 105.5,
+                          -5.65685 90.3824 105.5,
+                          5.65685 90.3824 107,
+                          3.95144e-13 92.7256 105.5,
+                          3.95144e-13 92.7256 107,
+                          -4 84.7256 105.5,
+                          -8 84.7256 105.5,
+                          -5.65685 90.3824 105.5,
+                          -5.65685 90.3824 107,
+                          -5.65685 90.3824 105.5,
+                          -8 84.7256 105.5,
+                          -2.00048 88.1891 105.5,
+                          -4 84.7256 105.5,
+                          -5.65685 90.3824 105.5,
+                          2.00048 88.1891 105.5,
+                          -2.00048 88.1891 105.5,
+                          -5.65685 90.3824 105.5,
+                          3.95144e-13 92.7256 107,
+                          -5.65685 90.3824 105.5,
+                          -5.65685 90.3824 107,
+                          -2.00048 81.2621 105.5,
+                          -5.65685 79.0687 105.5,
+                          -8 84.7256 105.5,
+                          -8 84.7256 107,
+                          -8 84.7256 105.5,
+                          -5.65685 79.0687 105.5,
+                          -4 84.7256 105.5,
+                          -2.00048 81.2621 105.5,
+                          -8 84.7256 105.5,
+                          -5.65685 90.3824 107,
+                          -8 84.7256 105.5,
+                          -8 84.7256 107,
+                          5.65685 79.0687 105.5,
+                          3.94164e-13 76.7256 105.5,
+                          -5.65685 79.0687 105.5,
+                          -5.65685 79.0687 107,
+                          -5.65685 79.0687 105.5,
+                          3.94164e-13 76.7256 105.5,
+                          -2.00048 81.2621 105.5,
+                          5.65685 79.0687 105.5,
+                          -5.65685 79.0687 105.5,
+                          -5.65685 79.0687 107,
+                          -8 84.7256 107,
+                          -5.65685 79.0687 105.5,
+                          3.94164e-13 76.7256 107,
+                          3.94164e-13 76.7256 105.5,
+                          5.65685 79.0687 105.5,
+                          3.94164e-13 76.7256 107,
+                          -5.65685 79.0687 107,
+                          3.94164e-13 76.7256 105.5,
+                          2.00048 81.2621 105.5,
+                          4 84.7256 105.5,
+                          5.65685 79.0687 105.5,
+                          -2.00048 81.2621 105.5,
+                          2.00048 81.2621 105.5,
+                          5.65685 79.0687 105.5,
+                          5.65685 79.0687 107,
+                          3.94164e-13 76.7256 107,
+                          5.65685 79.0687 105.5,
+                          4 84.7256 104,
+                          4 84.7256 105.5,
+                          2.00048 81.2621 105.5,
+                          2.00048 88.1891 104,
+                          2.00048 88.1891 105.5,
+                          4 84.7256 105.5,
+                          2.00048 88.1891 104,
+                          4 84.7256 105.5,
+                          4 84.7256 104,
+                          2.00048 81.2621 104,
+                          2.00048 81.2621 105.5,
+                          -2.00048 81.2621 105.5,
+                          2.00048 81.2621 104,
+                          4 84.7256 104,
+                          2.00048 81.2621 105.5,
+                          -2.00048 81.2621 104,
+                          -2.00048 81.2621 105.5,
+                          -4 84.7256 105.5,
+                          2.00048 81.2621 104,
+                          -2.00048 81.2621 105.5,
+                          -2.00048 81.2621 104,
+                          -4 84.7256 104,
+                          -4 84.7256 105.5,
+                          -2.00048 88.1891 105.5,
+                          -2.00048 81.2621 104,
+                          -4 84.7256 105.5,
+                          -4 84.7256 104,
+                          -2.00048 88.1891 104,
+                          -2.00048 88.1891 105.5,
+                          2.00048 88.1891 105.5,
+                          -4 84.7256 104,
+                          -2.00048 88.1891 105.5,
+                          -2.00048 88.1891 104,
+                          -2.00048 88.1891 104,
+                          2.00048 88.1891 105.5,
+                          2.00048 88.1891 104,
+                          -9.5 84.7256 107,
+                          -8 84.7256 107,
+                          -5.65685 79.0687 107,
+                          -10.2505 86.0247 107,
+                          -5.65685 90.3824 107,
+                          -8 84.7256 107,
+                          -9.5 84.7256 107,
+                          -10.2505 86.0247 107,
+                          -8 84.7256 107,
+                          -4.75047 76.4984 107,
+                          -5.65685 79.0687 107,
+                          3.94164e-13 76.7256 107,
+                          -4.75047 76.4984 107,
+                          -15.5 84.7256 107,
+                          -5.65685 79.0687 107,
+                          -11.7495 83.4265 107,
+                          -5.65685 79.0687 107,
+                          -15.5 84.7256 107,
+                          -10.2505 83.4265 107,
+                          -9.5 84.7256 107,
+                          -5.65685 79.0687 107,
+                          -11.7495 83.4265 107,
+                          -10.2505 83.4265 107,
+                          -5.65685 79.0687 107,
+                          6.24953 76.4984 107,
+                          3.94164e-13 76.7256 107,
+                          5.65685 79.0687 107,
+                          4.75047 76.4984 107,
+                          -4.75047 76.4984 107,
+                          3.94164e-13 76.7256 107,
+                          6.24953 76.4984 107,
+                          4.75047 76.4984 107,
+                          3.94164e-13 76.7256 107,
+                          10.2505 83.4265 107,
+                          5.65685 79.0687 107,
+                          8 84.7256 107,
+                          6.24953 76.4984 107,
+                          5.65685 79.0687 107,
+                          12.5399 75.6158 107,
+                          10.2505 83.4265 107,
+                          12.5399 75.6158 107,
+                          5.65685 79.0687 107,
+                          9.5 84.7256 107,
+                          8 84.7256 107,
+                          5.65685 90.3824 107,
+                          10.2505 83.4265 107,
+                          8 84.7256 107,
+                          9.5 84.7256 107,
+                          6.24953 92.9528 107,
+                          12.5399 93.8354 107,
+                          15.5 84.7256 107,
+                          16 84.7256 107.5,
+                          15.5 84.7256 107,
+                          12.5399 93.8354 107,
+                          12.5 84.7256 107,
+                          15.5 84.7256 107,
+                          12.5399 75.6158 107,
+                          12.9443 75.321 107.5,
+                          12.5399 75.6158 107,
+                          15.5 84.7256 107,
+                          4.75047 92.9528 107,
+                          15.5 84.7256 107,
+                          5.65685 90.3824 107,
+                          11.7495 86.0247 107,
+                          5.65685 90.3824 107,
+                          15.5 84.7256 107,
+                          4.75047 92.9528 107,
+                          6.24953 92.9528 107,
+                          15.5 84.7256 107,
+                          12.5 84.7256 107,
+                          11.7495 86.0247 107,
+                          15.5 84.7256 107,
+                          12.9443 75.321 107.5,
+                          15.5 84.7256 107,
+                          16 84.7256 107.5,
+                          -4.78822 99.4673 107,
+                          4.78822 99.4673 107,
+                          12.5399 93.8354 107,
+                          12.9443 94.1301 107.5,
+                          12.5399 93.8354 107,
+                          4.78822 99.4673 107,
+                          6.24953 95.551 107,
+                          -4.78822 99.4673 107,
+                          12.5399 93.8354 107,
+                          7 94.2519 107,
+                          6.24953 95.551 107,
+                          12.5399 93.8354 107,
+                          6.24953 92.9528 107,
+                          7 94.2519 107,
+                          12.5399 93.8354 107,
+                          12.9443 94.1301 107.5,
+                          16 84.7256 107.5,
+                          12.5399 93.8354 107,
+                          4.94427 99.9425 107.5,
+                          4.78822 99.4673 107,
+                          -4.78822 99.4673 107,
+                          4.94427 99.9425 107.5,
+                          12.9443 94.1301 107.5,
+                          4.78822 99.4673 107,
+                          -7 94.2519 107,
+                          -12.5399 93.8354 107,
+                          -4.78822 99.4673 107,
+                          -4.94427 99.9425 107.5,
+                          -4.78822 99.4673 107,
+                          -12.5399 93.8354 107,
+                          -6.24953 95.551 107,
+                          -7 94.2519 107,
+                          -4.78822 99.4673 107,
+                          -4.75047 95.551 107,
+                          -6.24953 95.551 107,
+                          -4.78822 99.4673 107,
+                          4.75047 95.551 107,
+                          -4.75047 95.551 107,
+                          -4.78822 99.4673 107,
+                          6.24953 95.551 107,
+                          4.75047 95.551 107,
+                          -4.78822 99.4673 107,
+                          -4.94427 99.9425 107.5,
+                          4.94427 99.9425 107.5,
+                          -4.78822 99.4673 107,
+                          -12.5 84.7256 107,
+                          -15.5 84.7256 107,
+                          -12.5399 93.8354 107,
+                          -12.9443 94.1301 107.5,
+                          -12.5399 93.8354 107,
+                          -15.5 84.7256 107,
+                          -6.24953 92.9528 107,
+                          -5.65685 90.3824 107,
+                          -12.5399 93.8354 107,
+                          -10.2505 86.0247 107,
+                          -12.5399 93.8354 107,
+                          -5.65685 90.3824 107,
+                          -6.24953 92.9528 107,
+                          -12.5399 93.8354 107,
+                          -7 94.2519 107,
+                          -11.7495 86.0247 107,
+                          -12.5 84.7256 107,
+                          -12.5399 93.8354 107,
+                          -10.2505 86.0247 107,
+                          -11.7495 86.0247 107,
+                          -12.5399 93.8354 107,
+                          -12.9443 94.1301 107.5,
+                          -4.94427 99.9425 107.5,
+                          -12.5399 93.8354 107,
+                          -6.24953 76.4984 107,
+                          -12.5399 75.6158 107,
+                          -15.5 84.7256 107,
+                          -16 84.7256 107.5,
+                          -15.5 84.7256 107,
+                          -12.5399 75.6158 107,
+                          -4.75047 76.4984 107,
+                          -6.24953 76.4984 107,
+                          -15.5 84.7256 107,
+                          -11.7495 83.4265 107,
+                          -15.5 84.7256 107,
+                          -12.5 84.7256 107,
+                          -12.9443 94.1301 107.5,
+                          -15.5 84.7256 107,
+                          -16 84.7256 107.5,
+                          4.78822 69.9839 107,
+                          -4.78822 69.9839 107,
+                          -12.5399 75.6158 107,
+                          -12.9443 75.321 107.5,
+                          -12.5399 75.6158 107,
+                          -4.78822 69.9839 107,
+                          -6.24953 73.9002 107,
+                          4.78822 69.9839 107,
+                          -12.5399 75.6158 107,
+                          -6.24953 76.4984 107,
+                          -7 75.1993 107,
+                          -12.5399 75.6158 107,
+                          -6.24953 73.9002 107,
+                          -12.5399 75.6158 107,
+                          -7 75.1993 107,
+                          -16 84.7256 107.5,
+                          -12.5399 75.6158 107,
+                          -12.9443 75.321 107.5,
+                          -4.94427 69.5087 107.5,
+                          -4.78822 69.9839 107,
+                          4.78822 69.9839 107,
+                          -12.9443 75.321 107.5,
+                          -4.78822 69.9839 107,
+                          -4.94427 69.5087 107.5,
+                          7 75.1993 107,
+                          12.5399 75.6158 107,
+                          4.78822 69.9839 107,
+                          4.94427 69.5087 107.5,
+                          4.78822 69.9839 107,
+                          12.5399 75.6158 107,
+                          -6.24953 73.9002 107,
+                          -4.75047 73.9002 107,
+                          4.78822 69.9839 107,
+                          4.75047 73.9002 107,
+                          4.78822 69.9839 107,
+                          -4.75047 73.9002 107,
+                          6.24953 73.9002 107,
+                          7 75.1993 107,
+                          4.78822 69.9839 107,
+                          4.75047 73.9002 107,
+                          6.24953 73.9002 107,
+                          4.78822 69.9839 107,
+                          -4.94427 69.5087 107.5,
+                          4.78822 69.9839 107,
+                          4.94427 69.5087 107.5,
+                          7 75.1993 107,
+                          6.24953 76.4984 107,
+                          12.5399 75.6158 107,
+                          11.7495 83.4265 107,
+                          12.5 84.7256 107,
+                          12.5399 75.6158 107,
+                          10.2505 83.4265 107,
+                          11.7495 83.4265 107,
+                          12.5399 75.6158 107,
+                          4.94427 69.5087 107.5,
+                          12.5399 75.6158 107,
+                          12.9443 75.321 107.5,
+                          -6.24953 92.9528 107,
+                          3.95144e-13 92.7256 107,
+                          -5.65685 90.3824 107,
+                          4.75047 92.9528 107,
+                          5.65685 90.3824 107,
+                          3.95144e-13 92.7256 107,
+                          -6.24953 92.9528 107,
+                          -4.75047 92.9528 107,
+                          3.95144e-13 92.7256 107,
+                          4.75047 92.9528 107,
+                          3.95144e-13 92.7256 107,
+                          -4.75047 92.9528 107,
+                          10.2505 86.0247 107,
+                          9.5 84.7256 107,
+                          5.65685 90.3824 107,
+                          11.7495 86.0247 107,
+                          10.2505 86.0247 107,
+                          5.65685 90.3824 107,
+                          -7 94.2519 110,
+                          -7 94.2519 107,
+                          -6.24953 95.551 107,
+                          -6.25037 92.9533 110,
+                          -6.24953 92.9528 107,
+                          -7 94.2519 107,
+                          -6.25037 92.9533 110,
+                          -7 94.2519 107,
+                          -7 94.2519 110,
+                          -6.25037 95.5504 110,
+                          -6.24953 95.551 107,
+                          -4.75047 95.551 107,
+                          -6.25037 95.5504 110,
+                          -7 94.2519 110,
+                          -6.24953 95.551 107,
+                          4 94.2519 107,
+                          -4 94.2519 107,
+                          -4.75047 95.551 107,
+                          -4.74963 95.5504 110,
+                          -4.75047 95.551 107,
+                          -4 94.2519 107,
+                          4.75047 95.551 107,
+                          4 94.2519 107,
+                          -4.75047 95.551 107,
+                          -6.25037 95.5504 110,
+                          -4.75047 95.551 107,
+                          -4.74963 95.5504 110,
+                          4.75047 92.9528 107,
+                          -4.75047 92.9528 107,
+                          -4 94.2519 107,
+                          -4 94.2519 110,
+                          -4 94.2519 107,
+                          -4.75047 92.9528 107,
+                          4.75047 92.9528 107,
+                          -4 94.2519 107,
+                          4 94.2519 107,
+                          -4.74963 95.5504 110,
+                          -4 94.2519 107,
+                          -4 94.2519 110,
+                          -4.74963 92.9533 110,
+                          -4.75047 92.9528 107,
+                          -6.24953 92.9528 107,
+                          -4 94.2519 110,
+                          -4.75047 92.9528 107,
+                          -4.74963 92.9533 110,
+                          -4.74963 92.9533 110,
+                          -6.24953 92.9528 107,
+                          -6.25037 92.9533 110,
+                          -7 75.1993 110,
+                          -7 75.1993 107,
+                          -6.24953 76.4984 107,
+                          -6.25037 73.9008 110,
+                          -6.24953 73.9002 107,
+                          -7 75.1993 107,
+                          -6.25037 73.9008 110,
+                          -7 75.1993 107,
+                          -7 75.1993 110,
+                          -6.25037 76.4978 110,
+                          -6.24953 76.4984 107,
+                          -4.75047 76.4984 107,
+                          -6.25037 76.4978 110,
+                          -7 75.1993 110,
+                          -6.24953 76.4984 107,
+                          4 75.1993 107,
+                          -4 75.1993 107,
+                          -4.75047 76.4984 107,
+                          -4.74963 76.4978 110,
+                          -4.75047 76.4984 107,
+                          -4 75.1993 107,
+                          4.75047 76.4984 107,
+                          4 75.1993 107,
+                          -4.75047 76.4984 107,
+                          -6.25037 76.4978 110,
+                          -4.75047 76.4984 107,
+                          -4.74963 76.4978 110,
+                          4.75047 73.9002 107,
+                          -4.75047 73.9002 107,
+                          -4 75.1993 107,
+                          -4 75.1993 110,
+                          -4 75.1993 107,
+                          -4.75047 73.9002 107,
+                          4.75047 73.9002 107,
+                          -4 75.1993 107,
+                          4 75.1993 107,
+                          -4.74963 76.4978 110,
+                          -4 75.1993 107,
+                          -4 75.1993 110,
+                          -4.74963 73.9008 110,
+                          -4.75047 73.9002 107,
+                          -6.24953 73.9002 107,
+                          -4 75.1993 110,
+                          -4.75047 73.9002 107,
+                          -4.74963 73.9008 110,
+                          -4.74963 73.9008 110,
+                          -6.24953 73.9002 107,
+                          -6.25037 73.9008 110,
+                          4 75.1993 110,
+                          4 75.1993 107,
+                          4.75047 76.4984 107,
+                          4.74963 73.9008 110,
+                          4.75047 73.9002 107,
+                          4 75.1993 107,
+                          4.74963 73.9008 110,
+                          4 75.1993 107,
+                          4 75.1993 110,
+                          4.74963 76.4978 110,
+                          4.75047 76.4984 107,
+                          6.24953 76.4984 107,
+                          4.74963 76.4978 110,
+                          4 75.1993 110,
+                          4.75047 76.4984 107,
+                          6.25037 76.4978 110,
+                          6.24953 76.4984 107,
+                          7 75.1993 107,
+                          6.25037 76.4978 110,
+                          4.74963 76.4978 110,
+                          6.24953 76.4984 107,
+                          7 75.1993 110,
+                          7 75.1993 107,
+                          6.24953 73.9002 107,
+                          7 75.1993 110,
+                          6.25037 76.4978 110,
+                          7 75.1993 107,
+                          6.25037 73.9008 110,
+                          6.24953 73.9002 107,
+                          4.75047 73.9002 107,
+                          6.25037 73.9008 110,
+                          7 75.1993 110,
+                          6.24953 73.9002 107,
+                          4.74963 73.9008 110,
+                          6.25037 73.9008 110,
+                          4.75047 73.9002 107,
+                          4 94.2519 110,
+                          4 94.2519 107,
+                          4.75047 95.551 107,
+                          4.74963 92.9533 110,
+                          4.75047 92.9528 107,
+                          4 94.2519 107,
+                          4.74963 92.9533 110,
+                          4 94.2519 107,
+                          4 94.2519 110,
+                          4.74963 95.5504 110,
+                          4.75047 95.551 107,
+                          6.24953 95.551 107,
+                          4.74963 95.5504 110,
+                          4 94.2519 110,
+                          4.75047 95.551 107,
+                          6.25037 95.5504 110,
+                          6.24953 95.551 107,
+                          7 94.2519 107,
+                          6.25037 95.5504 110,
+                          4.74963 95.5504 110,
+                          6.24953 95.551 107,
+                          7 94.2519 110,
+                          7 94.2519 107,
+                          6.24953 92.9528 107,
+                          7 94.2519 110,
+                          6.25037 95.5504 110,
+                          7 94.2519 107,
+                          6.25037 92.9533 110,
+                          6.24953 92.9528 107,
+                          4.75047 92.9528 107,
+                          6.25037 92.9533 110,
+                          7 94.2519 110,
+                          6.24953 92.9528 107,
+                          4.74963 92.9533 110,
+                          6.25037 92.9533 110,
+                          4.75047 92.9528 107,
+                          -12.5 84.7256 110,
+                          -12.5 84.7256 107,
+                          -11.7495 86.0247 107,
+                          -11.7504 83.4271 110,
+                          -11.7495 83.4265 107,
+                          -12.5 84.7256 107,
+                          -11.7504 83.4271 110,
+                          -12.5 84.7256 107,
+                          -12.5 84.7256 110,
+                          -11.7504 86.0241 110,
+                          -11.7495 86.0247 107,
+                          -10.2505 86.0247 107,
+                          -11.7504 86.0241 110,
+                          -12.5 84.7256 110,
+                          -11.7495 86.0247 107,
+                          -10.2496 86.0241 110,
+                          -10.2505 86.0247 107,
+                          -9.5 84.7256 107,
+                          -11.7504 86.0241 110,
+                          -10.2505 86.0247 107,
+                          -10.2496 86.0241 110,
+                          -9.5 84.7256 110,
+                          -9.5 84.7256 107,
+                          -10.2505 83.4265 107,
+                          -10.2496 86.0241 110,
+                          -9.5 84.7256 107,
+                          -9.5 84.7256 110,
+                          -10.2496 83.4271 110,
+                          -10.2505 83.4265 107,
+                          -11.7495 83.4265 107,
+                          -9.5 84.7256 110,
+                          -10.2505 83.4265 107,
+                          -10.2496 83.4271 110,
+                          -10.2496 83.4271 110,
+                          -11.7495 83.4265 107,
+                          -11.7504 83.4271 110,
+                          9.5 84.7256 110,
+                          9.5 84.7256 107,
+                          10.2505 86.0247 107,
+                          10.2496 83.4271 110,
+                          10.2505 83.4265 107,
+                          9.5 84.7256 107,
+                          10.2496 83.4271 110,
+                          9.5 84.7256 107,
+                          9.5 84.7256 110,
+                          10.2496 86.0241 110,
+                          10.2505 86.0247 107,
+                          11.7495 86.0247 107,
+                          10.2496 86.0241 110,
+                          9.5 84.7256 110,
+                          10.2505 86.0247 107,
+                          11.7504 86.0241 110,
+                          11.7495 86.0247 107,
+                          12.5 84.7256 107,
+                          11.7504 86.0241 110,
+                          10.2496 86.0241 110,
+                          11.7495 86.0247 107,
+                          12.5 84.7256 110,
+                          12.5 84.7256 107,
+                          11.7495 83.4265 107,
+                          12.5 84.7256 110,
+                          11.7504 86.0241 110,
+                          12.5 84.7256 107,
+                          11.7504 83.4271 110,
+                          11.7495 83.4265 107,
+                          10.2505 83.4265 107,
+                          11.7504 83.4271 110,
+                          12.5 84.7256 110,
+                          11.7495 83.4265 107,
+                          10.2496 83.4271 110,
+                          11.7504 83.4271 110,
+                          10.2505 83.4265 107,
+                          1.25 86.8906 104,
+                          2.00048 88.1891 104,
+                          4 84.7256 104,
+                          1.25 86.8906 104,
+                          -2.00048 88.1891 104,
+                          2.00048 88.1891 104,
+                          1.25 86.8906 104,
+                          -1.25 86.8906 104,
+                          -2.00048 88.1891 104 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.7 0.7 0.7
+    }
+    Separator {
+        Normal {
+            vector      [ -0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          -0.903953 0.427632 0,
+                          -0.5 0.866025 0,
+                          -0.8 0.6 0,
+                          -0.5 0.866025 0,
+                          -0.8 0.6 0,
+                          -0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          0.8 0.6 0,
+                          0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -4.34889e-17 -0.710251 -0.703948,
+                          -4.36425e-17 -0.71276 -0.701408,
+                          -6.12303e-17 -1 0,
+                          -4.34889e-17 -0.710251 -0.703948,
+                          -4.35127e-17 -0.71064 0.703556,
+                          -6.12303e-17 -1 2.44921e-16,
+                          -6.12303e-17 -1 2.44921e-16,
+                          -4.36875e-17 -0.713494 0.700661,
+                          -6.12303e-17 -1 2.44921e-16,
+                          -4.35127e-17 -0.71064 0.703556,
+                          0.5 0.866025 0,
+                          0.8 0.6 0,
+                          0.903739 0.428084 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -1.25 86.8906 94.5,
+                          -1.25 86.8906 104,
+                          1.25 86.8906 104,
+                          -2.25988 85.7947 99.5519,
+                          -1.25 86.8906 104,
+                          -2 86.2256 98.5,
+                          -1.25 86.8906 94.5,
+                          -2 86.2256 98.5,
+                          -1.25 86.8906 104,
+                          1.25 86.8906 94.5,
+                          1.25 86.8906 104,
+                          2 86.2256 98.5,
+                          1.25 86.8906 94.5,
+                          -1.25 86.8906 94.5,
+                          1.25 86.8906 104,
+                          -2 86.2256 98.5,
+                          2 86.2256 98.5,
+                          2.26164 85.7909 99.5558,
+                          -2.25988 85.7947 99.5519,
+                          -2 86.2256 98.5,
+                          2.26164 85.7909 99.5558,
+                          -2.26135 85.7916 97.4448,
+                          2 86.2256 98.5,
+                          -2 86.2256 98.5,
+                          2.25935 85.7958 97.4491,
+                          2 86.2256 98.5,
+                          -2.26135 85.7916 97.4448,
+                          1.25 86.8906 94.5,
+                          2 86.2256 98.5,
+                          2.25935 85.7958 97.4491 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.83 0 0
+    }
+    Separator {
+        Normal {
+            vector      [ -0.309017 -0.951057 0,
+                          -0.0344003 -0.999408 0,
+                          -0.347985 -0.9375 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.809017 -0.587785 0,
+                          -0.309017 -0.951057 0,
+                          -0.347985 -0.9375 0,
+                          -0.820956 -0.570991 0,
+                          -0.809017 -0.587785 0,
+                          -0.347985 -0.9375 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -4.94427 69.5087 107.5,
+                          -0.550404 68.7351 169,
+                          -5.56776 69.7256 169,
+                          3.93736e-13 69.7256 169,
+                          -5.56776 69.7256 169,
+                          -0.550404 68.7351 169,
+                          -12.9443 75.321 107.5,
+                          -4.94427 69.5087 107.5,
+                          -5.56776 69.7256 169,
+                          -13.1353 75.5897 169,
+                          -12.9443 75.321 107.5,
+                          -5.56776 69.7256 169 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.25 0.25 0.25
+    }
+    Separator {
+        Normal {
+            vector      [ 0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -26.1 70.7256 169,
+                          -13.1353 75.5897 169,
+                          -5.56776 69.7256 169,
+                          -25.1 69.7256 187.3,
+                          -5.56776 69.7256 169,
+                          3.93736e-13 69.7256 169,
+                          -25.1 69.7256 169,
+                          -5.56776 69.7256 169,
+                          -25.1 69.7256 187.3,
+                          -25.8071 70.0185 169,
+                          -26.1 70.7256 169,
+                          -5.56776 69.7256 169,
+                          -25.1 69.7256 169,
+                          -25.8071 70.0185 169,
+                          -5.56776 69.7256 169 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.83 0 0
+    }
+    Separator {
+        Normal {
+            vector      [ 0.309017 -0.951057 0,
+                          0.282706 -0.959207 0,
+                          -0.0344003 -0.999408 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.309017 -0.951057 0,
+                          0.309017 -0.951057 0,
+                          -0.0344003 -0.999408 0,
+                          0.309017 -0.951057 0,
+                          0.570933 -0.820996 0,
+                          0.282706 -0.959207 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.809017 -0.587785 0,
+                          0.800831 -0.598891 0,
+                          0.570933 -0.820996 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.309017 -0.951057 0,
+                          0.809017 -0.587785 0,
+                          0.570933 -0.820996 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.809017 -0.587785 0,
+                          0.9489 -0.315577 0,
+                          0.800831 -0.598891 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          1 -1.83691e-16 0,
+                          1 -1.83691e-16 0,
+                          0.9489 -0.315577 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.809017 -0.587785 0,
+                          1 -1.83691e-16 0,
+                          0.9489 -0.315577 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.809017 0.587785 0,
+                          1 -1.83691e-16 0,
+                          1 -1.83691e-16 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.809017 0.587785 0,
+                          0.9489 0.315577 0,
+                          1 -1.83691e-16 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -0.809017 -0.587785 0,
+                          -0.820956 -0.570991 0,
+                          -1 6.12303e-17 0,
+                          -0.809017 -0.587785 0,
+                          -0.820956 0.570991 0,
+                          -1 3.06152e-16 0,
+                          -1 3.06152e-16 0,
+                          -0.820956 0.570991 0,
+                          -0.809017 0.587785 0,
+                          -1 3.06152e-16 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 4.94427 69.5087 107.5,
+                          4.52329 69.3783 169,
+                          -0.550404 68.7351 169,
+                          3.93736e-13 69.7256 169,
+                          -0.550404 68.7351 169,
+                          4.52329 69.3783 169,
+                          -4.94427 69.5087 107.5,
+                          4.94427 69.5087 107.5,
+                          -0.550404 68.7351 169,
+                          4.94427 69.5087 107.5,
+                          9.13494 71.5896 169,
+                          4.52329 69.3783 169,
+                          3.93736e-13 69.7256 169,
+                          4.52329 69.3783 169,
+                          9.13494 71.5896 169,
+                          12.9443 75.321 107.5,
+                          12.8133 75.1433 169,
+                          9.13494 71.5896 169,
+                          8.81759 72.5911 169,
+                          9.13494 71.5896 169,
+                          12.8133 75.1433 169,
+                          4.94427 69.5087 107.5,
+                          12.9443 75.321 107.5,
+                          9.13494 71.5896 169,
+                          8.81759 72.5911 169,
+                          3.93736e-13 69.7256 169,
+                          9.13494 71.5896 169,
+                          12.9443 75.321 107.5,
+                          15.1824 79.6764 169,
+                          12.8133 75.1433 169,
+                          8.81759 72.5911 169,
+                          12.8133 75.1433 169,
+                          15.1824 79.6764 169,
+                          16 84.7256 107.5,
+                          16 84.7256 169,
+                          15.1824 79.6764 169,
+                          14.2658 80.0909 169,
+                          15.1824 79.6764 169,
+                          16 84.7256 169,
+                          12.9443 75.321 107.5,
+                          16 84.7256 107.5,
+                          15.1824 79.6764 169,
+                          14.2658 80.0909 169,
+                          8.81759 72.5911 169,
+                          15.1824 79.6764 169,
+                          12.9443 94.1301 107.5,
+                          16 84.7256 169,
+                          16 84.7256 107.5,
+                          14.2658 89.3603 169,
+                          16 84.7256 169,
+                          15.1824 89.7748 169,
+                          12.9443 94.1301 107.5,
+                          15.1824 89.7748 169,
+                          16 84.7256 169,
+                          14.2658 89.3603 169,
+                          14.2658 80.0909 169,
+                          16 84.7256 169,
+                          -16 84.7256 169,
+                          -16 84.7256 107.5,
+                          -12.9443 75.321 107.5,
+                          -13.1353 75.5897 169,
+                          -16 84.7256 169,
+                          -12.9443 75.321 107.5,
+                          -13.1353 93.8614 169,
+                          -16 84.7256 107.5,
+                          -16 84.7256 169,
+                          -13.1353 93.8614 169,
+                          -12.9443 94.1301 107.5,
+                          -16 84.7256 107.5 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.25 0.25 0.25
+    }
+    Separator {
+        Normal {
+            vector      [ 0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -26.1 98.7256 169,
+                          -16 84.7256 169,
+                          -13.1353 75.5897 169,
+                          -26.1 98.7256 169,
+                          -13.1353 93.8614 169,
+                          -16 84.7256 169,
+                          -26.1 70.7256 169,
+                          -26.1 98.7256 169,
+                          -13.1353 75.5897 169 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.83 0 0
+    }
+    Separator {
+        Normal {
+            vector      [ 0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.309017 0.951057 0,
+                          -0.347985 0.9375 0,
+                          -0.0344003 0.999408 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 4.52329 100.073 169,
+                          -0.550404 100.716 169,
+                          -5.56776 99.7256 169,
+                          -4.94427 99.9425 107.5,
+                          -5.56776 99.7256 169,
+                          -0.550404 100.716 169,
+                          3.97409e-13 99.7256 169,
+                          4.52329 100.073 169,
+                          -5.56776 99.7256 169 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.25 0.25 0.25
+    }
+    Separator {
+        Normal {
+            vector      [ 6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 3.97409e-13 99.7256 187.3,
+                          3.97409e-13 99.7256 169,
+                          -5.56776 99.7256 169,
+                          -25.1 99.7256 169,
+                          3.97409e-13 99.7256 187.3,
+                          -5.56776 99.7256 169 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.83 0 0
+    }
+    Separator {
+        Normal {
+            vector      [ -0.809017 0.587785 0,
+                          -0.347985 0.9375 0,
+                          -0.309017 0.951057 0,
+                          -0.820956 0.570991 0,
+                          -0.347985 0.9375 0,
+                          -0.809017 0.587785 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -12.9443 94.1301 107.5,
+                          -5.56776 99.7256 169,
+                          -4.94427 99.9425 107.5,
+                          -13.1353 93.8614 169,
+                          -5.56776 99.7256 169,
+                          -12.9443 94.1301 107.5 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.25 0.25 0.25
+    }
+    Separator {
+        Normal {
+            vector      [ 0 0 -1,
+                          0 0 -1,
+                          0 0 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -25.1 99.7256 169,
+                          -5.56776 99.7256 169,
+                          -13.1353 93.8614 169 ]
+        }
+        FaceSet {
+            numVertices [ 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.83 0 0
+    }
+    Separator {
+        Normal {
+            vector      [ -0.309017 0.951057 0,
+                          -0.0344003 0.999408 0,
+                          0.282706 0.959207 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.309017 0.951057 0,
+                          0.282706 0.959207 0,
+                          0.570933 0.820996 0,
+                          -0.309017 0.951057 0,
+                          0.282706 0.959207 0,
+                          0.309017 0.951057 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.309017 0.951057 0,
+                          0.570933 0.820996 0,
+                          0.800831 0.598891 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.809017 0.587785 0,
+                          0.800831 0.598891 0,
+                          0.9489 0.315577 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.309017 0.951057 0,
+                          0.800831 0.598891 0,
+                          0.809017 0.587785 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -4.94427 99.9425 107.5,
+                          -0.550404 100.716 169,
+                          4.52329 100.073 169,
+                          3.97409e-13 99.7256 169,
+                          9.13494 97.8615 169,
+                          4.52329 100.073 169,
+                          4.94427 99.9425 107.5,
+                          4.52329 100.073 169,
+                          9.13494 97.8615 169,
+                          -4.94427 99.9425 107.5,
+                          4.52329 100.073 169,
+                          4.94427 99.9425 107.5,
+                          8.81759 96.8601 169,
+                          12.8133 94.3078 169,
+                          9.13494 97.8615 169,
+                          4.94427 99.9425 107.5,
+                          9.13494 97.8615 169,
+                          12.8133 94.3078 169,
+                          3.97409e-13 99.7256 169,
+                          8.81759 96.8601 169,
+                          9.13494 97.8615 169,
+                          14.2658 89.3603 169,
+                          15.1824 89.7748 169,
+                          12.8133 94.3078 169,
+                          12.9443 94.1301 107.5,
+                          12.8133 94.3078 169,
+                          15.1824 89.7748 169,
+                          8.81759 96.8601 169,
+                          14.2658 89.3603 169,
+                          12.8133 94.3078 169,
+                          4.94427 99.9425 107.5,
+                          12.8133 94.3078 169,
+                          12.9443 94.1301 107.5 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.25 0.25 0.25
+    }
+    Separator {
+        Normal {
+            vector      [ -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          0.587785 -0.809017 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          0.587785 -0.809017 0,
+                          0.587785 -0.809017 0,
+                          0.951057 -0.309017 0,
+                          -6.12303e-17 -1 0,
+                          0.587785 -0.809017 0,
+                          0.587785 -0.809017 0,
+                          0.951057 -0.309017 0,
+                          0.951057 -0.309017 0,
+                          0.951057 0.309017 0,
+                          0.587785 -0.809017 0,
+                          0.951057 -0.309017 0,
+                          0.951057 -0.309017 0,
+                          0.951057 0.309017 0,
+                          0.951057 0.309017 0,
+                          0.587785 0.809017 0,
+                          0.951057 -0.309017 0,
+                          0.951057 0.309017 0,
+                          0.951057 0.309017 0,
+                          0.587785 0.809017 0,
+                          0.587785 0.809017 0,
+                          1.83691e-16 1 0,
+                          0.951057 0.309017 0,
+                          0.587785 0.809017 0,
+                          0.587785 0.809017 0,
+                          0.587785 0.809017 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 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,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 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,
+                          -3.06152e-16 -1 0,
+                          -3.06152e-16 -1 0,
+                          -0.707107 -0.707107 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          -1 2.44921e-16 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -3.06152e-16 -1 0,
+                          -0.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -0.707107 -0.707107 0,
+                          -1 2.44921e-16 0,
+                          -1 2.44921e-16 0,
+                          -1 2.44921e-16 0,
+                          -1 2.44921e-16 0,
+                          -0.707107 0.707107 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -0.707107 0.707107 0,
+                          -0.707107 0.707107 0,
+                          1.83691e-16 1 0,
+                          -1 2.44921e-16 0,
+                          -0.707107 0.707107 0,
+                          -0.707107 0.707107 0,
+                          -0.707107 0.707107 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 3.93736e-13 69.7256 187.3,
+                          3.93736e-13 69.7256 169,
+                          8.81759 72.5911 169,
+                          -25.1 69.7256 187.3,
+                          3.93736e-13 69.7256 169,
+                          3.93736e-13 69.7256 187.3,
+                          8.81712 72.591 187.3,
+                          8.81759 72.5911 169,
+                          14.2658 80.0909 169,
+                          3.93736e-13 69.7256 187.3,
+                          8.81759 72.5911 169,
+                          8.81712 72.591 187.3,
+                          14.2653 80.0892 187.3,
+                          14.2658 80.0909 169,
+                          14.2658 89.3603 169,
+                          8.81712 72.591 187.3,
+                          14.2658 80.0909 169,
+                          14.2653 80.0892 187.3,
+                          14.2653 89.362 187.3,
+                          14.2658 89.3603 169,
+                          8.81759 96.8601 169,
+                          14.2653 80.0892 187.3,
+                          14.2658 89.3603 169,
+                          14.2653 89.362 187.3,
+                          8.81712 96.8602 187.3,
+                          8.81759 96.8601 169,
+                          3.97409e-13 99.7256 169,
+                          14.2653 89.362 187.3,
+                          8.81759 96.8601 169,
+                          8.81712 96.8602 187.3,
+                          8.81712 96.8602 187.3,
+                          3.97409e-13 99.7256 169,
+                          3.97409e-13 99.7256 187.3,
+                          8.81712 72.591 187.3,
+                          8.81712 96.8602 187.3,
+                          3.97409e-13 99.7256 187.3,
+                          3.93736e-13 69.7256 187.3,
+                          8.81712 72.591 187.3,
+                          3.97409e-13 99.7256 187.3,
+                          -25.1 99.7256 187.3,
+                          3.93736e-13 69.7256 187.3,
+                          3.97409e-13 99.7256 187.3,
+                          -25.1 99.7256 169,
+                          -25.1 99.7256 187.3,
+                          3.97409e-13 99.7256 187.3,
+                          14.2653 80.0892 187.3,
+                          14.2653 89.362 187.3,
+                          8.81712 96.8602 187.3,
+                          8.81712 72.591 187.3,
+                          14.2653 80.0892 187.3,
+                          8.81712 96.8602 187.3,
+                          -25.1 99.7256 187.3,
+                          -25.1 69.7256 187.3,
+                          3.93736e-13 69.7256 187.3,
+                          -25.8071 99.4327 187.3,
+                          -25.8071 70.0185 187.3,
+                          -25.1 69.7256 187.3,
+                          -25.1 69.7256 169,
+                          -25.1 69.7256 187.3,
+                          -25.8071 70.0185 187.3,
+                          -25.1 99.7256 187.3,
+                          -25.8071 99.4327 187.3,
+                          -25.1 69.7256 187.3,
+                          -26.1 98.7256 187.3,
+                          -26.1 70.7256 187.3,
+                          -25.8071 70.0185 187.3,
+                          -25.8071 70.0185 169,
+                          -25.8071 70.0185 187.3,
+                          -26.1 70.7256 187.3,
+                          -25.8071 99.4327 187.3,
+                          -26.1 98.7256 187.3,
+                          -25.8071 70.0185 187.3,
+                          -25.1 69.7256 169,
+                          -25.8071 70.0185 187.3,
+                          -25.8071 70.0185 169,
+                          -26.1 70.7256 169,
+                          -26.1 70.7256 187.3,
+                          -26.1 98.7256 187.3,
+                          -25.8071 70.0185 169,
+                          -26.1 70.7256 187.3,
+                          -26.1 70.7256 169,
+                          -26.1 98.7256 169,
+                          -26.1 98.7256 187.3,
+                          -25.8071 99.4327 187.3,
+                          -26.1 70.7256 169,
+                          -26.1 98.7256 187.3,
+                          -26.1 98.7256 169,
+                          -25.8071 99.4327 169,
+                          -25.8071 99.4327 187.3,
+                          -25.1 99.7256 187.3,
+                          -26.1 98.7256 169,
+                          -25.8071 99.4327 187.3,
+                          -25.8071 99.4327 169,
+                          -25.8071 99.4327 169,
+                          -25.1 99.7256 187.3,
+                          -25.1 99.7256 169 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.83 0 0
+    }
+    Separator {
+        Normal {
+            vector      [ 0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 4.74963 73.9008 110,
+                          4 75.1993 110,
+                          4.74963 76.4978 110,
+                          4.74963 73.9008 110,
+                          4.74963 76.4978 110,
+                          6.25037 76.4978 110,
+                          6.25037 73.9008 110,
+                          6.25037 76.4978 110,
+                          7 75.1993 110,
+                          4.74963 73.9008 110,
+                          6.25037 76.4978 110,
+                          6.25037 73.9008 110,
+                          4.74963 92.9533 110,
+                          4 94.2519 110,
+                          4.74963 95.5504 110,
+                          4.74963 92.9533 110,
+                          4.74963 95.5504 110,
+                          6.25037 95.5504 110,
+                          6.25037 92.9533 110,
+                          6.25037 95.5504 110,
+                          7 94.2519 110,
+                          4.74963 92.9533 110,
+                          6.25037 95.5504 110,
+                          6.25037 92.9533 110,
+                          10.2496 83.4271 110,
+                          9.5 84.7256 110,
+                          10.2496 86.0241 110,
+                          10.2496 83.4271 110,
+                          10.2496 86.0241 110,
+                          11.7504 86.0241 110,
+                          11.7504 83.4271 110,
+                          11.7504 86.0241 110,
+                          12.5 84.7256 110,
+                          10.2496 83.4271 110,
+                          11.7504 86.0241 110,
+                          11.7504 83.4271 110,
+                          -6.25037 95.5504 110,
+                          -6.25037 92.9533 110,
+                          -7 94.2519 110,
+                          -4.74963 95.5504 110,
+                          -4.74963 92.9533 110,
+                          -6.25037 92.9533 110,
+                          -6.25037 95.5504 110,
+                          -4.74963 95.5504 110,
+                          -6.25037 92.9533 110,
+                          -4.74963 95.5504 110,
+                          -4 94.2519 110,
+                          -4.74963 92.9533 110,
+                          -6.25037 76.4978 110,
+                          -6.25037 73.9008 110,
+                          -7 75.1993 110,
+                          -4.74963 76.4978 110,
+                          -4.74963 73.9008 110,
+                          -6.25037 73.9008 110,
+                          -6.25037 76.4978 110,
+                          -4.74963 76.4978 110,
+                          -6.25037 73.9008 110,
+                          -4.74963 76.4978 110,
+                          -4 75.1993 110,
+                          -4.74963 73.9008 110,
+                          -11.7504 86.0241 110,
+                          -11.7504 83.4271 110,
+                          -12.5 84.7256 110,
+                          -10.2496 86.0241 110,
+                          -10.2496 83.4271 110,
+                          -11.7504 83.4271 110,
+                          -11.7504 86.0241 110,
+                          -10.2496 86.0241 110,
+                          -11.7504 83.4271 110,
+                          -10.2496 86.0241 110,
+                          -9.5 84.7256 110,
+                          -10.2496 83.4271 110 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.25 0.25 0.25
+    }
+    Separator {
+        Normal {
+            vector      [ 0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -25.8071 99.4327 169,
+                          -25.1 99.7256 169,
+                          -13.1353 93.8614 169,
+                          -26.1 98.7256 169,
+                          -25.8071 99.4327 169,
+                          -13.1353 93.8614 169 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.85 0.9 0.47
+    }
+    Separator {
+        Normal {
+            vector      [ 0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          2.25551e-17 0.368364 0.929681,
+                          2.25551e-17 0.368364 0.929681,
+                          2.25551e-17 0.368364 0.929681,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          2.25551e-17 0.368364 0.929681,
+                          2.25551e-17 0.368364 0.929681,
+                          2.25551e-17 0.368364 0.929681,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          2.25551e-17 0.368364 0.929681,
+                          2.25551e-17 0.368364 0.929681,
+                          2.25551e-17 0.368364 0.929681,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          2.25551e-17 0.368364 0.929681,
+                          2.25551e-17 0.368364 0.929681,
+                          2.25551e-17 0.368364 0.929681,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 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,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 25 57.5 91,
+                          28 54.5 91,
+                          28 57.5 91,
+                          28 110.5 60,
+                          28 57.5 91,
+                          28 54.5 91,
+                          28 110.5 70,
+                          25 57.5 91,
+                          28 57.5 91,
+                          28 110.5 70,
+                          28 57.5 91,
+                          28 110.5 60,
+                          -28 57.5 91,
+                          -28 54.5 91,
+                          28 54.5 91,
+                          28 54.5 60,
+                          28 54.5 91,
+                          -28 54.5 91,
+                          -25 57.5 91,
+                          -28 57.5 91,
+                          28 54.5 91,
+                          25 57.5 91,
+                          -25 57.5 91,
+                          28 54.5 91,
+                          28 110.5 60,
+                          28 54.5 91,
+                          28 54.5 60,
+                          -28 54.5 60,
+                          -28 54.5 91,
+                          -28 57.5 91,
+                          28 54.5 60,
+                          -28 54.5 91,
+                          -28 54.5 60,
+                          -25 110.5 70,
+                          -28 57.5 91,
+                          -25 57.5 91,
+                          -28 110.5 70,
+                          -28 54.5 60,
+                          -28 57.5 91,
+                          -25 110.5 70,
+                          -28 110.5 70,
+                          -28 57.5 91,
+                          -25 57.5 60,
+                          -25 57.5 91,
+                          25 57.5 91,
+                          -25 110.5 60,
+                          -25 57.5 91,
+                          -25 57.5 60,
+                          -25 110.5 70,
+                          -25 57.5 91,
+                          -25 110.5 60,
+                          -25 57.5 60,
+                          25 57.5 91,
+                          25 57.5 60,
+                          25 110.5 70,
+                          25 57.5 60,
+                          25 57.5 91,
+                          28 110.5 70,
+                          25 110.5 70,
+                          25 57.5 91,
+                          28 54.5 60,
+                          25 57.5 60,
+                          25 110.5 60,
+                          25 110.5 70,
+                          25 110.5 60,
+                          25 57.5 60,
+                          28 110.5 60,
+                          28 54.5 60,
+                          25 110.5 60,
+                          25 110.5 70,
+                          28 110.5 60,
+                          25 110.5 60,
+                          28 54.5 60,
+                          -25 57.5 60,
+                          25 57.5 60,
+                          -28 110.5 60,
+                          -25 110.5 60,
+                          -25 57.5 60,
+                          -28 54.5 60,
+                          -28 110.5 60,
+                          -25 57.5 60,
+                          28 54.5 60,
+                          -28 54.5 60,
+                          -25 57.5 60,
+                          -28 110.5 70,
+                          -25 110.5 60,
+                          -28 110.5 60,
+                          -25 110.5 70,
+                          -25 110.5 60,
+                          -28 110.5 70,
+                          -28 110.5 70,
+                          -28 110.5 60,
+                          -28 54.5 60,
+                          28 110.5 70,
+                          28 110.5 60,
+                          25 110.5 70 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 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,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 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,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -0.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.707107 -0.707107 0,
+                          0.707107 -0.707107 0,
+                          0.707107 -0.707107 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          0.707107 -0.707107 0,
+                          0.707107 -0.707107 0,
+                          0.707107 -0.707107 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.707107 0.707107 0,
+                          -0.707107 0.707107 0,
+                          -0.707107 0.707107 0,
+                          6.12303e-17 1 0,
+                          -0.707107 0.707107 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.707107 0.707107 0,
+                          0.707107 0.707107 0,
+                          1 0 0,
+                          0.707107 0.707107 0,
+                          6.12303e-17 1 0,
+                          0.707107 0.707107 0,
+                          1 0 0,
+                          1 0 0,
+                          0.707107 -0.707107 0,
+                          0.707107 0.707107 0,
+                          1 0 0,
+                          1 0 0,
+                          0.707107 -0.707107 0,
+                          0.707107 -0.707107 0,
+                          6.12303e-17 -1 0,
+                          1 0 0,
+                          0.707107 -0.707107 0,
+                          0.707107 -0.707107 0,
+                          -1.83691e-16 -1 0,
+                          -1.83691e-16 -1 0,
+                          -0.707107 -0.707107 0,
+                          0.707107 -0.707107 0,
+                          6.12303e-17 -1 0,
+                          6.12303e-17 -1 0,
+                          -0.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          -1 5.6655e-16 0,
+                          -1.83691e-16 -1 0,
+                          -0.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          -1 1.22461e-16 0,
+                          -1 5.6655e-16 0,
+                          -0.707107 0.707107 0,
+                          -0.707107 -0.707107 0,
+                          -1 5.6655e-16 0,
+                          -1 1.22461e-16 0,
+                          -1 1.22461e-16 0,
+                          -0.707107 0.707107 0,
+                          -0.707107 0.707107 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,
+                          -4.32964e-17 -0.707107 0.707107,
+                          0 -6.12303e-17 1,
+                          0 -6.12303e-17 1,
+                          -4.32964e-17 -0.707107 0.707107,
+                          -4.32964e-17 -0.707107 0.707107,
+                          0 -6.12303e-17 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.707107 0.707107 0,
+                          0.707107 0.707107 0,
+                          0.707107 0.707107 0,
+                          6.12303e-17 1 0,
+                          0.707107 0.707107 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.707107 0.707107 0,
+                          -0.707107 0.707107 0,
+                          -1 3.44505e-16 0,
+                          -0.707107 0.707107 0,
+                          6.12303e-17 1 0,
+                          -0.707107 0.707107 0,
+                          -1 1.22461e-16 0,
+                          -1 3.44505e-16 0,
+                          -0.707107 -0.707107 0,
+                          -0.707107 0.707107 0,
+                          -1 3.44505e-16 0,
+                          -1 1.22461e-16 0,
+                          -0.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          -1.83691e-16 -1 0,
+                          -1 1.22461e-16 0,
+                          -0.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          6.12303e-17 -1 0,
+                          6.12303e-17 -1 0,
+                          0.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          -1.83691e-16 -1 0,
+                          -1.83691e-16 -1 0,
+                          0.707107 -0.707107 0,
+                          0.707107 -0.707107 0,
+                          1 -2.22045e-16 0,
+                          6.12303e-17 -1 0,
+                          0.707107 -0.707107 0,
+                          0.707107 -0.707107 0,
+                          1 0 0,
+                          1 -2.22045e-16 0,
+                          0.707107 0.707107 0,
+                          0.707107 -0.707107 0,
+                          1 -2.22045e-16 0,
+                          1 0 0,
+                          1 0 0,
+                          0.707107 0.707107 0,
+                          0.707107 0.707107 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -4.32964e-17 -0.707107 0.707107,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -4.32964e-17 -0.707107 0.707107,
+                          -6.12303e-17 -1 0,
+                          -4.32964e-17 -0.707107 0.707107,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 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 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -13 117.726 32,
+                          -13 117.726 58,
+                          13 117.726 58,
+                          13 117.726 74,
+                          13 117.726 58,
+                          -13 117.726 58,
+                          13 117.726 32,
+                          -13 117.726 32,
+                          13 117.726 58,
+                          13 110.726 37,
+                          13 117.726 32,
+                          13 117.726 58,
+                          13 110.726 58,
+                          13 110.726 37,
+                          13 117.726 58,
+                          13 117.726 74,
+                          13 110.726 58,
+                          13 117.726 58,
+                          -13 110.726 58,
+                          -13 117.726 58,
+                          -13 117.726 32,
+                          -13 110.726 74,
+                          -13 117.726 58,
+                          -13 110.726 58,
+                          -13 117.726 74,
+                          -13 117.726 58,
+                          -13 110.726 74,
+                          13 117.726 74,
+                          -13 117.726 58,
+                          -13 117.726 74,
+                          -13 117.726 23,
+                          -13 117.726 32,
+                          13 117.726 32,
+                          -13 105.726 32,
+                          -13 117.726 32,
+                          -13 117.726 23,
+                          -13 109.261 33.4647,
+                          -13 117.726 32,
+                          -13 105.726 32,
+                          -13 110.726 58,
+                          -13 117.726 32,
+                          -13 110.726 37,
+                          -13 109.261 33.4647,
+                          -13 110.726 37,
+                          -13 117.726 32,
+                          -13 117.726 23,
+                          13 117.726 32,
+                          13 117.726 23,
+                          13 77.7256 23,
+                          13 117.726 23,
+                          13 117.726 32,
+                          13 105.726 32,
+                          13 77.7256 23,
+                          13 117.726 32,
+                          13 109.261 33.4647,
+                          13 105.726 32,
+                          13 117.726 32,
+                          13 109.261 33.4647,
+                          13 117.726 32,
+                          13 110.726 37,
+                          7.77865 92.5031 23,
+                          -13 117.726 23,
+                          13 117.726 23,
+                          10.9998 84.7256 23,
+                          13 117.726 23,
+                          13 77.7256 23,
+                          10.9998 84.7256 23,
+                          7.77865 92.5031 23,
+                          13 117.726 23,
+                          -10.9998 84.7256 23,
+                          -13 77.7256 23,
+                          -13 117.726 23,
+                          -13 77.7256 32,
+                          -13 117.726 23,
+                          -13 77.7256 23,
+                          -7.77865 92.5031 23,
+                          -10.9998 84.7256 23,
+                          -13 117.726 23,
+                          3.95328e-13 95.7256 23,
+                          -7.77865 92.5031 23,
+                          -13 117.726 23,
+                          7.77865 92.5031 23,
+                          3.95328e-13 95.7256 23,
+                          -13 117.726 23,
+                          -13 105.726 32,
+                          -13 117.726 23,
+                          -13 77.7256 32,
+                          3.9398e-13 73.7256 23,
+                          -7 71.7256 23,
+                          -13 77.7256 23,
+                          -7 71.7256 32,
+                          -13 77.7256 23,
+                          -7 71.7256 23,
+                          -7.77865 76.948 23,
+                          3.9398e-13 73.7256 23,
+                          -13 77.7256 23,
+                          -10.9998 84.7256 23,
+                          -7.77865 76.948 23,
+                          -13 77.7256 23,
+                          -13 77.7256 32,
+                          -13 77.7256 23,
+                          -7 71.7256 32,
+                          3.9398e-13 73.7256 23,
+                          7 71.7256 23,
+                          -7 71.7256 23,
+                          -7 71.7256 32,
+                          -7 71.7256 23,
+                          7 71.7256 23,
+                          7.77865 76.948 23,
+                          13 77.7256 23,
+                          7 71.7256 23,
+                          13 77.7256 32,
+                          7 71.7256 23,
+                          13 77.7256 23,
+                          7.77865 76.948 23,
+                          7 71.7256 23,
+                          3.9398e-13 73.7256 23,
+                          7 71.7256 32,
+                          -7 71.7256 32,
+                          7 71.7256 23,
+                          13 77.7256 32,
+                          7 71.7256 32,
+                          7 71.7256 23,
+                          7.77865 76.948 23,
+                          10.9998 84.7256 23,
+                          13 77.7256 23,
+                          13 105.726 32,
+                          13 77.7256 32,
+                          13 77.7256 23,
+                          3.9398e-13 73.7256 30,
+                          3.9398e-13 73.7256 23,
+                          -7.77865 76.948 23,
+                          7.77801 76.9476 30,
+                          7.77865 76.948 23,
+                          3.9398e-13 73.7256 23,
+                          7.77801 76.9476 30,
+                          3.9398e-13 73.7256 23,
+                          3.9398e-13 73.7256 30,
+                          -7.77801 76.9476 30,
+                          -7.77865 76.948 23,
+                          -10.9998 84.7256 23,
+                          -7.77801 76.9476 30,
+                          3.9398e-13 73.7256 30,
+                          -7.77865 76.948 23,
+                          -11 84.7256 30,
+                          -10.9998 84.7256 23,
+                          -7.77865 92.5031 23,
+                          -7.77801 76.9476 30,
+                          -10.9998 84.7256 23,
+                          -11 84.7256 30,
+                          -7.77801 92.5036 30,
+                          -7.77865 92.5031 23,
+                          3.95328e-13 95.7256 23,
+                          -11 84.7256 30,
+                          -7.77865 92.5031 23,
+                          -7.77801 92.5036 30,
+                          3.95328e-13 95.7256 30,
+                          3.95328e-13 95.7256 23,
+                          7.77865 92.5031 23,
+                          -7.77801 92.5036 30,
+                          3.95328e-13 95.7256 23,
+                          3.95328e-13 95.7256 30,
+                          7.77801 92.5036 30,
+                          7.77865 92.5031 23,
+                          10.9998 84.7256 23,
+                          3.95328e-13 95.7256 30,
+                          7.77865 92.5031 23,
+                          7.77801 92.5036 30,
+                          11 84.7256 30,
+                          10.9998 84.7256 23,
+                          7.77865 76.948 23,
+                          7.77801 92.5036 30,
+                          10.9998 84.7256 23,
+                          11 84.7256 30,
+                          11 84.7256 30,
+                          7.77865 76.948 23,
+                          7.77801 76.9476 30,
+                          13 77.7256 32,
+                          -7 71.7256 32,
+                          7 71.7256 32,
+                          3.94103e-13 75.7256 32,
+                          -7 71.7256 32,
+                          13 77.7256 32,
+                          3.94103e-13 75.7256 32,
+                          -13 77.7256 32,
+                          -7 71.7256 32,
+                          9 84.7256 32,
+                          13 77.7256 32,
+                          13 105.726 32,
+                          6.36382 78.3618 32,
+                          3.94103e-13 75.7256 32,
+                          13 77.7256 32,
+                          9 84.7256 32,
+                          6.36382 78.3618 32,
+                          13 77.7256 32,
+                          -6.36382 91.0894 32,
+                          -13 105.726 32,
+                          -13 77.7256 32,
+                          -6.36382 78.3618 32,
+                          -13 77.7256 32,
+                          3.94103e-13 75.7256 32,
+                          -9 84.7256 32,
+                          -6.36382 91.0894 32,
+                          -13 77.7256 32,
+                          -6.36382 78.3618 32,
+                          -9 84.7256 32,
+                          -13 77.7256 32,
+                          -6.36382 91.0894 32,
+                          13 105.726 32,
+                          -13 105.726 32,
+                          13 109.261 33.4647,
+                          -13 105.726 32,
+                          13 105.726 32,
+                          13 109.261 33.4647,
+                          -13 109.261 33.4647,
+                          -13 105.726 32,
+                          6.36382 91.0894 32,
+                          9 84.7256 32,
+                          13 105.726 32,
+                          3.95205e-13 93.7256 32,
+                          6.36382 91.0894 32,
+                          13 105.726 32,
+                          -6.36382 91.0894 32,
+                          3.95205e-13 93.7256 32,
+                          13 105.726 32,
+                          3.94103e-13 75.7256 30,
+                          3.94103e-13 75.7256 32,
+                          6.36382 78.3618 32,
+                          -6.36323 78.3611 30,
+                          -6.36382 78.3618 32,
+                          3.94103e-13 75.7256 32,
+                          -6.36323 78.3611 30,
+                          3.94103e-13 75.7256 32,
+                          3.94103e-13 75.7256 30,
+                          6.36323 78.3611 30,
+                          6.36382 78.3618 32,
+                          9 84.7256 32,
+                          6.36323 78.3611 30,
+                          3.94103e-13 75.7256 30,
+                          6.36382 78.3618 32,
+                          8.99975 84.7256 30,
+                          9 84.7256 32,
+                          6.36382 91.0894 32,
+                          6.36323 78.3611 30,
+                          9 84.7256 32,
+                          8.99975 84.7256 30,
+                          6.36323 91.0901 30,
+                          6.36382 91.0894 32,
+                          3.95205e-13 93.7256 32,
+                          8.99975 84.7256 30,
+                          6.36382 91.0894 32,
+                          6.36323 91.0901 30,
+                          3.95205e-13 93.7256 30,
+                          3.95205e-13 93.7256 32,
+                          -6.36382 91.0894 32,
+                          6.36323 91.0901 30,
+                          3.95205e-13 93.7256 32,
+                          3.95205e-13 93.7256 30,
+                          -6.36323 91.0901 30,
+                          -6.36382 91.0894 32,
+                          -9 84.7256 32,
+                          3.95205e-13 93.7256 30,
+                          -6.36382 91.0894 32,
+                          -6.36323 91.0901 30,
+                          -8.99975 84.7256 30,
+                          -9 84.7256 32,
+                          -6.36382 78.3618 32,
+                          -6.36323 91.0901 30,
+                          -9 84.7256 32,
+                          -8.99975 84.7256 30,
+                          -8.99975 84.7256 30,
+                          -6.36382 78.3618 32,
+                          -6.36323 78.3611 30,
+                          -13 110.726 58,
+                          -13 110.726 37,
+                          13 110.726 37,
+                          -13 109.261 33.4647,
+                          13 110.726 37,
+                          -13 110.726 37,
+                          13 110.726 58,
+                          -13 110.726 58,
+                          13 110.726 37,
+                          13 109.261 33.4647,
+                          13 110.726 37,
+                          -13 109.261 33.4647,
+                          -13 110.726 74,
+                          -13 110.726 58,
+                          13 110.726 58,
+                          -13 110.726 74,
+                          13 110.726 58,
+                          13 110.726 74,
+                          13 117.726 74,
+                          13 110.726 74,
+                          13 110.726 58,
+                          6.36323 78.3611 30,
+                          7.77801 76.9476 30,
+                          3.9398e-13 73.7256 30,
+                          3.94103e-13 75.7256 30,
+                          3.9398e-13 73.7256 30,
+                          -7.77801 76.9476 30,
+                          6.36323 78.3611 30,
+                          3.9398e-13 73.7256 30,
+                          3.94103e-13 75.7256 30,
+                          8.99975 84.7256 30,
+                          11 84.7256 30,
+                          7.77801 76.9476 30,
+                          6.36323 78.3611 30,
+                          8.99975 84.7256 30,
+                          7.77801 76.9476 30,
+                          8.99975 84.7256 30,
+                          7.77801 92.5036 30,
+                          11 84.7256 30,
+                          3.95205e-13 93.7256 30,
+                          3.95328e-13 95.7256 30,
+                          7.77801 92.5036 30,
+                          6.36323 91.0901 30,
+                          3.95205e-13 93.7256 30,
+                          7.77801 92.5036 30,
+                          8.99975 84.7256 30,
+                          6.36323 91.0901 30,
+                          7.77801 92.5036 30,
+                          -6.36323 91.0901 30,
+                          -7.77801 92.5036 30,
+                          3.95328e-13 95.7256 30,
+                          3.95205e-13 93.7256 30,
+                          -6.36323 91.0901 30,
+                          3.95328e-13 95.7256 30,
+                          -8.99975 84.7256 30,
+                          -11 84.7256 30,
+                          -7.77801 92.5036 30,
+                          -6.36323 91.0901 30,
+                          -8.99975 84.7256 30,
+                          -7.77801 92.5036 30,
+                          -8.99975 84.7256 30,
+                          -7.77801 76.9476 30,
+                          -11 84.7256 30,
+                          -6.36323 78.3611 30,
+                          3.94103e-13 75.7256 30,
+                          -7.77801 76.9476 30,
+                          -8.99975 84.7256 30,
+                          -6.36323 78.3611 30,
+                          -7.77801 76.9476 30,
+                          -13 117.726 74,
+                          -13 110.726 74,
+                          13 110.726 74,
+                          13 117.726 74,
+                          -13 117.726 74,
+                          13 110.726 74 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 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,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          5.07016e-17 0.828048 0.560657,
+                          5.07016e-17 0.828048 0.560657,
+                          5.07016e-17 0.828048 0.560657,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          5.07016e-17 0.828048 0.560657,
+                          5.07016e-17 0.828048 0.560657,
+                          5.07016e-17 0.828048 0.560657,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 117 -39.5 41,
+                          117 -49.5 41,
+                          117 -49.5 7,
+                          107 -49.5 7,
+                          117 -49.5 7,
+                          117 -49.5 41,
+                          117 -23.25 17,
+                          117 -39.5 41,
+                          117 -49.5 7,
+                          117 -23.25 7,
+                          117 -23.25 17,
+                          117 -49.5 7,
+                          107 -23.25 7,
+                          117 -23.25 7,
+                          117 -49.5 7,
+                          107 -23.25 7,
+                          117 -49.5 7,
+                          107 -49.5 7,
+                          107 -39.5 41,
+                          117 -49.5 41,
+                          117 -39.5 41,
+                          107 -49.5 41,
+                          107 -49.5 7,
+                          117 -49.5 41,
+                          107 -49.5 41,
+                          117 -49.5 41,
+                          107 -39.5 41,
+                          107 -39.5 41,
+                          117 -39.5 41,
+                          117 -23.25 17,
+                          107 -23.25 7,
+                          117 -23.25 17,
+                          117 -23.25 7,
+                          107 -23.25 17,
+                          117 -23.25 17,
+                          107 -23.25 7,
+                          107 -39.5 41,
+                          117 -23.25 17,
+                          107 -23.25 17,
+                          107 -49.5 41,
+                          107 -23.25 7,
+                          107 -49.5 7,
+                          107 -49.5 41,
+                          107 -23.25 17,
+                          107 -23.25 7,
+                          107 -49.5 41,
+                          107 -39.5 41,
+                          107 -23.25 17 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 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,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -5.07016e-17 -0.828048 0.560657,
+                          -5.07016e-17 -0.828048 0.560657,
+                          -5.07016e-17 -0.828048 0.560657,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -5.07016e-17 -0.828048 0.560657,
+                          -5.07016e-17 -0.828048 0.560657,
+                          -5.07016e-17 -0.828048 0.560657,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 107 39.5 41,
+                          107 49.5 41,
+                          107 49.5 7,
+                          117 49.5 7,
+                          107 49.5 7,
+                          107 49.5 41,
+                          107 23.25 17,
+                          107 39.5 41,
+                          107 49.5 7,
+                          107 23.25 7,
+                          107 23.25 17,
+                          107 49.5 7,
+                          117 23.25 7,
+                          107 23.25 7,
+                          107 49.5 7,
+                          117 23.25 7,
+                          107 49.5 7,
+                          117 49.5 7,
+                          117 39.5 41,
+                          107 49.5 41,
+                          107 39.5 41,
+                          117 49.5 41,
+                          117 49.5 7,
+                          107 49.5 41,
+                          117 49.5 41,
+                          107 49.5 41,
+                          117 39.5 41,
+                          117 39.5 41,
+                          107 39.5 41,
+                          107 23.25 17,
+                          117 23.25 7,
+                          107 23.25 17,
+                          107 23.25 7,
+                          117 23.25 17,
+                          107 23.25 17,
+                          117 23.25 7,
+                          117 39.5 41,
+                          107 23.25 17,
+                          117 23.25 17,
+                          117 49.5 41,
+                          117 23.25 7,
+                          117 49.5 7,
+                          117 49.5 41,
+                          117 23.25 17,
+                          117 23.25 7,
+                          117 49.5 41,
+                          117 39.5 41,
+                          117 23.25 17 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          1 -6.12303e-17 -3.44505e-16,
+                          1 -6.12303e-17 -3.44505e-16,
+                          0.5 -3.06152e-17 0.866025,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          0.5 -3.06152e-17 -0.866025,
+                          0.5 -3.06152e-17 -0.866025,
+                          1 -6.12303e-17 -3.44505e-16,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          1 -6.12303e-17 -3.44505e-16,
+                          0.5 -3.06152e-17 -0.866025,
+                          1 -6.12303e-17 -3.44505e-16,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          0.5 -3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          1 -6.12303e-17 -3.44505e-16,
+                          0.5 -3.06152e-17 0.866025,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -0.5 3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          -1 6.12303e-17 4.66966e-16,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -0.5 3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -0.5 3.06152e-17 -0.866025,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -0.5 3.06152e-17 0.866025,
+                          -1 6.12303e-17 4.66966e-16,
+                          -1 6.12303e-17 4.66966e-16,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -0.5 3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          0.5 -3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          -1 6.12303e-17 2.22045e-16,
+                          -0.5 3.06152e-17 -0.866025,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          0.5 -3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          0.5 -3.06152e-17 -0.866025,
+                          1 -6.12303e-17 -3.44505e-16,
+                          1 -6.12303e-17 -3.44505e-16,
+                          0.5 -3.06152e-17 -0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          1 -6.12303e-17 -3.44505e-16,
+                          0.5 -3.06152e-17 0.866025,
+                          1 -6.12303e-17 -3.44505e-16,
+                          1 -6.12303e-17 -3.44505e-16,
+                          0.5 -3.06152e-17 -0.866025,
+                          0.5 -3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          0.5 -3.06152e-17 -0.866025,
+                          1 -6.12303e-17 -3.44505e-16,
+                          0.5 -3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          -1 6.12303e-17 2.22045e-16,
+                          0.5 -3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          -1 6.12303e-17 4.66966e-16,
+                          -1 6.12303e-17 4.66966e-16,
+                          -0.5 3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -0.5 3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          -1 6.12303e-17 4.66966e-16,
+                          -0.5 3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          1 -6.12303e-17 -3.44505e-16,
+                          1 -6.12303e-17 -3.44505e-16,
+                          0.5 -3.06152e-17 -0.866025,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          0.5 -3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          1 -6.12303e-17 -3.44505e-16,
+                          0.5 -3.06152e-17 0.866025,
+                          1 -6.12303e-17 -3.44505e-16,
+                          1 -6.12303e-17 -3.44505e-16,
+                          0.5 -3.06152e-17 -0.866025,
+                          0.5 -3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          0.5 -3.06152e-17 -0.866025,
+                          1 -6.12303e-17 -3.44505e-16,
+                          0.5 -3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          -1 6.12303e-17 2.22045e-16,
+                          0.5 -3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -1 6.12303e-17 4.66966e-16,
+                          -1 6.12303e-17 4.66966e-16,
+                          -0.5 3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -0.5 3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          -1 6.12303e-17 4.66966e-16,
+                          -0.5 3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          1 -6.12303e-17 -3.44505e-16,
+                          1 -6.12303e-17 -3.44505e-16,
+                          0.5 -3.06152e-17 0.866025,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.5 -3.06152e-17 -0.866025,
+                          0.5 -3.06152e-17 -0.866025,
+                          1 -6.12303e-17 -3.44505e-16,
+                          1 -6.12303e-17 -3.44505e-16,
+                          0.5 -3.06152e-17 -0.866025,
+                          1 -6.12303e-17 -3.44505e-16,
+                          0.5 -3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          1 -6.12303e-17 -3.44505e-16,
+                          0.5 -3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          -1 6.12303e-17 4.66966e-16,
+                          0.5 -3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -0.5 3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          -1 6.12303e-17 4.66966e-16,
+                          -1 6.12303e-17 4.66966e-16,
+                          -0.5 3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          0.5 -3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          -1 6.12303e-17 2.22045e-16,
+                          -0.5 3.06152e-17 -0.866025,
+                          0.5 -3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          0.5 -3.06152e-17 -0.866025,
+                          0.5 -3.06152e-17 -0.866025,
+                          0.5 -3.06152e-17 -0.866025,
+                          1 -6.12303e-17 -3.44505e-16,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          1 -6.12303e-17 -3.44505e-16,
+                          0.5 -3.06152e-17 -0.866025,
+                          1 -6.12303e-17 -3.44505e-16,
+                          0.5 -3.06152e-17 0.866025,
+                          1 -6.12303e-17 -3.44505e-16,
+                          1 -6.12303e-17 -3.44505e-16,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.5 3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          0.5 -3.06152e-17 -0.866025,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.5 -3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          0.5 -3.06152e-17 -0.866025,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -0.5 3.06152e-17 -0.866025,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.5 3.06152e-17 -0.866025,
+                          -1 6.12303e-17 2.22045e-16,
+                          -0.5 3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          -1 6.12303e-17 4.66966e-16,
+                          -1 6.12303e-17 4.66966e-16,
+                          -0.5 3.06152e-17 0.866025,
+                          -1 6.12303e-17 4.66966e-16,
+                          -0.5 3.06152e-17 0.866025,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.5 -3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          1 -6.12303e-17 -3.44505e-16,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.5 3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.5 -3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 114.499 -14.75 16.3303,
+                          113.5 -14.75 14.5981,
+                          115 -14.75 12,
+                          115 -23.75 12,
+                          115 -14.75 12,
+                          113.5 -14.75 14.5981,
+                          117 -14.75 12,
+                          115 -14.75 12,
+                          113.5 -14.75 9.40192,
+                          113.5 -23.75 9.40192,
+                          113.5 -14.75 9.40192,
+                          115 -14.75 12,
+                          114.499 -14.75 16.3303,
+                          115 -14.75 12,
+                          117 -14.75 12,
+                          115 -23.75 12,
+                          113.5 -23.75 9.40192,
+                          115 -14.75 12,
+                          114.499 -14.75 16.3303,
+                          110.5 -14.75 14.5981,
+                          113.5 -14.75 14.5981,
+                          113.5 -23.75 14.5981,
+                          113.5 -14.75 14.5981,
+                          110.5 -14.75 14.5981,
+                          113.5 -23.75 14.5981,
+                          115 -23.75 12,
+                          113.5 -14.75 14.5981,
+                          107 -14.75 12,
+                          109 -14.75 12,
+                          110.5 -14.75 14.5981,
+                          110.5 -23.75 14.5981,
+                          110.5 -14.75 14.5981,
+                          109 -14.75 12,
+                          109.501 -14.75 16.3303,
+                          107 -14.75 12,
+                          110.5 -14.75 14.5981,
+                          114.499 -14.75 16.3303,
+                          109.501 -14.75 16.3303,
+                          110.5 -14.75 14.5981,
+                          110.5 -23.75 14.5981,
+                          113.5 -23.75 14.5981,
+                          110.5 -14.75 14.5981,
+                          109.501 -14.75 7.66973,
+                          110.5 -14.75 9.40192,
+                          109 -14.75 12,
+                          109 -23.75 12,
+                          109 -14.75 12,
+                          110.5 -14.75 9.40192,
+                          107 -14.75 12,
+                          109.501 -14.75 7.66973,
+                          109 -14.75 12,
+                          110.5 -23.75 14.5981,
+                          109 -14.75 12,
+                          109 -23.75 12,
+                          109.501 -14.75 7.66973,
+                          113.5 -14.75 9.40192,
+                          110.5 -14.75 9.40192,
+                          110.5 -23.75 9.40192,
+                          110.5 -14.75 9.40192,
+                          113.5 -14.75 9.40192,
+                          110.5 -23.75 9.40192,
+                          109 -23.75 12,
+                          110.5 -14.75 9.40192,
+                          114.499 -14.75 7.66973,
+                          117 -14.75 12,
+                          113.5 -14.75 9.40192,
+                          109.501 -14.75 7.66973,
+                          114.499 -14.75 7.66973,
+                          113.5 -14.75 9.40192,
+                          113.5 -23.75 9.40192,
+                          110.5 -23.75 9.40192,
+                          113.5 -14.75 9.40192,
+                          117 14.75 12,
+                          117 -14.75 12,
+                          114.499 -14.75 7.66973,
+                          114.499 14.75 16.3303,
+                          114.499 -14.75 16.3303,
+                          117 -14.75 12,
+                          114.499 14.75 16.3303,
+                          117 -14.75 12,
+                          117 14.75 12,
+                          114.499 14.75 7.66973,
+                          114.499 -14.75 7.66973,
+                          109.501 -14.75 7.66973,
+                          114.499 14.75 7.66973,
+                          117 14.75 12,
+                          114.499 -14.75 7.66973,
+                          109.501 14.75 7.66973,
+                          109.501 -14.75 7.66973,
+                          107 -14.75 12,
+                          114.499 14.75 7.66973,
+                          109.501 -14.75 7.66973,
+                          109.501 14.75 7.66973,
+                          107 14.75 12,
+                          107 -14.75 12,
+                          109.501 -14.75 16.3303,
+                          109.501 14.75 7.66973,
+                          107 -14.75 12,
+                          107 14.75 12,
+                          109.501 14.75 16.3303,
+                          109.501 -14.75 16.3303,
+                          114.499 -14.75 16.3303,
+                          107 14.75 12,
+                          109.501 -14.75 16.3303,
+                          109.501 14.75 16.3303,
+                          109.501 14.75 16.3303,
+                          114.499 -14.75 16.3303,
+                          114.499 14.75 16.3303,
+                          109.5 -23.75 12,
+                          109 -23.75 12,
+                          110.5 -23.75 9.40192,
+                          110.75 -23.75 14.1651,
+                          110.5 -23.75 14.5981,
+                          109 -23.75 12,
+                          109.5 -23.75 12,
+                          110.75 -23.75 14.1651,
+                          109 -23.75 12,
+                          113.25 -23.75 9.83494,
+                          110.5 -23.75 9.40192,
+                          113.5 -23.75 9.40192,
+                          110.75 -23.75 9.83494,
+                          109.5 -23.75 12,
+                          110.5 -23.75 9.40192,
+                          113.25 -23.75 9.83494,
+                          110.75 -23.75 9.83494,
+                          110.5 -23.75 9.40192,
+                          113.25 -23.75 9.83494,
+                          113.5 -23.75 9.40192,
+                          115 -23.75 12,
+                          114.5 -23.75 12,
+                          115 -23.75 12,
+                          113.5 -23.75 14.5981,
+                          113.25 -23.75 9.83494,
+                          115 -23.75 12,
+                          114.5 -23.75 12,
+                          110.75 -40 9.83494,
+                          113.25 -40 9.83494,
+                          114.5 -40 12,
+                          114.5 -23.75 12,
+                          114.5 -40 12,
+                          113.25 -40 9.83494,
+                          109.5 -40 12,
+                          110.75 -40 9.83494,
+                          114.5 -40 12,
+                          113.25 -40 14.1651,
+                          109.5 -40 12,
+                          114.5 -40 12,
+                          113.25 -23.75 14.1651,
+                          113.25 -40 14.1651,
+                          114.5 -40 12,
+                          113.25 -23.75 14.1651,
+                          114.5 -40 12,
+                          114.5 -23.75 12,
+                          113.25 -23.75 9.83494,
+                          113.25 -40 9.83494,
+                          110.75 -40 9.83494,
+                          113.25 -23.75 9.83494,
+                          114.5 -23.75 12,
+                          113.25 -40 9.83494,
+                          110.75 -23.75 9.83494,
+                          110.75 -40 9.83494,
+                          109.5 -40 12,
+                          113.25 -23.75 9.83494,
+                          110.75 -40 9.83494,
+                          110.75 -23.75 9.83494,
+                          113.25 -40 14.1651,
+                          110.75 -40 14.1651,
+                          109.5 -40 12,
+                          109.5 -23.75 12,
+                          109.5 -40 12,
+                          110.75 -40 14.1651,
+                          110.75 -23.75 9.83494,
+                          109.5 -40 12,
+                          109.5 -23.75 12,
+                          110.75 -23.75 14.1651,
+                          110.75 -40 14.1651,
+                          113.25 -40 14.1651,
+                          109.5 -23.75 12,
+                          110.75 -40 14.1651,
+                          110.75 -23.75 14.1651,
+                          110.75 -23.75 14.1651,
+                          113.25 -40 14.1651,
+                          113.25 -23.75 14.1651,
+                          110.75 40 14.1651,
+                          113.25 40 14.1651,
+                          114.5 40 12,
+                          114.5 23.75 12,
+                          114.5 40 12,
+                          113.25 40 14.1651,
+                          109.5 40 12,
+                          110.75 40 14.1651,
+                          114.5 40 12,
+                          113.25 40 9.83494,
+                          109.5 40 12,
+                          114.5 40 12,
+                          113.25 23.75 9.83494,
+                          113.25 40 9.83494,
+                          114.5 40 12,
+                          114.5 23.75 12,
+                          113.25 23.75 9.83494,
+                          114.5 40 12,
+                          113.25 23.75 14.1651,
+                          113.25 40 14.1651,
+                          110.75 40 14.1651,
+                          113.25 23.75 14.1651,
+                          114.5 23.75 12,
+                          113.25 40 14.1651,
+                          110.75 23.75 14.1651,
+                          110.75 40 14.1651,
+                          109.5 40 12,
+                          113.25 23.75 14.1651,
+                          110.75 40 14.1651,
+                          110.75 23.75 14.1651,
+                          113.25 40 9.83494,
+                          110.75 40 9.83494,
+                          109.5 40 12,
+                          109.5 23.75 12,
+                          109.5 40 12,
+                          110.75 40 9.83494,
+                          110.75 23.75 14.1651,
+                          109.5 40 12,
+                          109.5 23.75 12,
+                          110.75 23.75 9.83494,
+                          110.75 40 9.83494,
+                          113.25 40 9.83494,
+                          110.75 23.75 9.83494,
+                          109.5 23.75 12,
+                          110.75 40 9.83494,
+                          113.25 23.75 9.83494,
+                          110.75 23.75 9.83494,
+                          113.25 40 9.83494,
+                          113.5 14.75 9.40192,
+                          113.5 23.75 9.40192,
+                          115 23.75 12,
+                          114.5 23.75 12,
+                          115 23.75 12,
+                          113.5 23.75 9.40192,
+                          115 14.75 12,
+                          113.5 14.75 9.40192,
+                          115 23.75 12,
+                          113.5 23.75 14.5981,
+                          115 14.75 12,
+                          115 23.75 12,
+                          113.25 23.75 14.1651,
+                          113.5 23.75 14.5981,
+                          115 23.75 12,
+                          113.25 23.75 14.1651,
+                          115 23.75 12,
+                          114.5 23.75 12,
+                          110.5 14.75 9.40192,
+                          110.5 23.75 9.40192,
+                          113.5 23.75 9.40192,
+                          110.75 23.75 9.83494,
+                          113.5 23.75 9.40192,
+                          110.5 23.75 9.40192,
+                          113.5 14.75 9.40192,
+                          110.5 14.75 9.40192,
+                          113.5 23.75 9.40192,
+                          113.25 23.75 9.83494,
+                          113.5 23.75 9.40192,
+                          110.75 23.75 9.83494,
+                          114.5 23.75 12,
+                          113.5 23.75 9.40192,
+                          113.25 23.75 9.83494,
+                          109 14.75 12,
+                          109 23.75 12,
+                          110.5 23.75 9.40192,
+                          110.75 23.75 9.83494,
+                          110.5 23.75 9.40192,
+                          109 23.75 12,
+                          110.5 14.75 9.40192,
+                          109 14.75 12,
+                          110.5 23.75 9.40192,
+                          110.5 14.75 14.5981,
+                          109 23.75 12,
+                          109 14.75 12,
+                          110.5 23.75 14.5981,
+                          109 23.75 12,
+                          110.5 14.75 14.5981,
+                          109.5 23.75 12,
+                          109 23.75 12,
+                          110.5 23.75 14.5981,
+                          110.75 23.75 9.83494,
+                          109 23.75 12,
+                          109.5 23.75 12,
+                          107 14.75 12,
+                          109 14.75 12,
+                          110.5 14.75 9.40192,
+                          109.501 14.75 16.3303,
+                          110.5 14.75 14.5981,
+                          109 14.75 12,
+                          107 14.75 12,
+                          109.501 14.75 16.3303,
+                          109 14.75 12,
+                          114.499 14.75 7.66973,
+                          110.5 14.75 9.40192,
+                          113.5 14.75 9.40192,
+                          109.501 14.75 7.66973,
+                          107 14.75 12,
+                          110.5 14.75 9.40192,
+                          114.499 14.75 7.66973,
+                          109.501 14.75 7.66973,
+                          110.5 14.75 9.40192,
+                          114.499 14.75 7.66973,
+                          113.5 14.75 9.40192,
+                          115 14.75 12,
+                          117 14.75 12,
+                          115 14.75 12,
+                          113.5 14.75 14.5981,
+                          113.5 23.75 14.5981,
+                          113.5 14.75 14.5981,
+                          115 14.75 12,
+                          114.499 14.75 7.66973,
+                          115 14.75 12,
+                          117 14.75 12,
+                          109.501 14.75 16.3303,
+                          113.5 14.75 14.5981,
+                          110.5 14.75 14.5981,
+                          110.5 23.75 14.5981,
+                          110.5 14.75 14.5981,
+                          113.5 14.75 14.5981,
+                          114.499 14.75 16.3303,
+                          117 14.75 12,
+                          113.5 14.75 14.5981,
+                          109.501 14.75 16.3303,
+                          114.499 14.75 16.3303,
+                          113.5 14.75 14.5981,
+                          113.5 23.75 14.5981,
+                          110.5 23.75 14.5981,
+                          113.5 14.75 14.5981,
+                          110.75 -23.75 14.1651,
+                          113.5 -23.75 14.5981,
+                          110.5 -23.75 14.5981,
+                          113.25 -23.75 14.1651,
+                          114.5 -23.75 12,
+                          113.5 -23.75 14.5981,
+                          110.75 -23.75 14.1651,
+                          113.25 -23.75 14.1651,
+                          113.5 -23.75 14.5981,
+                          113.25 23.75 14.1651,
+                          110.5 23.75 14.5981,
+                          113.5 23.75 14.5981,
+                          110.75 23.75 14.1651,
+                          109.5 23.75 12,
+                          110.5 23.75 14.5981,
+                          113.25 23.75 14.1651,
+                          110.75 23.75 14.1651,
+                          110.5 23.75 14.5981 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -4.05736e-16 0 -1,
+                          -4.05736e-16 0 -1,
+                          -0.707107 4.32964e-17 -0.707107,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          -4.05736e-16 0 -1,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.707107 -4.32964e-17 -0.707107,
+                          -4.05736e-16 0 -1,
+                          -4.05736e-16 0 -1,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -1 6.12303e-17 3.44505e-16,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -4.05736e-16 0 -1,
+                          -0.707107 4.32964e-17 -0.707107,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -1 6.12303e-17 3.44505e-16,
+                          -1 6.12303e-17 3.44505e-16,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -1 6.12303e-17 3.44505e-16,
+                          -1 6.12303e-17 3.44505e-16,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          2.83275e-16 0 1,
+                          -1 6.12303e-17 3.44505e-16,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          5.28196e-16 0 1,
+                          5.28196e-16 0 1,
+                          0.707107 -4.32964e-17 0.707107,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.707107 4.32964e-17 0.707107,
+                          2.83275e-16 0 1,
+                          2.83275e-16 0 1,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          1 -6.12303e-17 -4.66966e-16,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          5.28196e-16 0 1,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          1 -6.12303e-17 -4.66966e-16,
+                          1 -6.12303e-17 -4.66966e-16,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          1 -6.12303e-17 -4.66966e-16,
+                          1 -6.12303e-17 -4.66966e-16,
+                          1 -6.12303e-17 -4.66966e-16,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -4.05736e-16 0 -1,
+                          -4.05736e-16 0 -1,
+                          -0.707107 4.32964e-17 -0.707107,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          -4.05736e-16 0 -1,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.707107 -4.32964e-17 -0.707107,
+                          -4.05736e-16 0 -1,
+                          -4.05736e-16 0 -1,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -1 6.12303e-17 2.12086e-15,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -4.05736e-16 0 -1,
+                          -0.707107 4.32964e-17 -0.707107,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -1 6.12303e-17 2.12086e-15,
+                          -1 6.12303e-17 2.12086e-15,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -1 6.12303e-17 2.12086e-15,
+                          -1 6.12303e-17 2.12086e-15,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          2.83275e-16 0 1,
+                          -1 6.12303e-17 2.12086e-15,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          5.28196e-16 0 1,
+                          5.28196e-16 0 1,
+                          0.707107 -4.32964e-17 0.707107,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.707107 4.32964e-17 0.707107,
+                          2.83275e-16 0 1,
+                          2.83275e-16 0 1,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          1 -6.12303e-17 -4.66966e-16,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          5.28196e-16 0 1,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          1 -6.12303e-17 -4.66966e-16,
+                          1 -6.12303e-17 -4.66966e-16,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          1 -6.12303e-17 -4.66966e-16,
+                          1 -6.12303e-17 -4.66966e-16,
+                          1 -6.12303e-17 -4.66966e-16,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 121.5 23 107,
+                          115.535 23 106.536,
+                          112 23 108,
+                          112 15 108,
+                          112 23 108,
+                          115.535 23 106.536,
+                          102.5 23 107,
+                          112 23 108,
+                          108.465 23 106.536,
+                          108.465 15 106.536,
+                          108.465 23 106.536,
+                          112 23 108,
+                          108 23 112.5,
+                          121.5 23 107,
+                          112 23 108,
+                          102.5 23 107,
+                          108 23 112.5,
+                          112 23 108,
+                          108.465 15 106.536,
+                          112 23 108,
+                          112 15 108,
+                          121.5 23 99,
+                          117 23 103,
+                          115.535 23 106.536,
+                          115.535 15 106.536,
+                          115.535 23 106.536,
+                          117 23 103,
+                          121.5 23 107,
+                          121.5 23 99,
+                          115.535 23 106.536,
+                          115.535 15 106.536,
+                          112 15 108,
+                          115.535 23 106.536,
+                          121.5 23 99,
+                          115.535 23 99.4638,
+                          117 23 103,
+                          117 15 103,
+                          117 23 103,
+                          115.535 23 99.4638,
+                          115.535 15 106.536,
+                          117 23 103,
+                          117 15 103,
+                          121.5 23 99,
+                          112 23 98,
+                          115.535 23 99.4638,
+                          115.535 15 99.4638,
+                          115.535 23 99.4638,
+                          112 23 98,
+                          117 15 103,
+                          115.535 23 99.4638,
+                          115.535 15 99.4638,
+                          102.5 23 99,
+                          108.465 23 99.4638,
+                          112 23 98,
+                          112 15 98,
+                          112 23 98,
+                          108.465 23 99.4638,
+                          121.5 23 99,
+                          116 23 93.5,
+                          112 23 98,
+                          102.5 23 99,
+                          112 23 98,
+                          116 23 93.5,
+                          115.535 15 99.4638,
+                          112 23 98,
+                          112 15 98,
+                          102.5 23 107,
+                          107 23 103,
+                          108.465 23 99.4638,
+                          108.465 15 99.4638,
+                          108.465 23 99.4638,
+                          107 23 103,
+                          102.5 23 99,
+                          102.5 23 107,
+                          108.465 23 99.4638,
+                          112 15 98,
+                          108.465 23 99.4638,
+                          108.465 15 99.4638,
+                          102.5 23 107,
+                          108.465 23 106.536,
+                          107 23 103,
+                          107 15 103,
+                          107 23 103,
+                          108.465 23 106.536,
+                          108.465 15 99.4638,
+                          107 23 103,
+                          107 15 103,
+                          107 15 103,
+                          108.465 23 106.536,
+                          108.465 15 106.536,
+                          121.5 23 16,
+                          115.535 23 15.5362,
+                          112 23 17,
+                          112 15 17,
+                          112 23 17,
+                          115.535 23 15.5362,
+                          102.5 23 16,
+                          112 23 17,
+                          108.465 23 15.5362,
+                          108.465 15 15.5362,
+                          108.465 23 15.5362,
+                          112 23 17,
+                          108 23 21.5,
+                          121.5 23 16,
+                          112 23 17,
+                          102.5 23 16,
+                          108 23 21.5,
+                          112 23 17,
+                          108.465 15 15.5362,
+                          112 23 17,
+                          112 15 17,
+                          121.5 23 8,
+                          117 23 12,
+                          115.535 23 15.5362,
+                          115.535 15 15.5362,
+                          115.535 23 15.5362,
+                          117 23 12,
+                          121.5 23 16,
+                          121.5 23 8,
+                          115.535 23 15.5362,
+                          115.535 15 15.5362,
+                          112 15 17,
+                          115.535 23 15.5362,
+                          121.5 23 8,
+                          115.535 23 8.46384,
+                          117 23 12,
+                          117 15 12,
+                          117 23 12,
+                          115.535 23 8.46384,
+                          115.535 15 15.5362,
+                          117 23 12,
+                          117 15 12,
+                          121.5 23 8,
+                          112 23 7,
+                          115.535 23 8.46384,
+                          115.535 15 8.46384,
+                          115.535 23 8.46384,
+                          112 23 7,
+                          117 15 12,
+                          115.535 23 8.46384,
+                          115.535 15 8.46384,
+                          102.5 23 8,
+                          108.465 23 8.46384,
+                          112 23 7,
+                          112 15 7,
+                          112 23 7,
+                          108.465 23 8.46384,
+                          121.5 23 8,
+                          116 23 2.5,
+                          112 23 7,
+                          102.5 23 8,
+                          112 23 7,
+                          116 23 2.5,
+                          115.535 15 8.46384,
+                          112 23 7,
+                          112 15 7,
+                          102.5 23 16,
+                          107 23 12,
+                          108.465 23 8.46384,
+                          108.465 15 8.46384,
+                          108.465 23 8.46384,
+                          107 23 12,
+                          102.5 23 8,
+                          102.5 23 16,
+                          108.465 23 8.46384,
+                          112 15 7,
+                          108.465 23 8.46384,
+                          108.465 15 8.46384,
+                          102.5 23 16,
+                          108.465 23 15.5362,
+                          107 23 12,
+                          107 15 12,
+                          107 23 12,
+                          108.465 23 15.5362,
+                          108.465 15 8.46384,
+                          107 23 12,
+                          107 15 12,
+                          107 15 12,
+                          108.465 23 15.5362,
+                          108.465 15 15.5362,
+                          121.5 15 8,
+                          116 23 2.5,
+                          121.5 23 8,
+                          108 23 2.5,
+                          102.5 23 8,
+                          116 23 2.5,
+                          116 15 2.5,
+                          108 23 2.5,
+                          116 23 2.5,
+                          121.5 15 8,
+                          116 15 2.5,
+                          116 23 2.5,
+                          121.5 15 16,
+                          121.5 23 8,
+                          121.5 23 16,
+                          121.5 15 8,
+                          121.5 23 8,
+                          121.5 15 16,
+                          108 23 21.5,
+                          116 23 21.5,
+                          121.5 23 16,
+                          116 15 21.5,
+                          121.5 23 16,
+                          116 23 21.5,
+                          121.5 15 16,
+                          121.5 23 16,
+                          116 15 21.5,
+                          108 23 93.5,
+                          116 23 93.5,
+                          116 23 21.5,
+                          116 15 21.5,
+                          116 23 21.5,
+                          116 23 93.5,
+                          108 23 21.5,
+                          108 23 93.5,
+                          116 23 21.5,
+                          121.5 15 99,
+                          116 23 93.5,
+                          121.5 23 99,
+                          108 23 93.5,
+                          102.5 23 99,
+                          116 23 93.5,
+                          116 15 93.5,
+                          116 23 93.5,
+                          121.5 15 99,
+                          116 15 21.5,
+                          116 23 93.5,
+                          116 15 93.5,
+                          121.5 15 107,
+                          121.5 23 99,
+                          121.5 23 107,
+                          121.5 15 99,
+                          121.5 23 99,
+                          121.5 15 107,
+                          108 23 112.5,
+                          116 23 112.5,
+                          121.5 23 107,
+                          116 15 112.5,
+                          121.5 23 107,
+                          116 23 112.5,
+                          121.5 15 107,
+                          121.5 23 107,
+                          116 15 112.5,
+                          108 15 112.5,
+                          116 23 112.5,
+                          108 23 112.5,
+                          116 15 112.5,
+                          116 23 112.5,
+                          108 15 112.5,
+                          102.5 15 107,
+                          108 23 112.5,
+                          102.5 23 107,
+                          108 15 112.5,
+                          108 23 112.5,
+                          102.5 15 107,
+                          102.5 15 99,
+                          102.5 23 107,
+                          102.5 23 99,
+                          102.5 15 107,
+                          102.5 23 107,
+                          102.5 15 99,
+                          108 15 93.5,
+                          102.5 23 99,
+                          108 23 93.5,
+                          102.5 15 99,
+                          102.5 23 99,
+                          108 15 93.5,
+                          108 15 93.5,
+                          108 23 93.5,
+                          108 23 21.5,
+                          102.5 15 16,
+                          108 23 21.5,
+                          102.5 23 16,
+                          108 15 21.5,
+                          108 23 21.5,
+                          102.5 15 16,
+                          108 15 93.5,
+                          108 23 21.5,
+                          108 15 21.5,
+                          102.5 15 8,
+                          102.5 23 16,
+                          102.5 23 8,
+                          102.5 15 16,
+                          102.5 23 16,
+                          102.5 15 8,
+                          108 15 2.5,
+                          102.5 23 8,
+                          108 23 2.5,
+                          102.5 15 8,
+                          102.5 23 8,
+                          108 15 2.5,
+                          108 15 2.5,
+                          108 23 2.5,
+                          116 15 2.5,
+                          102.5 15 107,
+                          108.465 15 106.536,
+                          112 15 108,
+                          121.5 15 107,
+                          112 15 108,
+                          115.535 15 106.536,
+                          116 15 112.5,
+                          102.5 15 107,
+                          112 15 108,
+                          121.5 15 107,
+                          116 15 112.5,
+                          112 15 108,
+                          102.5 15 99,
+                          107 15 103,
+                          108.465 15 106.536,
+                          102.5 15 107,
+                          102.5 15 99,
+                          108.465 15 106.536,
+                          102.5 15 99,
+                          108.465 15 99.4638,
+                          107 15 103,
+                          102.5 15 99,
+                          112 15 98,
+                          108.465 15 99.4638,
+                          121.5 15 99,
+                          115.535 15 99.4638,
+                          112 15 98,
+                          102.5 15 99,
+                          108 15 93.5,
+                          112 15 98,
+                          121.5 15 99,
+                          112 15 98,
+                          108 15 93.5,
+                          121.5 15 107,
+                          117 15 103,
+                          115.535 15 99.4638,
+                          121.5 15 99,
+                          121.5 15 107,
+                          115.535 15 99.4638,
+                          121.5 15 107,
+                          115.535 15 106.536,
+                          117 15 103,
+                          102.5 15 16,
+                          108.465 15 15.5362,
+                          112 15 17,
+                          121.5 15 16,
+                          112 15 17,
+                          115.535 15 15.5362,
+                          116 15 21.5,
+                          102.5 15 16,
+                          112 15 17,
+                          121.5 15 16,
+                          116 15 21.5,
+                          112 15 17,
+                          102.5 15 8,
+                          107 15 12,
+                          108.465 15 15.5362,
+                          102.5 15 16,
+                          102.5 15 8,
+                          108.465 15 15.5362,
+                          102.5 15 8,
+                          108.465 15 8.46384,
+                          107 15 12,
+                          102.5 15 8,
+                          112 15 7,
+                          108.465 15 8.46384,
+                          121.5 15 8,
+                          115.535 15 8.46384,
+                          112 15 7,
+                          102.5 15 8,
+                          108 15 2.5,
+                          112 15 7,
+                          121.5 15 8,
+                          112 15 7,
+                          108 15 2.5,
+                          121.5 15 16,
+                          117 15 12,
+                          115.535 15 8.46384,
+                          121.5 15 8,
+                          121.5 15 16,
+                          115.535 15 8.46384,
+                          121.5 15 16,
+                          115.535 15 15.5362,
+                          117 15 12,
+                          121.5 15 8,
+                          108 15 2.5,
+                          116 15 2.5,
+                          116 15 21.5,
+                          108 15 21.5,
+                          102.5 15 16,
+                          116 15 93.5,
+                          108 15 93.5,
+                          108 15 21.5,
+                          116 15 21.5,
+                          116 15 93.5,
+                          108 15 21.5,
+                          116 15 93.5,
+                          121.5 15 99,
+                          108 15 93.5,
+                          116 15 112.5,
+                          108 15 112.5,
+                          102.5 15 107 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -4.05736e-16 0 -1,
+                          -4.05736e-16 0 -1,
+                          -0.707107 4.32964e-17 -0.707107,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          -4.05736e-16 0 -1,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.707107 -4.32964e-17 -0.707107,
+                          -4.05736e-16 0 -1,
+                          -4.05736e-16 0 -1,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -1 6.12303e-17 3.44505e-16,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -4.05736e-16 0 -1,
+                          -0.707107 4.32964e-17 -0.707107,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -1 6.12303e-17 3.44505e-16,
+                          -1 6.12303e-17 3.44505e-16,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -1 6.12303e-17 3.44505e-16,
+                          -1 6.12303e-17 3.44505e-16,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          2.83275e-16 0 1,
+                          -1 6.12303e-17 3.44505e-16,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          5.28196e-16 0 1,
+                          5.28196e-16 0 1,
+                          0.707107 -4.32964e-17 0.707107,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.707107 4.32964e-17 0.707107,
+                          2.83275e-16 0 1,
+                          2.83275e-16 0 1,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          1 -6.12303e-17 -4.66966e-16,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          5.28196e-16 0 1,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          1 -6.12303e-17 -4.66966e-16,
+                          1 -6.12303e-17 -4.66966e-16,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          1 -6.12303e-17 -4.66966e-16,
+                          1 -6.12303e-17 -4.66966e-16,
+                          1 -6.12303e-17 -4.66966e-16,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -4.05736e-16 0 -1,
+                          -4.05736e-16 0 -1,
+                          -0.707107 4.32964e-17 -0.707107,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          -4.05736e-16 0 -1,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.707107 -4.32964e-17 -0.707107,
+                          -4.05736e-16 0 -1,
+                          -4.05736e-16 0 -1,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -1 6.12303e-17 2.12086e-15,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -4.05736e-16 0 -1,
+                          -0.707107 4.32964e-17 -0.707107,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -1 6.12303e-17 2.12086e-15,
+                          -1 6.12303e-17 2.12086e-15,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -1 6.12303e-17 2.12086e-15,
+                          -1 6.12303e-17 2.12086e-15,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          2.83275e-16 0 1,
+                          -1 6.12303e-17 2.12086e-15,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          5.28196e-16 0 1,
+                          5.28196e-16 0 1,
+                          0.707107 -4.32964e-17 0.707107,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.707107 4.32964e-17 0.707107,
+                          2.83275e-16 0 1,
+                          2.83275e-16 0 1,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          1 -6.12303e-17 -4.66966e-16,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          5.28196e-16 0 1,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          1 -6.12303e-17 -4.66966e-16,
+                          1 -6.12303e-17 -4.66966e-16,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          1 -6.12303e-17 -4.66966e-16,
+                          1 -6.12303e-17 -4.66966e-16,
+                          1 -6.12303e-17 -4.66966e-16,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          0.707107 -4.32964e-17 -0.707107,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          0.707107 -4.32964e-17 0.707107,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          -0.707107 4.32964e-17 0.707107,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -0.707107 4.32964e-17 -0.707107,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 121.5 -15 107,
+                          115.535 -15 106.536,
+                          112 -15 108,
+                          112 -23 108,
+                          112 -15 108,
+                          115.535 -15 106.536,
+                          102.5 -15 107,
+                          112 -15 108,
+                          108.465 -15 106.536,
+                          108.465 -23 106.536,
+                          108.465 -15 106.536,
+                          112 -15 108,
+                          108 -15 112.5,
+                          121.5 -15 107,
+                          112 -15 108,
+                          102.5 -15 107,
+                          108 -15 112.5,
+                          112 -15 108,
+                          108.465 -23 106.536,
+                          112 -15 108,
+                          112 -23 108,
+                          121.5 -15 99,
+                          117 -15 103,
+                          115.535 -15 106.536,
+                          115.535 -23 106.536,
+                          115.535 -15 106.536,
+                          117 -15 103,
+                          121.5 -15 107,
+                          121.5 -15 99,
+                          115.535 -15 106.536,
+                          115.535 -23 106.536,
+                          112 -23 108,
+                          115.535 -15 106.536,
+                          121.5 -15 99,
+                          115.535 -15 99.4638,
+                          117 -15 103,
+                          117 -23 103,
+                          117 -15 103,
+                          115.535 -15 99.4638,
+                          115.535 -23 106.536,
+                          117 -15 103,
+                          117 -23 103,
+                          121.5 -15 99,
+                          112 -15 98,
+                          115.535 -15 99.4638,
+                          115.535 -23 99.4638,
+                          115.535 -15 99.4638,
+                          112 -15 98,
+                          117 -23 103,
+                          115.535 -15 99.4638,
+                          115.535 -23 99.4638,
+                          102.5 -15 99,
+                          108.465 -15 99.4638,
+                          112 -15 98,
+                          112 -23 98,
+                          112 -15 98,
+                          108.465 -15 99.4638,
+                          121.5 -15 99,
+                          116 -15 93.5,
+                          112 -15 98,
+                          102.5 -15 99,
+                          112 -15 98,
+                          116 -15 93.5,
+                          115.535 -23 99.4638,
+                          112 -15 98,
+                          112 -23 98,
+                          102.5 -15 107,
+                          107 -15 103,
+                          108.465 -15 99.4638,
+                          108.465 -23 99.4638,
+                          108.465 -15 99.4638,
+                          107 -15 103,
+                          102.5 -15 99,
+                          102.5 -15 107,
+                          108.465 -15 99.4638,
+                          112 -23 98,
+                          108.465 -15 99.4638,
+                          108.465 -23 99.4638,
+                          102.5 -15 107,
+                          108.465 -15 106.536,
+                          107 -15 103,
+                          107 -23 103,
+                          107 -15 103,
+                          108.465 -15 106.536,
+                          108.465 -23 99.4638,
+                          107 -15 103,
+                          107 -23 103,
+                          107 -23 103,
+                          108.465 -15 106.536,
+                          108.465 -23 106.536,
+                          121.5 -15 16,
+                          115.535 -15 15.5362,
+                          112 -15 17,
+                          112 -23 17,
+                          112 -15 17,
+                          115.535 -15 15.5362,
+                          102.5 -15 16,
+                          112 -15 17,
+                          108.465 -15 15.5362,
+                          108.465 -23 15.5362,
+                          108.465 -15 15.5362,
+                          112 -15 17,
+                          108 -15 21.5,
+                          121.5 -15 16,
+                          112 -15 17,
+                          102.5 -15 16,
+                          108 -15 21.5,
+                          112 -15 17,
+                          108.465 -23 15.5362,
+                          112 -15 17,
+                          112 -23 17,
+                          121.5 -15 8,
+                          117 -15 12,
+                          115.535 -15 15.5362,
+                          115.535 -23 15.5362,
+                          115.535 -15 15.5362,
+                          117 -15 12,
+                          121.5 -15 16,
+                          121.5 -15 8,
+                          115.535 -15 15.5362,
+                          115.535 -23 15.5362,
+                          112 -23 17,
+                          115.535 -15 15.5362,
+                          121.5 -15 8,
+                          115.535 -15 8.46384,
+                          117 -15 12,
+                          117 -23 12,
+                          117 -15 12,
+                          115.535 -15 8.46384,
+                          115.535 -23 15.5362,
+                          117 -15 12,
+                          117 -23 12,
+                          121.5 -15 8,
+                          112 -15 7,
+                          115.535 -15 8.46384,
+                          115.535 -23 8.46384,
+                          115.535 -15 8.46384,
+                          112 -15 7,
+                          117 -23 12,
+                          115.535 -15 8.46384,
+                          115.535 -23 8.46384,
+                          102.5 -15 8,
+                          108.465 -15 8.46384,
+                          112 -15 7,
+                          112 -23 7,
+                          112 -15 7,
+                          108.465 -15 8.46384,
+                          121.5 -15 8,
+                          116 -15 2.5,
+                          112 -15 7,
+                          102.5 -15 8,
+                          112 -15 7,
+                          116 -15 2.5,
+                          115.535 -23 8.46384,
+                          112 -15 7,
+                          112 -23 7,
+                          102.5 -15 16,
+                          107 -15 12,
+                          108.465 -15 8.46384,
+                          108.465 -23 8.46384,
+                          108.465 -15 8.46384,
+                          107 -15 12,
+                          102.5 -15 8,
+                          102.5 -15 16,
+                          108.465 -15 8.46384,
+                          112 -23 7,
+                          108.465 -15 8.46384,
+                          108.465 -23 8.46384,
+                          102.5 -15 16,
+                          108.465 -15 15.5362,
+                          107 -15 12,
+                          107 -23 12,
+                          107 -15 12,
+                          108.465 -15 15.5362,
+                          108.465 -23 8.46384,
+                          107 -15 12,
+                          107 -23 12,
+                          107 -23 12,
+                          108.465 -15 15.5362,
+                          108.465 -23 15.5362,
+                          121.5 -23 8,
+                          116 -15 2.5,
+                          121.5 -15 8,
+                          108 -15 2.5,
+                          102.5 -15 8,
+                          116 -15 2.5,
+                          116 -23 2.5,
+                          108 -15 2.5,
+                          116 -15 2.5,
+                          121.5 -23 8,
+                          116 -23 2.5,
+                          116 -15 2.5,
+                          121.5 -23 16,
+                          121.5 -15 8,
+                          121.5 -15 16,
+                          121.5 -23 8,
+                          121.5 -15 8,
+                          121.5 -23 16,
+                          108 -15 21.5,
+                          116 -15 21.5,
+                          121.5 -15 16,
+                          116 -23 21.5,
+                          121.5 -15 16,
+                          116 -15 21.5,
+                          121.5 -23 16,
+                          121.5 -15 16,
+                          116 -23 21.5,
+                          108 -15 93.5,
+                          116 -15 93.5,
+                          116 -15 21.5,
+                          116 -23 21.5,
+                          116 -15 21.5,
+                          116 -15 93.5,
+                          108 -15 21.5,
+                          108 -15 93.5,
+                          116 -15 21.5,
+                          121.5 -23 99,
+                          116 -15 93.5,
+                          121.5 -15 99,
+                          108 -15 93.5,
+                          102.5 -15 99,
+                          116 -15 93.5,
+                          116 -23 93.5,
+                          116 -15 93.5,
+                          121.5 -23 99,
+                          116 -23 21.5,
+                          116 -15 93.5,
+                          116 -23 93.5,
+                          121.5 -23 107,
+                          121.5 -15 99,
+                          121.5 -15 107,
+                          121.5 -23 99,
+                          121.5 -15 99,
+                          121.5 -23 107,
+                          108 -15 112.5,
+                          116 -15 112.5,
+                          121.5 -15 107,
+                          116 -23 112.5,
+                          121.5 -15 107,
+                          116 -15 112.5,
+                          121.5 -23 107,
+                          121.5 -15 107,
+                          116 -23 112.5,
+                          108 -23 112.5,
+                          116 -15 112.5,
+                          108 -15 112.5,
+                          116 -23 112.5,
+                          116 -15 112.5,
+                          108 -23 112.5,
+                          102.5 -23 107,
+                          108 -15 112.5,
+                          102.5 -15 107,
+                          108 -23 112.5,
+                          108 -15 112.5,
+                          102.5 -23 107,
+                          102.5 -23 99,
+                          102.5 -15 107,
+                          102.5 -15 99,
+                          102.5 -23 107,
+                          102.5 -15 107,
+                          102.5 -23 99,
+                          108 -23 93.5,
+                          102.5 -15 99,
+                          108 -15 93.5,
+                          102.5 -23 99,
+                          102.5 -15 99,
+                          108 -23 93.5,
+                          108 -23 93.5,
+                          108 -15 93.5,
+                          108 -15 21.5,
+                          102.5 -23 16,
+                          108 -15 21.5,
+                          102.5 -15 16,
+                          108 -23 21.5,
+                          108 -15 21.5,
+                          102.5 -23 16,
+                          108 -23 93.5,
+                          108 -15 21.5,
+                          108 -23 21.5,
+                          102.5 -23 8,
+                          102.5 -15 16,
+                          102.5 -15 8,
+                          102.5 -23 16,
+                          102.5 -15 16,
+                          102.5 -23 8,
+                          108 -23 2.5,
+                          102.5 -15 8,
+                          108 -15 2.5,
+                          102.5 -23 8,
+                          102.5 -15 8,
+                          108 -23 2.5,
+                          108 -23 2.5,
+                          108 -15 2.5,
+                          116 -23 2.5,
+                          102.5 -23 107,
+                          108.465 -23 106.536,
+                          112 -23 108,
+                          121.5 -23 107,
+                          112 -23 108,
+                          115.535 -23 106.536,
+                          116 -23 112.5,
+                          102.5 -23 107,
+                          112 -23 108,
+                          121.5 -23 107,
+                          116 -23 112.5,
+                          112 -23 108,
+                          102.5 -23 99,
+                          107 -23 103,
+                          108.465 -23 106.536,
+                          102.5 -23 107,
+                          102.5 -23 99,
+                          108.465 -23 106.536,
+                          102.5 -23 99,
+                          108.465 -23 99.4638,
+                          107 -23 103,
+                          102.5 -23 99,
+                          112 -23 98,
+                          108.465 -23 99.4638,
+                          121.5 -23 99,
+                          115.535 -23 99.4638,
+                          112 -23 98,
+                          102.5 -23 99,
+                          108 -23 93.5,
+                          112 -23 98,
+                          121.5 -23 99,
+                          112 -23 98,
+                          108 -23 93.5,
+                          121.5 -23 107,
+                          117 -23 103,
+                          115.535 -23 99.4638,
+                          121.5 -23 99,
+                          121.5 -23 107,
+                          115.535 -23 99.4638,
+                          121.5 -23 107,
+                          115.535 -23 106.536,
+                          117 -23 103,
+                          102.5 -23 16,
+                          108.465 -23 15.5362,
+                          112 -23 17,
+                          121.5 -23 16,
+                          112 -23 17,
+                          115.535 -23 15.5362,
+                          116 -23 21.5,
+                          102.5 -23 16,
+                          112 -23 17,
+                          121.5 -23 16,
+                          116 -23 21.5,
+                          112 -23 17,
+                          102.5 -23 8,
+                          107 -23 12,
+                          108.465 -23 15.5362,
+                          102.5 -23 16,
+                          102.5 -23 8,
+                          108.465 -23 15.5362,
+                          102.5 -23 8,
+                          108.465 -23 8.46384,
+                          107 -23 12,
+                          102.5 -23 8,
+                          112 -23 7,
+                          108.465 -23 8.46384,
+                          121.5 -23 8,
+                          115.535 -23 8.46384,
+                          112 -23 7,
+                          102.5 -23 8,
+                          108 -23 2.5,
+                          112 -23 7,
+                          121.5 -23 8,
+                          112 -23 7,
+                          108 -23 2.5,
+                          121.5 -23 16,
+                          117 -23 12,
+                          115.535 -23 8.46384,
+                          121.5 -23 8,
+                          121.5 -23 16,
+                          115.535 -23 8.46384,
+                          121.5 -23 16,
+                          115.535 -23 15.5362,
+                          117 -23 12,
+                          121.5 -23 8,
+                          108 -23 2.5,
+                          116 -23 2.5,
+                          116 -23 21.5,
+                          108 -23 21.5,
+                          102.5 -23 16,
+                          116 -23 93.5,
+                          108 -23 93.5,
+                          108 -23 21.5,
+                          116 -23 21.5,
+                          116 -23 93.5,
+                          108 -23 21.5,
+                          116 -23 93.5,
+                          121.5 -23 99,
+                          108 -23 93.5,
+                          116 -23 112.5,
+                          108 -23 112.5,
+                          102.5 -23 107 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -3.06152e-16 -1 0,
+                          -3.06152e-16 -1 0,
+                          -0.707107 -0.707107 1.57009e-16,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          0.707107 -0.707107 -1.57009e-16,
+                          0.707107 -0.707107 -1.57009e-16,
+                          -6.12303e-17 -1 0,
+                          0.707107 -0.707107 -1.57009e-16,
+                          -6.12303e-17 -1 0,
+                          -1.83691e-16 -1 0,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -0.707107 -0.707107 1.57009e-16,
+                          -0.707107 -0.707107 1.57009e-16,
+                          -1 2.44921e-16 2.22045e-16,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -0.707107 -0.707107 1.57009e-16,
+                          -3.06152e-16 -1 0,
+                          -0.707107 -0.707107 1.57009e-16,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -1 2.44921e-16 2.22045e-16,
+                          -1 2.44921e-16 2.22045e-16,
+                          -0.707107 0.707107 1.57009e-16,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -1 2.44921e-16 2.22045e-16,
+                          -0.707107 -0.707107 1.57009e-16,
+                          -1 2.44921e-16 2.22045e-16,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -0.707107 0.707107 1.57009e-16,
+                          -0.707107 0.707107 1.57009e-16,
+                          1.83691e-16 1 0,
+                          -0.707107 0.707107 1.57009e-16,
+                          -1 2.44921e-16 2.22045e-16,
+                          -0.707107 0.707107 1.57009e-16,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          0.707107 0.707107 -1.57009e-16,
+                          -0.707107 0.707107 1.57009e-16,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          0.707107 0.707107 -1.57009e-16,
+                          0.707107 0.707107 -1.57009e-16,
+                          1 -1.22461e-16 -2.22045e-16,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          0.707107 0.707107 -1.57009e-16,
+                          1.83691e-16 1 0,
+                          0.707107 0.707107 -1.57009e-16,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          1 -5.6655e-16 -2.22045e-16,
+                          1 -1.22461e-16 -2.22045e-16,
+                          0.707107 -0.707107 -1.57009e-16,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          1 -5.6655e-16 -2.22045e-16,
+                          0.707107 0.707107 -1.57009e-16,
+                          1 -1.22461e-16 -2.22045e-16,
+                          0.707107 -0.707107 -1.57009e-16,
+                          1 -5.6655e-16 -2.22045e-16,
+                          0.707107 -0.707107 -1.57009e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -9.9584e-17 0 -1,
+                          -9.9584e-17 0 -1,
+                          0.866025 -5.3027e-17 -0.5,
+                          -0.866025 5.3027e-17 -0.5,
+                          -0.866025 5.3027e-17 -0.5,
+                          -9.9584e-17 0 -1,
+                          -0.866025 5.3027e-17 -0.5,
+                          -9.9584e-17 0 -1,
+                          -9.9584e-17 0 -1,
+                          0.866025 -5.3027e-17 -0.5,
+                          0.866025 -5.3027e-17 -0.5,
+                          0.866025 -5.3027e-17 0.5,
+                          0.866025 -5.3027e-17 -0.5,
+                          -9.9584e-17 0 -1,
+                          0.866025 -5.3027e-17 -0.5,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          0.866025 -5.3027e-17 0.5,
+                          0.866025 -5.3027e-17 0.5,
+                          2.22045e-16 0 1,
+                          0.866025 -5.3027e-17 -0.5,
+                          0.866025 -5.3027e-17 0.5,
+                          0.866025 -5.3027e-17 0.5,
+                          -2.28767e-17 0 1,
+                          -2.28767e-17 0 1,
+                          -0.866025 5.3027e-17 0.5,
+                          0.866025 -5.3027e-17 0.5,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          -0.866025 5.3027e-17 0.5,
+                          -0.866025 5.3027e-17 0.5,
+                          -0.866025 5.3027e-17 -0.5,
+                          -2.28767e-17 0 1,
+                          -0.866025 5.3027e-17 0.5,
+                          -0.866025 5.3027e-17 0.5,
+                          -0.866025 5.3027e-17 0.5,
+                          -0.866025 5.3027e-17 -0.5,
+                          -0.866025 5.3027e-17 -0.5,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -9.9584e-17 0 -1,
+                          -9.9584e-17 0 -1,
+                          -0.866025 5.3027e-17 -0.5,
+                          0.866025 -5.3027e-17 -0.5,
+                          0.866025 -5.3027e-17 -0.5,
+                          -9.9584e-17 0 -1,
+                          -9.9584e-17 0 -1,
+                          0.866025 -5.3027e-17 -0.5,
+                          -9.9584e-17 0 -1,
+                          -0.866025 5.3027e-17 -0.5,
+                          -0.866025 5.3027e-17 -0.5,
+                          -0.866025 5.3027e-17 0.5,
+                          -0.866025 5.3027e-17 -0.5,
+                          -9.9584e-17 0 -1,
+                          -0.866025 5.3027e-17 -0.5,
+                          -0.866025 5.3027e-17 0.5,
+                          -0.866025 5.3027e-17 0.5,
+                          -2.28767e-17 0 1,
+                          -0.866025 5.3027e-17 -0.5,
+                          -0.866025 5.3027e-17 0.5,
+                          -0.866025 5.3027e-17 0.5,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          0.866025 -5.3027e-17 0.5,
+                          -0.866025 5.3027e-17 0.5,
+                          -2.28767e-17 0 1,
+                          -2.28767e-17 0 1,
+                          0.866025 -5.3027e-17 0.5,
+                          0.866025 -5.3027e-17 0.5,
+                          0.866025 -5.3027e-17 -0.5,
+                          0.866025 -5.3027e-17 0.5,
+                          2.22045e-16 0 1,
+                          0.866025 -5.3027e-17 0.5,
+                          0.866025 -5.3027e-17 -0.5,
+                          0.866025 -5.3027e-17 0.5,
+                          0.866025 -5.3027e-17 -0.5,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 103.1 15 97.05,
+                          117.404 5.30287 97.05,
+                          112.1 7.5 97.05,
+                          112.1 7.5 109.55,
+                          112.1 7.5 97.05,
+                          117.404 5.30287 97.05,
+                          103.1 15 97.05,
+                          112.1 7.5 97.05,
+                          106.796 5.30287 97.05,
+                          106.797 5.30319 109.55,
+                          106.796 5.30287 97.05,
+                          112.1 7.5 97.05,
+                          106.797 5.30319 109.55,
+                          112.1 7.5 97.05,
+                          112.1 7.5 109.55,
+                          125.1 15 97.05,
+                          119.6 -6.55543e-14 97.05,
+                          117.404 5.30287 97.05,
+                          117.403 5.30319 109.55,
+                          117.404 5.30287 97.05,
+                          119.6 -6.55543e-14 97.05,
+                          125.1 15 97.05,
+                          117.404 5.30287 97.05,
+                          103.1 15 97.05,
+                          117.403 5.30319 109.55,
+                          112.1 7.5 109.55,
+                          117.404 5.30287 97.05,
+                          125.1 -15 97.05,
+                          117.404 -5.30287 97.05,
+                          119.6 -6.55543e-14 97.05,
+                          119.6 -6.41665e-14 109.55,
+                          119.6 -6.55543e-14 97.05,
+                          117.404 -5.30287 97.05,
+                          125.1 15 97.05,
+                          125.1 -15 97.05,
+                          119.6 -6.55543e-14 97.05,
+                          119.6 -6.41665e-14 109.55,
+                          117.403 5.30319 109.55,
+                          119.6 -6.55543e-14 97.05,
+                          125.1 -15 97.05,
+                          112.1 -7.5 97.05,
+                          117.404 -5.30287 97.05,
+                          117.403 -5.30319 109.55,
+                          117.404 -5.30287 97.05,
+                          112.1 -7.5 97.05,
+                          117.403 -5.30319 109.55,
+                          119.6 -6.41665e-14 109.55,
+                          117.404 -5.30287 97.05,
+                          125.1 -15 97.05,
+                          106.796 -5.30287 97.05,
+                          112.1 -7.5 97.05,
+                          112.1 -7.5 109.55,
+                          112.1 -7.5 97.05,
+                          106.796 -5.30287 97.05,
+                          117.403 -5.30319 109.55,
+                          112.1 -7.5 97.05,
+                          112.1 -7.5 109.55,
+                          103.1 -15 97.05,
+                          104.6 -6.2804e-14 97.05,
+                          106.796 -5.30287 97.05,
+                          106.797 -5.30319 109.55,
+                          106.796 -5.30287 97.05,
+                          104.6 -6.2804e-14 97.05,
+                          125.1 -15 97.05,
+                          103.1 -15 97.05,
+                          106.796 -5.30287 97.05,
+                          106.797 -5.30319 109.55,
+                          112.1 -7.5 109.55,
+                          106.796 -5.30287 97.05,
+                          103.1 15 97.05,
+                          106.796 5.30287 97.05,
+                          104.6 -6.2804e-14 97.05,
+                          104.6 -6.32481e-14 109.55,
+                          104.6 -6.2804e-14 97.05,
+                          106.796 5.30287 97.05,
+                          103.1 -15 97.05,
+                          103.1 15 97.05,
+                          104.6 -6.2804e-14 97.05,
+                          104.6 -6.32481e-14 109.55,
+                          106.797 -5.30319 109.55,
+                          104.6 -6.2804e-14 97.05,
+                          106.797 5.30319 109.55,
+                          104.6 -6.32481e-14 109.55,
+                          106.796 5.30287 97.05,
+                          103.1 15 109.55,
+                          103.1 15 97.05,
+                          103.1 -15 97.05,
+                          112.1 15 100.05,
+                          125.1 15 97.05,
+                          103.1 15 97.05,
+                          109.502 15 104.55,
+                          103.1 15 97.05,
+                          103.1 15 109.55,
+                          109.502 15 101.55,
+                          112.1 15 100.05,
+                          103.1 15 97.05,
+                          109.502 15 104.55,
+                          109.502 15 101.55,
+                          103.1 15 97.05,
+                          112.1 -15 100.05,
+                          103.1 -15 97.05,
+                          125.1 -15 97.05,
+                          103.1 -15 109.55,
+                          103.1 15 109.55,
+                          103.1 -15 97.05,
+                          109.502 -15 101.55,
+                          103.1 -15 109.55,
+                          103.1 -15 97.05,
+                          109.502 -15 101.55,
+                          103.1 -15 97.05,
+                          112.1 -15 100.05,
+                          125.1 -15 109.55,
+                          125.1 -15 97.05,
+                          125.1 15 97.05,
+                          114.698 -15 101.55,
+                          112.1 -15 100.05,
+                          125.1 -15 97.05,
+                          114.698 -15 104.55,
+                          114.698 -15 101.55,
+                          125.1 -15 97.05,
+                          125.1 -15 109.55,
+                          114.698 -15 104.55,
+                          125.1 -15 97.05,
+                          125.1 15 109.55,
+                          125.1 -15 109.55,
+                          125.1 15 97.05,
+                          114.698 15 101.55,
+                          125.1 15 109.55,
+                          125.1 15 97.05,
+                          114.698 15 101.55,
+                          125.1 15 97.05,
+                          112.1 15 100.05,
+                          103.1 -15 109.55,
+                          117.403 -5.30319 109.55,
+                          112.1 -7.5 109.55,
+                          103.1 -15 109.55,
+                          112.1 -7.5 109.55,
+                          106.797 -5.30319 109.55,
+                          125.1 15 109.55,
+                          112.1 7.5 109.55,
+                          117.403 5.30319 109.55,
+                          125.1 15 109.55,
+                          106.797 5.30319 109.55,
+                          112.1 7.5 109.55,
+                          125.1 15 109.55,
+                          117.403 5.30319 109.55,
+                          119.6 -6.41665e-14 109.55,
+                          125.1 -15 109.55,
+                          119.6 -6.41665e-14 109.55,
+                          117.403 -5.30319 109.55,
+                          125.1 15 109.55,
+                          119.6 -6.41665e-14 109.55,
+                          125.1 -15 109.55,
+                          125.1 -15 109.55,
+                          117.403 -5.30319 109.55,
+                          103.1 -15 109.55,
+                          103.1 -15 109.55,
+                          106.797 -5.30319 109.55,
+                          104.6 -6.32481e-14 109.55,
+                          103.1 15 109.55,
+                          104.6 -6.32481e-14 109.55,
+                          106.797 5.30319 109.55,
+                          103.1 -15 109.55,
+                          104.6 -6.32481e-14 109.55,
+                          103.1 15 109.55,
+                          125.1 15 109.55,
+                          103.1 15 109.55,
+                          106.797 5.30319 109.55,
+                          112.1 15 106.05,
+                          103.1 15 109.55,
+                          125.1 15 109.55,
+                          112.1 15 106.05,
+                          109.502 15 104.55,
+                          103.1 15 109.55,
+                          109.502 -15 104.55,
+                          112.1 -15 106.05,
+                          103.1 -15 109.55,
+                          125.1 -15 109.55,
+                          103.1 -15 109.55,
+                          112.1 -15 106.05,
+                          109.502 -15 101.55,
+                          109.502 -15 104.55,
+                          103.1 -15 109.55,
+                          112.1 -26 100.05,
+                          112.1 -15 100.05,
+                          114.698 -15 101.55,
+                          109.502 -26 101.55,
+                          109.502 -15 101.55,
+                          112.1 -15 100.05,
+                          109.502 -26 101.55,
+                          112.1 -15 100.05,
+                          112.1 -26 100.05,
+                          114.698 -26 101.55,
+                          114.698 -15 101.55,
+                          114.698 -15 104.55,
+                          114.698 -26 101.55,
+                          112.1 -26 100.05,
+                          114.698 -15 101.55,
+                          125.1 -15 109.55,
+                          112.1 -15 106.05,
+                          114.698 -15 104.55,
+                          114.698 -26 104.55,
+                          114.698 -15 104.55,
+                          112.1 -15 106.05,
+                          114.698 -26 101.55,
+                          114.698 -15 104.55,
+                          114.698 -26 104.55,
+                          112.1 -26 106.05,
+                          112.1 -15 106.05,
+                          109.502 -15 104.55,
+                          114.698 -26 104.55,
+                          112.1 -15 106.05,
+                          112.1 -26 106.05,
+                          109.502 -26 104.55,
+                          109.502 -15 104.55,
+                          109.502 -15 101.55,
+                          112.1 -26 106.05,
+                          109.502 -15 104.55,
+                          109.502 -26 104.55,
+                          109.502 -26 104.55,
+                          109.502 -15 101.55,
+                          109.502 -26 101.55,
+                          114.698 15 104.55,
+                          112.1 15 106.05,
+                          125.1 15 109.55,
+                          114.698 15 101.55,
+                          114.698 15 104.55,
+                          125.1 15 109.55,
+                          112.1 26 100.05,
+                          112.1 15 100.05,
+                          109.502 15 101.55,
+                          114.698 26 101.55,
+                          114.698 15 101.55,
+                          112.1 15 100.05,
+                          112.1 26 100.05,
+                          114.698 26 101.55,
+                          112.1 15 100.05,
+                          109.502 26 101.55,
+                          109.502 15 101.55,
+                          109.502 15 104.55,
+                          109.502 26 101.55,
+                          112.1 26 100.05,
+                          109.502 15 101.55,
+                          109.502 26 104.55,
+                          109.502 15 104.55,
+                          112.1 15 106.05,
+                          109.502 26 101.55,
+                          109.502 15 104.55,
+                          109.502 26 104.55,
+                          112.1 26 106.05,
+                          112.1 15 106.05,
+                          114.698 15 104.55,
+                          109.502 26 104.55,
+                          112.1 15 106.05,
+                          112.1 26 106.05,
+                          114.698 26 104.55,
+                          114.698 15 104.55,
+                          114.698 15 101.55,
+                          114.698 26 104.55,
+                          112.1 26 106.05,
+                          114.698 15 104.55,
+                          114.698 26 101.55,
+                          114.698 26 104.55,
+                          114.698 15 101.55,
+                          109.502 -26 104.55,
+                          109.502 -26 101.55,
+                          112.1 -26 100.05,
+                          112.1 -26 106.05,
+                          109.502 -26 104.55,
+                          112.1 -26 100.05,
+                          114.698 -26 101.55,
+                          112.1 -26 106.05,
+                          112.1 -26 100.05,
+                          114.698 -26 101.55,
+                          114.698 -26 104.55,
+                          112.1 -26 106.05,
+                          112.1 26 100.05,
+                          112.1 26 106.05,
+                          114.698 26 104.55,
+                          109.502 26 101.55,
+                          112.1 26 106.05,
+                          112.1 26 100.05,
+                          109.502 26 101.55,
+                          109.502 26 104.55,
+                          112.1 26 106.05,
+                          112.1 26 100.05,
+                          114.698 26 104.55,
+                          114.698 26 101.55 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0 0 1
+    }
+    Separator {
+        Normal {
+            vector      [ 6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -0.5 3.06152e-17 -0.866025,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.5 3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          -1 6.12303e-17 4.66966e-16,
+                          -0.5 3.06152e-17 0.866025,
+                          -1 6.12303e-17 4.66966e-16,
+                          -1 6.12303e-17 4.66966e-16,
+                          -0.5 3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          0.5 -3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          -1 6.12303e-17 2.22045e-16,
+                          -0.5 3.06152e-17 -0.866025,
+                          0.5 -3.06152e-17 -0.866025,
+                          0.5 -3.06152e-17 -0.866025,
+                          1 -6.12303e-17 -3.44505e-16,
+                          -0.5 3.06152e-17 -0.866025,
+                          0.5 -3.06152e-17 -0.866025,
+                          0.5 -3.06152e-17 -0.866025,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          1 -6.12303e-17 -3.44505e-16,
+                          1 -6.12303e-17 -3.44505e-16,
+                          0.5 -3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 -0.866025,
+                          1 -6.12303e-17 -3.44505e-16,
+                          1 -6.12303e-17 -3.44505e-16,
+                          0.5 -3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          1 -6.12303e-17 -3.44505e-16,
+                          0.5 -3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 114.6 23 98.72,
+                          109.6 23 98.72,
+                          107.1 23 103.05,
+                          107.1 15 103.05,
+                          107.1 23 103.05,
+                          109.6 23 98.72,
+                          117.1 23 103.05,
+                          114.6 23 98.72,
+                          107.1 23 103.05,
+                          109.6 23 107.38,
+                          117.1 23 103.05,
+                          107.1 23 103.05,
+                          109.6 15 107.38,
+                          109.6 23 107.38,
+                          107.1 23 103.05,
+                          109.6 15 107.38,
+                          107.1 23 103.05,
+                          107.1 15 103.05,
+                          109.6 15 98.72,
+                          109.6 23 98.72,
+                          114.6 23 98.72,
+                          109.6 15 98.72,
+                          107.1 15 103.05,
+                          109.6 23 98.72,
+                          114.6 15 98.72,
+                          114.6 23 98.72,
+                          117.1 23 103.05,
+                          109.6 15 98.72,
+                          114.6 23 98.72,
+                          114.6 15 98.72,
+                          109.6 23 107.38,
+                          114.6 23 107.38,
+                          117.1 23 103.05,
+                          117.1 15 103.05,
+                          117.1 23 103.05,
+                          114.6 23 107.38,
+                          114.6 15 98.72,
+                          117.1 23 103.05,
+                          117.1 15 103.05,
+                          114.6 15 107.38,
+                          114.6 23 107.38,
+                          109.6 23 107.38,
+                          117.1 15 103.05,
+                          114.6 23 107.38,
+                          114.6 15 107.38,
+                          114.6 15 107.38,
+                          109.6 23 107.38,
+                          109.6 15 107.38,
+                          114.6 15 107.38,
+                          109.6 15 107.38,
+                          107.1 15 103.05,
+                          117.1 15 103.05,
+                          114.6 15 107.38,
+                          107.1 15 103.05,
+                          109.6 15 98.72,
+                          117.1 15 103.05,
+                          107.1 15 103.05,
+                          109.6 15 98.72,
+                          114.6 15 98.72,
+                          117.1 15 103.05 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          0.5 -3.06152e-17 -0.866025,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          0.5 -3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          1 -6.12303e-17 2.28767e-17,
+                          0.5 -3.06152e-17 0.866025,
+                          1 -6.12303e-17 2.28767e-17,
+                          1 -6.12303e-17 2.28767e-17,
+                          0.5 -3.06152e-17 -0.866025,
+                          0.5 -3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          0.5 -3.06152e-17 -0.866025,
+                          1 -6.12303e-17 -2.22045e-16,
+                          0.5 -3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          -1 6.12303e-17 9.9584e-17,
+                          0.5 -3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -1 6.12303e-17 9.9584e-17,
+                          -1 6.12303e-17 9.9584e-17,
+                          -0.5 3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          -1 6.12303e-17 9.9584e-17,
+                          -1 6.12303e-17 9.9584e-17,
+                          -0.5 3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          -1 6.12303e-17 9.9584e-17,
+                          -0.5 3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 109.6 -23 98.72,
+                          114.6 -23 98.72,
+                          117.1 -23 103.05,
+                          117.1 -15 103.05,
+                          117.1 -23 103.05,
+                          114.6 -23 98.72,
+                          107.1 -23 103.05,
+                          109.6 -23 98.72,
+                          117.1 -23 103.05,
+                          114.6 -23 107.38,
+                          107.1 -23 103.05,
+                          117.1 -23 103.05,
+                          114.6 -15 107.38,
+                          114.6 -23 107.38,
+                          117.1 -23 103.05,
+                          114.6 -15 107.38,
+                          117.1 -23 103.05,
+                          117.1 -15 103.05,
+                          114.6 -15 98.72,
+                          114.6 -23 98.72,
+                          109.6 -23 98.72,
+                          114.6 -15 98.72,
+                          117.1 -15 103.05,
+                          114.6 -23 98.72,
+                          109.6 -15 98.72,
+                          109.6 -23 98.72,
+                          107.1 -23 103.05,
+                          114.6 -15 98.72,
+                          109.6 -23 98.72,
+                          109.6 -15 98.72,
+                          114.6 -23 107.38,
+                          109.6 -23 107.38,
+                          107.1 -23 103.05,
+                          107.1 -15 103.05,
+                          107.1 -23 103.05,
+                          109.6 -23 107.38,
+                          109.6 -15 98.72,
+                          107.1 -23 103.05,
+                          107.1 -15 103.05,
+                          109.6 -15 107.38,
+                          109.6 -23 107.38,
+                          114.6 -23 107.38,
+                          107.1 -15 103.05,
+                          109.6 -23 107.38,
+                          109.6 -15 107.38,
+                          109.6 -15 107.38,
+                          114.6 -23 107.38,
+                          114.6 -15 107.38,
+                          109.6 -15 107.38,
+                          114.6 -15 107.38,
+                          117.1 -15 103.05,
+                          107.1 -15 103.05,
+                          109.6 -15 107.38,
+                          117.1 -15 103.05,
+                          114.6 -15 98.72,
+                          107.1 -15 103.05,
+                          117.1 -15 103.05,
+                          114.6 -15 98.72,
+                          109.6 -15 98.72,
+                          107.1 -15 103.05 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          0.5 -3.06152e-17 -0.866025,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          0.5 -3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          1 -6.12303e-17 2.28767e-17,
+                          0.5 -3.06152e-17 0.866025,
+                          1 -6.12303e-17 2.28767e-17,
+                          1 -6.12303e-17 2.28767e-17,
+                          0.5 -3.06152e-17 -0.866025,
+                          0.5 -3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          0.5 -3.06152e-17 -0.866025,
+                          1 -6.12303e-17 -2.22045e-16,
+                          0.5 -3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          -1 6.12303e-17 9.9584e-17,
+                          0.5 -3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -1 6.12303e-17 9.9584e-17,
+                          -1 6.12303e-17 9.9584e-17,
+                          -0.5 3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          -1 6.12303e-17 9.9584e-17,
+                          -1 6.12303e-17 9.9584e-17,
+                          -0.5 3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          -1 6.12303e-17 9.9584e-17,
+                          -0.5 3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 109.5 15 7.67,
+                          114.5 15 7.67,
+                          117 15 12,
+                          117 23 12,
+                          117 15 12,
+                          114.5 15 7.67,
+                          107 15 12,
+                          109.5 15 7.67,
+                          117 15 12,
+                          114.5 15 16.33,
+                          107 15 12,
+                          117 15 12,
+                          114.5 23 16.33,
+                          114.5 15 16.33,
+                          117 15 12,
+                          114.5 23 16.33,
+                          117 15 12,
+                          117 23 12,
+                          114.5 23 7.67,
+                          114.5 15 7.67,
+                          109.5 15 7.67,
+                          114.5 23 7.67,
+                          117 23 12,
+                          114.5 15 7.67,
+                          109.5 23 7.67,
+                          109.5 15 7.67,
+                          107 15 12,
+                          114.5 23 7.67,
+                          109.5 15 7.67,
+                          109.5 23 7.67,
+                          114.5 15 16.33,
+                          109.5 15 16.33,
+                          107 15 12,
+                          107 23 12,
+                          107 15 12,
+                          109.5 15 16.33,
+                          109.5 23 7.67,
+                          107 15 12,
+                          107 23 12,
+                          109.5 23 16.33,
+                          109.5 15 16.33,
+                          114.5 15 16.33,
+                          107 23 12,
+                          109.5 15 16.33,
+                          109.5 23 16.33,
+                          109.5 23 16.33,
+                          114.5 15 16.33,
+                          114.5 23 16.33,
+                          109.5 23 16.33,
+                          114.5 23 16.33,
+                          117 23 12,
+                          107 23 12,
+                          109.5 23 16.33,
+                          117 23 12,
+                          114.5 23 7.67,
+                          107 23 12,
+                          117 23 12,
+                          114.5 23 7.67,
+                          109.5 23 7.67,
+                          107 23 12 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          0.5 -3.06152e-17 -0.866025,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          0.5 -3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          1 -6.12303e-17 2.28767e-17,
+                          0.5 -3.06152e-17 0.866025,
+                          1 -6.12303e-17 2.28767e-17,
+                          1 -6.12303e-17 2.28767e-17,
+                          0.5 -3.06152e-17 -0.866025,
+                          0.5 -3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          0.5 -3.06152e-17 -0.866025,
+                          1 -6.12303e-17 -2.22045e-16,
+                          0.5 -3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          -1 6.12303e-17 9.9584e-17,
+                          0.5 -3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -1 6.12303e-17 9.9584e-17,
+                          -1 6.12303e-17 9.9584e-17,
+                          -0.5 3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 -0.866025,
+                          -1 6.12303e-17 9.9584e-17,
+                          -1 6.12303e-17 9.9584e-17,
+                          -0.5 3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          -1 6.12303e-17 9.9584e-17,
+                          -0.5 3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          -0.5 3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          0.5 -3.06152e-17 0.866025,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 109.5 -23 7.67,
+                          114.5 -23 7.67,
+                          117 -23 12,
+                          117 -15 12,
+                          117 -23 12,
+                          114.5 -23 7.67,
+                          107 -23 12,
+                          109.5 -23 7.67,
+                          117 -23 12,
+                          114.5 -23 16.33,
+                          107 -23 12,
+                          117 -23 12,
+                          114.5 -15 16.33,
+                          114.5 -23 16.33,
+                          117 -23 12,
+                          114.5 -15 16.33,
+                          117 -23 12,
+                          117 -15 12,
+                          114.5 -15 7.67,
+                          114.5 -23 7.67,
+                          109.5 -23 7.67,
+                          114.5 -15 7.67,
+                          117 -15 12,
+                          114.5 -23 7.67,
+                          109.5 -15 7.67,
+                          109.5 -23 7.67,
+                          107 -23 12,
+                          114.5 -15 7.67,
+                          109.5 -23 7.67,
+                          109.5 -15 7.67,
+                          114.5 -23 16.33,
+                          109.5 -23 16.33,
+                          107 -23 12,
+                          107 -15 12,
+                          107 -23 12,
+                          109.5 -23 16.33,
+                          109.5 -15 7.67,
+                          107 -23 12,
+                          107 -15 12,
+                          109.5 -15 16.33,
+                          109.5 -23 16.33,
+                          114.5 -23 16.33,
+                          107 -15 12,
+                          109.5 -23 16.33,
+                          109.5 -15 16.33,
+                          109.5 -15 16.33,
+                          114.5 -23 16.33,
+                          114.5 -15 16.33,
+                          109.5 -15 16.33,
+                          114.5 -15 16.33,
+                          117 -15 12,
+                          107 -15 12,
+                          109.5 -15 16.33,
+                          117 -15 12,
+                          114.5 -15 7.67,
+                          107 -15 12,
+                          117 -15 12,
+                          114.5 -15 7.67,
+                          109.5 -15 7.67,
+                          107 -15 12 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.85 0.9 0.47
+    }
+    Separator {
+        Normal {
+            vector      [ 6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          1 -6.12303e-17 -4.66966e-16,
+                          1 -6.12303e-17 -4.66966e-16,
+                          0.809017 -4.95364e-17 -0.587785,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.809017 -4.95364e-17 0.587785,
+                          0.809017 -4.95364e-17 0.587785,
+                          1 -6.12303e-17 -2.22045e-16,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.809017 -4.95364e-17 0.587785,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.809017 -4.95364e-17 -0.587785,
+                          0.809017 -4.95364e-17 -0.587785,
+                          0.309017 -1.89212e-17 -0.951057,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.809017 -4.95364e-17 -0.587785,
+                          1 -6.12303e-17 -4.66966e-16,
+                          0.809017 -4.95364e-17 -0.587785,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.309017 -1.89212e-17 -0.951057,
+                          0.309017 -1.89212e-17 -0.951057,
+                          -0.309017 1.89212e-17 -0.951057,
+                          0.809017 -4.95364e-17 -0.587785,
+                          0.309017 -1.89212e-17 -0.951057,
+                          0.309017 -1.89212e-17 -0.951057,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.309017 1.89212e-17 -0.951057,
+                          -0.309017 1.89212e-17 -0.951057,
+                          -0.809017 4.95364e-17 -0.587785,
+                          0.309017 -1.89212e-17 -0.951057,
+                          -0.309017 1.89212e-17 -0.951057,
+                          -0.309017 1.89212e-17 -0.951057,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.809017 4.95364e-17 -0.587785,
+                          -0.809017 4.95364e-17 -0.587785,
+                          -1 6.12303e-17 3.44505e-16,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.309017 1.89212e-17 -0.951057,
+                          -0.809017 4.95364e-17 -0.587785,
+                          -0.809017 4.95364e-17 -0.587785,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -1 6.12303e-17 3.44505e-16,
+                          -1 6.12303e-17 3.44505e-16,
+                          -0.809017 4.95364e-17 0.587785,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.809017 4.95364e-17 -0.587785,
+                          -1 6.12303e-17 3.44505e-16,
+                          -1 6.12303e-17 3.44505e-16,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.809017 4.95364e-17 0.587785,
+                          -0.809017 4.95364e-17 0.587785,
+                          -0.309017 1.89212e-17 0.951057,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -1 6.12303e-17 3.44505e-16,
+                          -0.809017 4.95364e-17 0.587785,
+                          -0.809017 4.95364e-17 0.587785,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.309017 1.89212e-17 0.951057,
+                          -0.309017 1.89212e-17 0.951057,
+                          0.309017 -1.89212e-17 0.951057,
+                          -0.809017 4.95364e-17 0.587785,
+                          -0.309017 1.89212e-17 0.951057,
+                          -0.309017 1.89212e-17 0.951057,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          0.309017 -1.89212e-17 0.951057,
+                          0.309017 -1.89212e-17 0.951057,
+                          0.809017 -4.95364e-17 0.587785,
+                          -0.309017 1.89212e-17 0.951057,
+                          0.309017 -1.89212e-17 0.951057,
+                          0.309017 -1.89212e-17 0.951057,
+                          0.309017 -1.89212e-17 0.951057,
+                          0.809017 -4.95364e-17 0.587785,
+                          0.809017 -4.95364e-17 0.587785,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          0.382885 1.20464e-16 0.923796,
+                          0.382885 1.20464e-16 0.923796,
+                          2.2481e-16 2.66048e-16 1,
+                          0.382885 1.20464e-16 0.923796,
+                          2.2481e-16 2.66048e-16 1,
+                          2.7802e-16 2.66048e-16 1,
+                          3.88578e-16 0 1,
+                          3.88578e-16 0 1,
+                          -0.459053 2.8108e-17 0.888409,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.459053 2.8108e-17 0.888409,
+                          -0.459053 2.8108e-17 0.888409,
+                          -0.815895 4.99575e-17 0.5782,
+                          3.88578e-16 0 1,
+                          -0.459053 2.8108e-17 0.888409,
+                          -0.459053 2.8108e-17 0.888409,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.815895 4.99575e-17 0.5782,
+                          -0.815895 4.99575e-17 0.5782,
+                          -0.990268 6.06344e-17 0.139173,
+                          -0.459053 2.8108e-17 0.888409,
+                          -0.815895 4.99575e-17 0.5782,
+                          -0.815895 4.99575e-17 0.5782,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -0.990268 6.06344e-17 0.139173,
+                          -0.990268 6.06344e-17 0.139173,
+                          -0.990268 6.06344e-17 0.139173,
+                          -0.815895 4.99575e-17 0.5782,
+                          -0.990268 6.06344e-17 0.139173,
+                          -0.990268 6.06344e-17 0.139173,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -0.990268 6.06344e-17 0.139173,
+                          -0.990268 6.06344e-17 0.139173,
+                          -0.990268 6.06344e-17 0.139173,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          6.12303e-17 1 0,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          0.620964 -3.80218e-17 0.783839,
+                          0.620964 -3.80218e-17 0.783839,
+                          0.620964 -3.80218e-17 0.783839,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          0.620964 -3.80218e-17 0.783839,
+                          0.620964 -3.80218e-17 0.783839,
+                          0.620964 -3.80218e-17 0.783839,
+                          1 -3.27278e-16 -2.20026e-16,
+                          1 -3.27278e-16 -4.42071e-16,
+                          0.923782 -2.00459e-16 0.382919,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          0.923782 -2.00459e-16 0.382919,
+                          0.923782 -2.00459e-16 0.382919,
+                          0.707093 -4.32884e-17 0.70712,
+                          0.923782 -2.00459e-16 0.382919,
+                          1 -3.27278e-16 -2.20026e-16,
+                          0.923782 -2.00459e-16 0.382919,
+                          0.707093 -4.32884e-17 0.70712,
+                          0.707093 -4.32884e-17 0.70712,
+                          0.382885 1.20464e-16 0.923796,
+                          0.923782 -2.00459e-16 0.382919,
+                          0.707093 -4.32884e-17 0.70712,
+                          0.707093 -4.32884e-17 0.70712,
+                          0.707093 -4.32884e-17 0.70712,
+                          0.382885 1.20464e-16 0.923796,
+                          0.382885 1.20464e-16 0.923796,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -12.9511 -49.5 155.5,
+                          -12.9443 -49.5 136.405,
+                          -16 -49.5 127,
+                          -16 -55.5 127,
+                          -16 -49.5 127,
+                          -12.9443 -49.5 136.405,
+                          -49.5 -49.5 7,
+                          -16 -49.5 127,
+                          -12.9443 -49.5 117.595,
+                          -12.9443 -55.5 117.595,
+                          -12.9443 -49.5 117.595,
+                          -16 -49.5 127,
+                          -26.7227 -49.5 152.152,
+                          -12.9511 -49.5 155.5,
+                          -16 -49.5 127,
+                          -49.5 -49.5 7,
+                          -26.7227 -49.5 152.152,
+                          -16 -49.5 127,
+                          -12.9443 -55.5 117.595,
+                          -16 -49.5 127,
+                          -16 -55.5 127,
+                          10 -49.5 155.5,
+                          -4.94427 -49.5 142.217,
+                          -12.9443 -49.5 136.405,
+                          -12.9443 -55.5 136.405,
+                          -12.9443 -49.5 136.405,
+                          -4.94427 -49.5 142.217,
+                          -12.9511 -49.5 155.5,
+                          10 -49.5 155.5,
+                          -12.9443 -49.5 136.405,
+                          -12.9443 -55.5 136.405,
+                          -16 -55.5 127,
+                          -12.9443 -49.5 136.405,
+                          10 -49.5 155.5,
+                          4.94427 -49.5 142.217,
+                          -4.94427 -49.5 142.217,
+                          -4.94427 -55.5 142.217,
+                          -4.94427 -49.5 142.217,
+                          4.94427 -49.5 142.217,
+                          -12.9443 -55.5 136.405,
+                          -4.94427 -49.5 142.217,
+                          -4.94427 -55.5 142.217,
+                          10 -49.5 155.5,
+                          12.9443 -49.5 136.405,
+                          4.94427 -49.5 142.217,
+                          4.94427 -55.5 142.217,
+                          4.94427 -49.5 142.217,
+                          12.9443 -49.5 136.405,
+                          -4.94427 -55.5 142.217,
+                          4.94427 -49.5 142.217,
+                          4.94427 -55.5 142.217,
+                          21.4843 -49.5 153.215,
+                          16 -49.5 127,
+                          12.9443 -49.5 136.405,
+                          12.9443 -55.5 136.405,
+                          12.9443 -49.5 136.405,
+                          16 -49.5 127,
+                          21.4843 -49.5 153.215,
+                          12.9443 -49.5 136.405,
+                          10 -49.5 155.5,
+                          4.94427 -55.5 142.217,
+                          12.9443 -49.5 136.405,
+                          12.9443 -55.5 136.405,
+                          31.2114 -49.5 146.712,
+                          12.9443 -49.5 117.595,
+                          16 -49.5 127,
+                          16 -55.5 127,
+                          16 -49.5 127,
+                          12.9443 -49.5 117.595,
+                          21.4843 -49.5 153.215,
+                          31.2114 -49.5 146.712,
+                          16 -49.5 127,
+                          12.9443 -55.5 136.405,
+                          16 -49.5 127,
+                          16 -55.5 127,
+                          -49.5 -49.5 7,
+                          4.94427 -49.5 111.783,
+                          12.9443 -49.5 117.595,
+                          12.9443 -55.5 117.595,
+                          12.9443 -49.5 117.595,
+                          4.94427 -49.5 111.783,
+                          31.2114 -49.5 146.712,
+                          -49.5 -49.5 7,
+                          12.9443 -49.5 117.595,
+                          16 -55.5 127,
+                          12.9443 -49.5 117.595,
+                          12.9443 -55.5 117.595,
+                          -49.5 -49.5 7,
+                          -4.94427 -49.5 111.783,
+                          4.94427 -49.5 111.783,
+                          4.94427 -55.5 111.783,
+                          4.94427 -49.5 111.783,
+                          -4.94427 -49.5 111.783,
+                          12.9443 -55.5 117.595,
+                          4.94427 -49.5 111.783,
+                          4.94427 -55.5 111.783,
+                          -49.5 -49.5 7,
+                          -12.9443 -49.5 117.595,
+                          -4.94427 -49.5 111.783,
+                          -4.94427 -55.5 111.783,
+                          -4.94427 -49.5 111.783,
+                          -12.9443 -49.5 117.595,
+                          4.94427 -55.5 111.783,
+                          -4.94427 -49.5 111.783,
+                          -4.94427 -55.5 111.783,
+                          -4.94427 -55.5 111.783,
+                          -12.9443 -49.5 117.595,
+                          -12.9443 -55.5 117.595,
+                          10 -55.5 155.5,
+                          10 -49.5 155.5,
+                          -12.9511 -49.5 155.5,
+                          21.4843 -55.5 153.215,
+                          21.4843 -49.5 153.215,
+                          10 -49.5 155.5,
+                          21.4843 -55.5 153.215,
+                          10 -49.5 155.5,
+                          10 -55.5 155.5,
+                          -12.9511 -55.5 155.5,
+                          -12.9511 -49.5 155.5,
+                          -26.7227 -49.5 152.152,
+                          10 -55.5 155.5,
+                          -12.9511 -49.5 155.5,
+                          -12.9511 -55.5 155.5,
+                          -49.5 -49.5 7,
+                          -37.4279 -49.5 142.846,
+                          -26.7227 -49.5 152.152,
+                          -26.7227 -55.5 152.152,
+                          -26.7227 -49.5 152.152,
+                          -37.4279 -49.5 142.846,
+                          -12.9511 -55.5 155.5,
+                          -26.7227 -49.5 152.152,
+                          -26.7227 -55.5 152.152,
+                          -49.5 -49.5 7,
+                          -42.6591 -49.5 129.675,
+                          -37.4279 -49.5 142.846,
+                          -37.4279 -55.5 142.846,
+                          -37.4279 -49.5 142.846,
+                          -42.6591 -49.5 129.675,
+                          -26.7227 -55.5 152.152,
+                          -37.4279 -49.5 142.846,
+                          -37.4279 -55.5 142.846,
+                          -49.5 -49.5 7,
+                          -49.5 -49.5 81,
+                          -42.6591 -49.5 129.675,
+                          -42.6591 -55.5 129.675,
+                          -42.6591 -49.5 129.675,
+                          -49.5 -49.5 81,
+                          -37.4279 -55.5 142.846,
+                          -42.6591 -49.5 129.675,
+                          -42.6591 -55.5 129.675,
+                          -49.5 -55.5 81,
+                          -49.5 -49.5 81,
+                          -49.5 -49.5 7,
+                          -42.6591 -55.5 129.675,
+                          -49.5 -49.5 81,
+                          -49.5 -55.5 81,
+                          117 -49.5 41,
+                          117 -49.5 7,
+                          -49.5 -49.5 7,
+                          -49.5 -55.5 7,
+                          -49.5 -49.5 7,
+                          117 -49.5 7,
+                          40 -49.5 102,
+                          117 -49.5 41,
+                          -49.5 -49.5 7,
+                          40 -49.5 125.5,
+                          40 -49.5 102,
+                          -49.5 -49.5 7,
+                          37.7147 -49.5 136.985,
+                          40 -49.5 125.5,
+                          -49.5 -49.5 7,
+                          31.2114 -49.5 146.712,
+                          37.7147 -49.5 136.985,
+                          -49.5 -49.5 7,
+                          -49.5 -55.5 81,
+                          -49.5 -49.5 7,
+                          -49.5 -55.5 7,
+                          117 -55.5 7,
+                          117 -49.5 7,
+                          117 -49.5 41,
+                          -49.5 -55.5 7,
+                          117 -49.5 7,
+                          117 -55.5 7,
+                          117 -55.5 41,
+                          117 -49.5 41,
+                          40 -49.5 102,
+                          117 -55.5 7,
+                          117 -49.5 41,
+                          117 -55.5 41,
+                          40 -55.5 102,
+                          40 -49.5 102,
+                          40 -49.5 125.5,
+                          117 -55.5 41,
+                          40 -49.5 102,
+                          40 -55.5 102,
+                          40 -55.5 125.5,
+                          40 -49.5 125.5,
+                          37.7147 -49.5 136.985,
+                          40 -55.5 102,
+                          40 -49.5 125.5,
+                          40 -55.5 125.5,
+                          37.7147 -55.5 136.985,
+                          37.7147 -49.5 136.985,
+                          31.2114 -49.5 146.712,
+                          37.7147 -55.5 136.985,
+                          40 -55.5 125.5,
+                          37.7147 -49.5 136.985,
+                          31.2114 -55.5 146.712,
+                          31.2114 -49.5 146.712,
+                          21.4843 -49.5 153.215,
+                          37.7147 -55.5 136.985,
+                          31.2114 -49.5 146.712,
+                          31.2114 -55.5 146.712,
+                          31.2114 -55.5 146.712,
+                          21.4843 -49.5 153.215,
+                          21.4843 -55.5 153.215,
+                          -26.7227 -55.5 152.152,
+                          -12.9443 -55.5 117.595,
+                          -16 -55.5 127,
+                          -12.9511 -55.5 155.5,
+                          -16 -55.5 127,
+                          -12.9443 -55.5 136.405,
+                          -12.9511 -55.5 155.5,
+                          -26.7227 -55.5 152.152,
+                          -16 -55.5 127,
+                          117 -55.5 7,
+                          -4.94427 -55.5 111.783,
+                          -12.9443 -55.5 117.595,
+                          -42.6591 -55.5 129.675,
+                          117 -55.5 7,
+                          -12.9443 -55.5 117.595,
+                          -37.4279 -55.5 142.846,
+                          -42.6591 -55.5 129.675,
+                          -12.9443 -55.5 117.595,
+                          -26.7227 -55.5 152.152,
+                          -37.4279 -55.5 142.846,
+                          -12.9443 -55.5 117.595,
+                          117 -55.5 7,
+                          4.94427 -55.5 111.783,
+                          -4.94427 -55.5 111.783,
+                          117 -55.5 7,
+                          12.9443 -55.5 117.595,
+                          4.94427 -55.5 111.783,
+                          117 -55.5 7,
+                          16 -55.5 127,
+                          12.9443 -55.5 117.595,
+                          10 -55.5 155.5,
+                          12.9443 -55.5 136.405,
+                          16 -55.5 127,
+                          117 -55.5 7,
+                          40 -55.5 102,
+                          16 -55.5 127,
+                          21.4843 -55.5 153.215,
+                          16 -55.5 127,
+                          40 -55.5 102,
+                          21.4843 -55.5 153.215,
+                          10 -55.5 155.5,
+                          16 -55.5 127,
+                          10 -55.5 155.5,
+                          4.94427 -55.5 142.217,
+                          12.9443 -55.5 136.405,
+                          -12.9511 -55.5 155.5,
+                          -4.94427 -55.5 142.217,
+                          4.94427 -55.5 142.217,
+                          10 -55.5 155.5,
+                          -12.9511 -55.5 155.5,
+                          4.94427 -55.5 142.217,
+                          -12.9511 -55.5 155.5,
+                          -12.9443 -55.5 136.405,
+                          -4.94427 -55.5 142.217,
+                          37.7147 -55.5 136.985,
+                          40 -55.5 102,
+                          40 -55.5 125.5,
+                          117 -55.5 7,
+                          117 -55.5 41,
+                          40 -55.5 102,
+                          31.2114 -55.5 146.712,
+                          21.4843 -55.5 153.215,
+                          40 -55.5 102,
+                          37.7147 -55.5 136.985,
+                          31.2114 -55.5 146.712,
+                          40 -55.5 102,
+                          -49.5 -55.5 81,
+                          -49.5 -55.5 7,
+                          117 -55.5 7,
+                          -42.6591 -55.5 129.675,
+                          -49.5 -55.5 81,
+                          117 -55.5 7 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.7 0.7 0.7
+    }
+    Separator {
+        Normal {
+            vector      [ 2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          -6.12303e-17 1 0,
+                          -6.12303e-17 1 0,
+                          0.866025 0.5 -1.92296e-16,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          -0.866025 0.5 1.92296e-16,
+                          -0.866025 0.5 1.92296e-16,
+                          -6.12303e-17 1 0,
+                          -6.12303e-17 1 0,
+                          -0.866025 0.5 1.92296e-16,
+                          -6.12303e-17 1 0,
+                          0.866025 0.5 -1.92296e-16,
+                          0.866025 0.5 -1.92296e-16,
+                          0.866025 -0.5 -1.92296e-16,
+                          0.866025 0.5 -1.92296e-16,
+                          -6.12303e-17 1 0,
+                          0.866025 0.5 -1.92296e-16,
+                          0.866025 -0.5 -1.92296e-16,
+                          0.866025 -0.5 -1.92296e-16,
+                          1.83691e-16 -1 0,
+                          0.866025 -0.5 -1.92296e-16,
+                          0.866025 0.5 -1.92296e-16,
+                          0.866025 -0.5 -1.92296e-16,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -0.866025 -0.5 1.92296e-16,
+                          0.866025 -0.5 -1.92296e-16,
+                          1.83691e-16 -1 0,
+                          1.83691e-16 -1 0,
+                          -0.866025 -0.5 1.92296e-16,
+                          -0.866025 -0.5 1.92296e-16,
+                          -0.866025 0.5 1.92296e-16,
+                          -0.866025 -0.5 1.92296e-16,
+                          -6.12303e-17 -1 0,
+                          -0.866025 -0.5 1.92296e-16,
+                          -0.866025 0.5 1.92296e-16,
+                          -0.866025 -0.5 1.92296e-16,
+                          -0.866025 0.5 1.92296e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 81.4786 15.4244 152.25,
+                          81.4786 17.9244 152.25,
+                          79.3136 19.1744 152.25,
+                          79.3136 19.1744 142.25,
+                          79.3136 19.1744 152.25,
+                          81.4786 17.9244 152.25,
+                          79.3136 14.1744 152.25,
+                          81.4786 15.4244 152.25,
+                          79.3136 19.1744 152.25,
+                          77.1485 17.9244 152.25,
+                          79.3136 14.1744 152.25,
+                          79.3136 19.1744 152.25,
+                          77.1485 17.9244 142.25,
+                          77.1485 17.9244 152.25,
+                          79.3136 19.1744 152.25,
+                          79.3136 19.1744 142.25,
+                          77.1485 17.9244 142.25,
+                          79.3136 19.1744 152.25,
+                          81.4786 17.9244 142.25,
+                          81.4786 17.9244 152.25,
+                          81.4786 15.4244 152.25,
+                          81.4786 17.9244 142.25,
+                          79.3136 19.1744 142.25,
+                          81.4786 17.9244 152.25,
+                          81.4786 15.4244 142.25,
+                          81.4786 15.4244 152.25,
+                          79.3136 14.1744 152.25,
+                          81.4786 15.4244 142.25,
+                          81.4786 17.9244 142.25,
+                          81.4786 15.4244 152.25,
+                          77.1485 17.9244 152.25,
+                          77.1485 15.4244 152.25,
+                          79.3136 14.1744 152.25,
+                          79.3136 14.1744 142.25,
+                          79.3136 14.1744 152.25,
+                          77.1485 15.4244 152.25,
+                          81.4786 15.4244 142.25,
+                          79.3136 14.1744 152.25,
+                          79.3136 14.1744 142.25,
+                          77.1485 15.4244 142.25,
+                          77.1485 15.4244 152.25,
+                          77.1485 17.9244 152.25,
+                          77.1485 15.4244 142.25,
+                          79.3136 14.1744 142.25,
+                          77.1485 15.4244 152.25,
+                          77.1485 17.9244 142.25,
+                          77.1485 15.4244 142.25,
+                          77.1485 17.9244 152.25 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.83 0 0
+    }
+    Separator {
+        Normal {
+            vector      [ -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -0.866025 -0.5 1.92296e-16,
+                          0.866025 -0.5 -1.92296e-16,
+                          0.866025 -0.5 -1.92296e-16,
+                          1.83691e-16 -1 0,
+                          0.866025 -0.5 -1.92296e-16,
+                          1.83691e-16 -1 0,
+                          1.83691e-16 -1 0,
+                          -0.866025 -0.5 1.92296e-16,
+                          -0.866025 -0.5 1.92296e-16,
+                          -0.866025 0.5 1.92296e-16,
+                          -0.866025 -0.5 1.92296e-16,
+                          -6.12303e-17 -1 0,
+                          -0.866025 -0.5 1.92296e-16,
+                          -0.866025 0.5 1.92296e-16,
+                          -0.866025 0.5 1.92296e-16,
+                          -6.12303e-17 1 0,
+                          -0.866025 0.5 1.92296e-16,
+                          -0.866025 -0.5 1.92296e-16,
+                          -0.866025 0.5 1.92296e-16,
+                          -6.12303e-17 1 0,
+                          -6.12303e-17 1 0,
+                          0.866025 0.5 -1.92296e-16,
+                          -6.12303e-17 1 0,
+                          -0.866025 0.5 1.92296e-16,
+                          -6.12303e-17 1 0,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          -6.12303e-17 1 0,
+                          -6.12303e-17 1 0,
+                          0.587785 0.809017 -1.30515e-16,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          -0.315577 0.9489 7.00721e-17,
+                          -0.587785 0.809017 1.30515e-16,
+                          -6.12303e-17 1 0,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          -6.12303e-17 1 0,
+                          -0.315577 0.9489 7.00721e-17,
+                          -6.12303e-17 1 0,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          0.598891 0.800831 -1.3298e-16,
+                          0.587785 0.809017 -1.30515e-16,
+                          0.951057 0.309017 -2.11177e-16,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          0.315577 0.9489 -7.00721e-17,
+                          -6.12303e-17 1 0,
+                          0.587785 0.809017 -1.30515e-16,
+                          0.598891 0.800831 -1.3298e-16,
+                          0.315577 0.9489 -7.00721e-17,
+                          0.587785 0.809017 -1.30515e-16,
+                          0.959207 0.282706 -2.12987e-16,
+                          0.951057 0.309017 -2.11177e-16,
+                          0.951057 -0.309017 -2.11177e-16,
+                          0.820996 0.570933 -1.82298e-16,
+                          0.598891 0.800831 -1.3298e-16,
+                          0.951057 0.309017 -2.11177e-16,
+                          0.959207 0.282706 -2.12987e-16,
+                          0.820996 0.570933 -1.82298e-16,
+                          0.951057 0.309017 -2.11177e-16,
+                          0.9375 -0.347985 -2.08167e-16,
+                          0.951057 -0.309017 -2.11177e-16,
+                          0.587785 -0.809017 -1.30515e-16,
+                          0.999408 -0.0344003 -2.21913e-16,
+                          0.959207 0.282706 -2.12987e-16,
+                          0.951057 -0.309017 -2.11177e-16,
+                          0.9375 -0.347985 -2.08167e-16,
+                          0.999408 -0.0344003 -2.21913e-16,
+                          0.951057 -0.309017 -2.11177e-16,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          0.570991 -0.820956 -1.26785e-16,
+                          0.587785 -0.809017 -1.30515e-16,
+                          1.83691e-16 -1 0,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          0.570991 -0.820956 -1.26785e-16,
+                          0.9375 -0.347985 -2.08167e-16,
+                          0.587785 -0.809017 -1.30515e-16,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -0.587785 -0.809017 1.30515e-16,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          0.570991 -0.820956 -1.26785e-16,
+                          1.83691e-16 -1 0,
+                          1.83691e-16 -1 0,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          -0.9375 -0.347985 2.08167e-16,
+                          -0.587785 -0.809017 1.30515e-16,
+                          -0.951057 -0.309017 2.11177e-16,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          -0.570991 -0.820956 1.26785e-16,
+                          -0.587785 -0.809017 1.30515e-16,
+                          -0.9375 -0.347985 2.08167e-16,
+                          -0.570991 -0.820956 1.26785e-16,
+                          -6.12303e-17 -1 0,
+                          -0.587785 -0.809017 1.30515e-16,
+                          -0.999408 -0.0344003 2.21913e-16,
+                          -0.951057 -0.309017 2.11177e-16,
+                          -0.951057 0.309017 2.11177e-16,
+                          -0.999408 -0.0344003 2.21913e-16,
+                          -0.9375 -0.347985 2.08167e-16,
+                          -0.951057 -0.309017 2.11177e-16,
+                          -0.820996 0.570933 1.82298e-16,
+                          -0.951057 0.309017 2.11177e-16,
+                          -0.587785 0.809017 1.30515e-16,
+                          -0.959207 0.282706 2.12987e-16,
+                          -0.999408 -0.0344003 2.21913e-16,
+                          -0.951057 0.309017 2.11177e-16,
+                          -0.820996 0.570933 1.82298e-16,
+                          -0.959207 0.282706 2.12987e-16,
+                          -0.951057 0.309017 2.11177e-16,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          -0.598891 0.800831 1.3298e-16,
+                          -0.820996 0.570933 1.82298e-16,
+                          -0.587785 0.809017 1.30515e-16,
+                          -0.315577 0.9489 7.00721e-17,
+                          -0.598891 0.800831 1.3298e-16,
+                          -0.587785 0.809017 1.30515e-16,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          0.866025 0.5 -1.92296e-16,
+                          0.866025 0.5 -1.92296e-16,
+                          0.866025 -0.5 -1.92296e-16,
+                          0.866025 0.5 -1.92296e-16,
+                          -6.12303e-17 1 0,
+                          0.866025 0.5 -1.92296e-16,
+                          0.866025 0.5 -1.92296e-16,
+                          0.866025 -0.5 -1.92296e-16,
+                          0.866025 -0.5 -1.92296e-16,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 79.3136 14.1744 139.25,
+                          79.3136 14.1744 142.25,
+                          77.1485 15.4244 142.25,
+                          81.4786 15.4244 139.25,
+                          81.4786 15.4244 142.25,
+                          79.3136 14.1744 142.25,
+                          81.4786 15.4244 139.25,
+                          79.3136 14.1744 142.25,
+                          79.3136 14.1744 139.25,
+                          77.1485 15.4244 139.25,
+                          77.1485 15.4244 142.25,
+                          77.1485 17.9244 142.25,
+                          77.1485 15.4244 139.25,
+                          79.3136 14.1744 139.25,
+                          77.1485 15.4244 142.25,
+                          77.1485 17.9244 139.25,
+                          77.1485 17.9244 142.25,
+                          79.3136 19.1744 142.25,
+                          77.1485 17.9244 139.25,
+                          77.1485 15.4244 139.25,
+                          77.1485 17.9244 142.25,
+                          79.3136 19.1744 139.25,
+                          79.3136 19.1744 142.25,
+                          81.4786 17.9244 142.25,
+                          79.3136 19.1744 139.25,
+                          77.1485 17.9244 139.25,
+                          79.3136 19.1744 142.25,
+                          84.9704 22.3313 139.25,
+                          88.719 29.6179 139.25,
+                          79.3136 32.6744 139.25,
+                          79.3136 32.6744 77.25,
+                          79.3136 32.6744 139.25,
+                          88.719 29.6179 139.25,
+                          79.3136 24.6744 139.25,
+                          79.3136 32.6744 139.25,
+                          69.9081 29.6179 139.25,
+                          74.2643 31.8568 77.25,
+                          69.9081 29.6179 139.25,
+                          79.3136 32.6744 139.25,
+                          84.9704 22.3313 139.25,
+                          79.3136 32.6744 139.25,
+                          79.3136 24.6744 139.25,
+                          79.3136 32.6744 77.25,
+                          74.2643 31.8568 77.25,
+                          79.3136 32.6744 139.25,
+                          94.5304 11.7308 139.25,
+                          94.5304 21.6181 139.25,
+                          88.719 29.6179 139.25,
+                          88.8958 29.4877 77.25,
+                          88.719 29.6179 139.25,
+                          94.5304 21.6181 139.25,
+                          88.719 3.73092 139.25,
+                          94.5304 11.7308 139.25,
+                          88.719 29.6179 139.25,
+                          87.3136 16.6744 139.25,
+                          88.719 3.73092 139.25,
+                          88.719 29.6179 139.25,
+                          84.9704 22.3313 139.25,
+                          87.3136 16.6744 139.25,
+                          88.719 29.6179 139.25,
+                          84.3628 31.8568 77.25,
+                          79.3136 32.6744 77.25,
+                          88.719 29.6179 139.25,
+                          88.8958 29.4877 77.25,
+                          84.3628 31.8568 77.25,
+                          88.719 29.6179 139.25,
+                          94.6609 21.1977 77.25,
+                          94.5304 21.6181 139.25,
+                          94.5304 11.7308 139.25,
+                          92.4495 25.8094 77.25,
+                          88.8958 29.4877 77.25,
+                          94.5304 21.6181 139.25,
+                          94.6609 21.1977 77.25,
+                          92.4495 25.8094 77.25,
+                          94.5304 21.6181 139.25,
+                          94.3136 11.1067 77.25,
+                          94.5304 11.7308 139.25,
+                          88.719 3.73092 139.25,
+                          95.3041 16.124 77.25,
+                          94.6609 21.1977 77.25,
+                          94.5304 11.7308 139.25,
+                          94.3136 11.1067 77.25,
+                          95.3041 16.124 77.25,
+                          94.5304 11.7308 139.25,
+                          79.3136 8.67442 139.25,
+                          79.3136 0.674416 139.25,
+                          88.719 3.73092 139.25,
+                          88.4494 3.53911 77.25,
+                          88.719 3.73092 139.25,
+                          79.3136 0.674416 139.25,
+                          84.9704 11.0176 139.25,
+                          79.3136 8.67442 139.25,
+                          88.719 3.73092 139.25,
+                          87.3136 16.6744 139.25,
+                          84.9704 11.0176 139.25,
+                          88.719 3.73092 139.25,
+                          88.4494 3.53911 77.25,
+                          94.3136 11.1067 77.25,
+                          88.719 3.73092 139.25,
+                          73.6567 11.0176 139.25,
+                          69.9081 3.73092 139.25,
+                          79.3136 0.674416 139.25,
+                          79.3136 0.674416 77.25,
+                          79.3136 0.674416 139.25,
+                          69.9081 3.73092 139.25,
+                          79.3136 8.67442 139.25,
+                          73.6567 11.0176 139.25,
+                          79.3136 0.674416 139.25,
+                          88.4494 3.53911 77.25,
+                          79.3136 0.674416 139.25,
+                          79.3136 0.674416 77.25,
+                          64.0967 21.6181 139.25,
+                          64.0967 11.7308 139.25,
+                          69.9081 3.73092 139.25,
+                          64.3136 11.1067 77.25,
+                          69.9081 3.73092 139.25,
+                          64.0967 11.7308 139.25,
+                          69.9081 29.6179 139.25,
+                          64.0967 21.6181 139.25,
+                          69.9081 3.73092 139.25,
+                          71.3136 16.6744 139.25,
+                          69.9081 29.6179 139.25,
+                          69.9081 3.73092 139.25,
+                          73.6567 11.0176 139.25,
+                          71.3136 16.6744 139.25,
+                          69.9081 3.73092 139.25,
+                          70.1777 3.53911 77.25,
+                          69.9081 3.73092 139.25,
+                          64.3136 11.1067 77.25,
+                          70.1777 3.53911 77.25,
+                          79.3136 0.674416 77.25,
+                          69.9081 3.73092 139.25,
+                          63.323 16.124 77.25,
+                          64.0967 11.7308 139.25,
+                          64.0967 21.6181 139.25,
+                          63.323 16.124 77.25,
+                          64.3136 11.1067 77.25,
+                          64.0967 11.7308 139.25,
+                          66.1776 25.8094 77.25,
+                          64.0967 21.6181 139.25,
+                          69.9081 29.6179 139.25,
+                          63.9662 21.1977 77.25,
+                          63.323 16.124 77.25,
+                          64.0967 21.6181 139.25,
+                          66.1776 25.8094 77.25,
+                          63.9662 21.1977 77.25,
+                          64.0967 21.6181 139.25,
+                          73.6567 22.3313 139.25,
+                          79.3136 24.6744 139.25,
+                          69.9081 29.6179 139.25,
+                          71.3136 16.6744 139.25,
+                          73.6567 22.3313 139.25,
+                          69.9081 29.6179 139.25,
+                          69.7313 29.4877 77.25,
+                          66.1776 25.8094 77.25,
+                          69.9081 29.6179 139.25,
+                          74.2643 31.8568 77.25,
+                          69.7313 29.4877 77.25,
+                          69.9081 29.6179 139.25,
+                          79.3136 19.1744 139.25,
+                          79.3136 24.6744 139.25,
+                          73.6567 22.3313 139.25,
+                          84.9704 22.3313 139.25,
+                          79.3136 24.6744 139.25,
+                          84.9704 11.0176 139.25,
+                          81.4786 17.9244 139.25,
+                          84.9704 11.0176 139.25,
+                          79.3136 24.6744 139.25,
+                          81.4786 17.9244 139.25,
+                          79.3136 24.6744 139.25,
+                          79.3136 19.1744 139.25,
+                          73.6567 11.0176 139.25,
+                          73.6567 22.3313 139.25,
+                          71.3136 16.6744 139.25,
+                          79.3136 8.67442 139.25,
+                          73.6567 22.3313 139.25,
+                          73.6567 11.0176 139.25,
+                          77.1485 15.4244 139.25,
+                          73.6567 22.3313 139.25,
+                          79.3136 8.67442 139.25,
+                          77.1485 17.9244 139.25,
+                          73.6567 22.3313 139.25,
+                          77.1485 15.4244 139.25,
+                          79.3136 19.1744 139.25,
+                          73.6567 22.3313 139.25,
+                          77.1485 17.9244 139.25,
+                          79.3136 14.1744 139.25,
+                          79.3136 8.67442 139.25,
+                          84.9704 11.0176 139.25,
+                          77.1485 15.4244 139.25,
+                          79.3136 8.67442 139.25,
+                          79.3136 14.1744 139.25,
+                          84.9704 22.3313 139.25,
+                          84.9704 11.0176 139.25,
+                          87.3136 16.6744 139.25,
+                          81.4786 15.4244 139.25,
+                          79.3136 14.1744 139.25,
+                          84.9704 11.0176 139.25,
+                          81.4786 17.9244 139.25,
+                          81.4786 15.4244 139.25,
+                          84.9704 11.0176 139.25,
+                          81.4786 17.9244 139.25,
+                          81.4786 17.9244 142.25,
+                          81.4786 15.4244 142.25,
+                          81.4786 17.9244 139.25,
+                          79.3136 19.1744 139.25,
+                          81.4786 17.9244 142.25,
+                          81.4786 17.9244 139.25,
+                          81.4786 15.4244 142.25,
+                          81.4786 15.4244 139.25,
+                          64.3136 16.6744 77.25,
+                          64.3136 11.1067 77.25,
+                          63.323 16.124 77.25 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.25 0.25 0.25
+    }
+    Separator {
+        Normal {
+            vector      [ 2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 65.3136 -9.42558 77.25,
+                          70.1777 3.53911 77.25,
+                          64.3136 11.1067 77.25,
+                          64.3136 -8.42558 58.95,
+                          64.3136 11.1067 77.25,
+                          64.3136 16.6744 77.25,
+                          64.6064 -9.13269 77.25,
+                          65.3136 -9.42558 77.25,
+                          64.3136 11.1067 77.25,
+                          64.3136 -8.42558 77.25,
+                          64.6064 -9.13269 77.25,
+                          64.3136 11.1067 77.25,
+                          64.3136 -8.42558 58.95,
+                          64.3136 -8.42558 77.25,
+                          64.3136 11.1067 77.25 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.83 0 0
+    }
+    Separator {
+        Normal {
+            vector      [ -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 64.3136 16.6744 77.25,
+                          63.323 16.124 77.25,
+                          63.9662 21.1977 77.25,
+                          64.3136 16.6744 77.25,
+                          63.9662 21.1977 77.25,
+                          66.1776 25.8094 77.25,
+                          67.179 25.492 77.25,
+                          66.1776 25.8094 77.25,
+                          69.7313 29.4877 77.25,
+                          67.179 25.492 77.25,
+                          64.3136 16.6744 77.25,
+                          66.1776 25.8094 77.25,
+                          67.179 25.492 77.25,
+                          69.7313 29.4877 77.25,
+                          74.2643 31.8568 77.25,
+                          74.6789 30.9402 77.25,
+                          74.2643 31.8568 77.25,
+                          79.3136 32.6744 77.25,
+                          74.6789 30.9402 77.25,
+                          67.179 25.492 77.25,
+                          74.2643 31.8568 77.25,
+                          83.9482 30.9402 77.25,
+                          79.3136 32.6744 77.25,
+                          84.3628 31.8568 77.25,
+                          83.9482 30.9402 77.25,
+                          74.6789 30.9402 77.25,
+                          79.3136 32.6744 77.25 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.25 0.25 0.25
+    }
+    Separator {
+        Normal {
+            vector      [ 2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 93.3136 -9.42558 77.25,
+                          79.3136 0.674416 77.25,
+                          70.1777 3.53911 77.25,
+                          93.3136 -9.42558 77.25,
+                          88.4494 3.53911 77.25,
+                          79.3136 0.674416 77.25,
+                          65.3136 -9.42558 77.25,
+                          93.3136 -9.42558 77.25,
+                          70.1777 3.53911 77.25 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.83 0 0
+    }
+    Separator {
+        Normal {
+            vector      [ -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 83.9482 30.9402 77.25,
+                          84.3628 31.8568 77.25,
+                          88.8958 29.4877 77.25,
+                          91.4481 25.492 77.25,
+                          88.8958 29.4877 77.25,
+                          92.4495 25.8094 77.25,
+                          91.4481 25.492 77.25,
+                          83.9482 30.9402 77.25,
+                          88.8958 29.4877 77.25,
+                          94.3136 16.6744 77.25,
+                          92.4495 25.8094 77.25,
+                          94.6609 21.1977 77.25,
+                          94.3136 16.6744 77.25,
+                          91.4481 25.492 77.25,
+                          92.4495 25.8094 77.25,
+                          94.3136 11.1067 77.25,
+                          94.6609 21.1977 77.25,
+                          95.3041 16.124 77.25,
+                          94.3136 16.6744 77.25,
+                          94.6609 21.1977 77.25,
+                          94.3136 11.1067 77.25 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.25 0.25 0.25
+    }
+    Separator {
+        Normal {
+            vector      [ 2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          2.22045e-16 0 1,
+                          -1 -1.83691e-16 2.22045e-16,
+                          -1 -1.83691e-16 2.22045e-16,
+                          -0.809017 0.587785 1.79638e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -1 6.12303e-17 2.22045e-16,
+                          -0.809017 0.587785 1.79638e-16,
+                          -0.809017 0.587785 1.79638e-16,
+                          -0.309017 0.951057 6.86156e-17,
+                          -1 -1.83691e-16 2.22045e-16,
+                          -0.809017 0.587785 1.79638e-16,
+                          -0.809017 0.587785 1.79638e-16,
+                          -0.309017 0.951057 6.86156e-17,
+                          -0.309017 0.951057 6.86156e-17,
+                          0.309017 0.951057 -6.86156e-17,
+                          -0.809017 0.587785 1.79638e-16,
+                          -0.309017 0.951057 6.86156e-17,
+                          -0.309017 0.951057 6.86156e-17,
+                          0.309017 0.951057 -6.86156e-17,
+                          0.309017 0.951057 -6.86156e-17,
+                          0.809017 0.587785 -1.79638e-16,
+                          -0.309017 0.951057 6.86156e-17,
+                          0.309017 0.951057 -6.86156e-17,
+                          0.309017 0.951057 -6.86156e-17,
+                          0.809017 0.587785 -1.79638e-16,
+                          0.809017 0.587785 -1.79638e-16,
+                          1 3.06152e-16 -2.22045e-16,
+                          0.309017 0.951057 -6.86156e-17,
+                          0.809017 0.587785 -1.79638e-16,
+                          0.809017 0.587785 -1.79638e-16,
+                          0.809017 0.587785 -1.79638e-16,
+                          1 3.06152e-16 -2.22045e-16,
+                          1 3.06152e-16 -2.22045e-16,
+                          1 6.12303e-17 -2.22045e-16,
+                          1 6.12303e-17 -2.22045e-16,
+                          0.707107 -0.707107 -1.57009e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          1 -6.12303e-17 -2.22045e-16,
+                          0.707107 -0.707107 -1.57009e-16,
+                          0.707107 -0.707107 -1.57009e-16,
+                          1.22461e-16 -1 0,
+                          1 6.12303e-17 -2.22045e-16,
+                          0.707107 -0.707107 -1.57009e-16,
+                          0.707107 -0.707107 -1.57009e-16,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          0.707107 -0.707107 -1.57009e-16,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          -0.707107 -0.707107 1.57009e-16,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          -0.707107 -0.707107 1.57009e-16,
+                          -0.707107 -0.707107 1.57009e-16,
+                          -1 -1.83691e-16 2.22045e-16,
+                          1.22461e-16 -1 0,
+                          -0.707107 -0.707107 1.57009e-16,
+                          -0.707107 -0.707107 1.57009e-16,
+                          -0.707107 -0.707107 1.57009e-16,
+                          -1 -1.83691e-16 2.22045e-16,
+                          -1 -1.83691e-16 2.22045e-16,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1,
+                          -2.22045e-16 0 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 94.3136 -8.42558 77.25,
+                          94.3136 11.1067 77.25,
+                          88.4494 3.53911 77.25,
+                          94.3136 16.6744 58.95,
+                          94.3136 16.6744 77.25,
+                          94.3136 11.1067 77.25,
+                          94.3136 16.6744 58.95,
+                          94.3136 11.1067 77.25,
+                          94.3136 -8.42558 77.25,
+                          94.0207 -9.13269 77.25,
+                          94.3136 -8.42558 77.25,
+                          88.4494 3.53911 77.25,
+                          93.3136 -9.42558 77.25,
+                          94.0207 -9.13269 77.25,
+                          88.4494 3.53911 77.25,
+                          64.3136 16.6744 58.95,
+                          64.3136 16.6744 77.25,
+                          67.179 25.492 77.25,
+                          64.3136 -8.42558 58.95,
+                          64.3136 16.6744 77.25,
+                          64.3136 16.6744 58.95,
+                          67.1789 25.4915 58.95,
+                          67.179 25.492 77.25,
+                          74.6789 30.9402 77.25,
+                          64.3136 16.6744 58.95,
+                          67.179 25.492 77.25,
+                          67.1789 25.4915 58.95,
+                          74.6771 30.9397 58.95,
+                          74.6789 30.9402 77.25,
+                          83.9482 30.9402 77.25,
+                          67.1789 25.4915 58.95,
+                          74.6789 30.9402 77.25,
+                          74.6771 30.9397 58.95,
+                          83.95 30.9397 58.95,
+                          83.9482 30.9402 77.25,
+                          91.4481 25.492 77.25,
+                          74.6771 30.9397 58.95,
+                          83.9482 30.9402 77.25,
+                          83.95 30.9397 58.95,
+                          91.4482 25.4915 58.95,
+                          91.4481 25.492 77.25,
+                          94.3136 16.6744 77.25,
+                          83.95 30.9397 58.95,
+                          91.4481 25.492 77.25,
+                          91.4482 25.4915 58.95,
+                          91.4482 25.4915 58.95,
+                          94.3136 16.6744 77.25,
+                          94.3136 16.6744 58.95,
+                          94.3136 -8.42558 58.95,
+                          94.3136 -8.42558 77.25,
+                          94.0207 -9.13269 77.25,
+                          94.3136 -8.42558 58.95,
+                          94.3136 16.6744 58.95,
+                          94.3136 -8.42558 77.25,
+                          94.0207 -9.13269 58.95,
+                          94.0207 -9.13269 77.25,
+                          93.3136 -9.42558 77.25,
+                          94.3136 -8.42558 58.95,
+                          94.0207 -9.13269 77.25,
+                          94.0207 -9.13269 58.95,
+                          93.3136 -9.42558 58.95,
+                          93.3136 -9.42558 77.25,
+                          65.3136 -9.42558 77.25,
+                          94.0207 -9.13269 58.95,
+                          93.3136 -9.42558 77.25,
+                          93.3136 -9.42558 58.95,
+                          65.3136 -9.42558 58.95,
+                          65.3136 -9.42558 77.25,
+                          64.6064 -9.13269 77.25,
+                          93.3136 -9.42558 58.95,
+                          65.3136 -9.42558 77.25,
+                          65.3136 -9.42558 58.95,
+                          64.6064 -9.13269 58.95,
+                          64.6064 -9.13269 77.25,
+                          64.3136 -8.42558 77.25,
+                          65.3136 -9.42558 58.95,
+                          64.6064 -9.13269 77.25,
+                          64.6064 -9.13269 58.95,
+                          64.6064 -9.13269 58.95,
+                          64.3136 -8.42558 77.25,
+                          64.3136 -8.42558 58.95,
+                          67.1789 25.4915 58.95,
+                          91.4482 25.4915 58.95,
+                          94.3136 16.6744 58.95,
+                          64.3136 16.6744 58.95,
+                          67.1789 25.4915 58.95,
+                          94.3136 16.6744 58.95,
+                          94.3136 -8.42558 58.95,
+                          64.3136 16.6744 58.95,
+                          94.3136 16.6744 58.95,
+                          74.6771 30.9397 58.95,
+                          83.95 30.9397 58.95,
+                          91.4482 25.4915 58.95,
+                          67.1789 25.4915 58.95,
+                          74.6771 30.9397 58.95,
+                          91.4482 25.4915 58.95,
+                          94.3136 -8.42558 58.95,
+                          64.3136 -8.42558 58.95,
+                          64.3136 16.6744 58.95,
+                          94.0207 -9.13269 58.95,
+                          64.6064 -9.13269 58.95,
+                          64.3136 -8.42558 58.95,
+                          94.3136 -8.42558 58.95,
+                          94.0207 -9.13269 58.95,
+                          64.3136 -8.42558 58.95,
+                          93.3136 -9.42558 58.95,
+                          65.3136 -9.42558 58.95,
+                          64.6064 -9.13269 58.95,
+                          94.0207 -9.13269 58.95,
+                          93.3136 -9.42558 58.95,
+                          64.6064 -9.13269 58.95 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/platform/platform.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/platform/platform.iv
new file mode 100644
index 0000000000000000000000000000000000000000..925076dc9ae24a800548818e6cafbd986e4b98dd
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/platform/platform.iv
@@ -0,0 +1,5872 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.54 0.87 0.89
+    }
+    Separator {
+        Normal {
+            vector      [ -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.00330516 0.979122 -0.203248,
+                          -0.00292088 0.999996 0,
+                          -0.0695545 0.997578 0,
+                          -0.0311303 0.197857 -0.979736,
+                          -0.0310915 0 -0.999517,
+                          -0.00219066 0 -0.999998,
+                          -0.00277184 0.216815 -0.976209,
+                          -0.0311303 0.197857 -0.979736,
+                          -0.00219066 0 -0.999998,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.100566 0.989974 -0.0991901,
+                          -0.0695545 0.997578 0,
+                          -0.112639 0.993636 0,
+                          -0.0602187 0.986488 -0.152367,
+                          -0.00330516 0.979122 -0.203248,
+                          -0.0695545 0.997578 0,
+                          -0.100566 0.989974 -0.0991901,
+                          -0.0602187 0.986488 -0.152367,
+                          -0.0695545 0.997578 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.12407 0.991257 -0.0449069,
+                          -0.112639 0.993636 0,
+                          -0.130358 0.991467 0,
+                          -0.12407 0.991257 -0.0449069,
+                          -0.100566 0.989974 -0.0991901,
+                          -0.112639 0.993636 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.130766 0.991365 0.00976412,
+                          -0.130358 0.991467 0,
+                          -0.122182 0.992508 0,
+                          -0.130766 0.991365 0.00976412,
+                          -0.12407 0.991257 -0.0449069,
+                          -0.130358 0.991467 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.120691 0.990603 0.0643358,
+                          -0.122182 0.992508 0,
+                          -0.0883377 0.996091 0,
+                          -0.120691 0.990603 0.0643358,
+                          -0.130766 0.991365 0.00976412,
+                          -0.122182 0.992508 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.075345 0.293716 0.952919,
+                          -0.0516635 0 0.998665,
+                          -0.101268 0 0.994859,
+                          -0.0928257 0.991112 0.095287,
+                          -0.120691 0.990603 0.0643358,
+                          -0.0883377 0.996091 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.162938 0.243456 0.956128,
+                          -0.101268 0 0.994859,
+                          -0.146923 0 0.989148,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.121508 0.269411 0.955329,
+                          -0.075345 0.293716 0.952919,
+                          -0.101268 0 0.994859,
+                          -0.162938 0.243456 0.956128,
+                          -0.121508 0.269411 0.955329,
+                          -0.101268 0 0.994859,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.199474 0.216309 0.95573,
+                          -0.146923 0 0.989148,
+                          -0.187938 0 0.982181,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.199474 0.216309 0.95573,
+                          -0.162938 0.243456 0.956128,
+                          -0.146923 0 0.989148,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.231087 0.188339 0.95453,
+                          -0.187938 0 0.982181,
+                          -0.223838 0 0.974626,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.231087 0.188339 0.95453,
+                          -0.199474 0.216309 0.95573,
+                          -0.187938 0 0.982181,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.257838 0.159833 0.952876,
+                          -0.223838 0 0.974626,
+                          -0.254336 0 0.967116,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.257838 0.159833 0.952876,
+                          -0.231087 0.188339 0.95453,
+                          -0.223838 0 0.974626,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.279841 0.131 0.951067,
+                          -0.254336 0 0.967116,
+                          -0.27929 0 0.960207,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.279841 0.131 0.951067,
+                          -0.257838 0.159833 0.952876,
+                          -0.254336 0 0.967116,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.297231 0.101984 0.949344,
+                          -0.27929 0 0.960207,
+                          -0.298657 0 0.95436,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.297231 0.101984 0.949344,
+                          -0.279841 0.131 0.951067,
+                          -0.27929 0 0.960207,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.310138 0.072878 0.947894,
+                          -0.298657 0 0.95436,
+                          -0.312451 0 0.949934,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.310138 0.072878 0.947894,
+                          -0.297231 0.101984 0.949344,
+                          -0.298657 0 0.95436,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.318676 0.0437343 0.946854,
+                          -0.312451 0 0.949934,
+                          -0.320706 0 0.947179,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.318676 0.0437343 0.946854,
+                          -0.310138 0.072878 0.947894,
+                          -0.312451 0 0.949934,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.322924 0.0145788 0.946313,
+                          -0.320706 0 0.947179,
+                          -0.323454 0 0.946244,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.322924 0.0145788 0.946313,
+                          -0.318676 0.0437343 0.946854,
+                          -0.320706 0 0.947179,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.322924 -0.0145788 0.946313,
+                          -0.323454 0 0.946244,
+                          -0.320706 0 0.947179,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.322924 -0.0145788 0.946313,
+                          -0.322924 0.0145788 0.946313,
+                          -0.323454 0 0.946244,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.318676 -0.0437343 0.946854,
+                          -0.320706 0 0.947179,
+                          -0.312451 0 0.949934,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.318676 -0.0437343 0.946854,
+                          -0.322924 -0.0145788 0.946313,
+                          -0.320706 0 0.947179,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.310138 -0.072878 0.947894,
+                          -0.312451 0 0.949934,
+                          -0.298657 0 0.95436,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.310138 -0.072878 0.947894,
+                          -0.318676 -0.0437343 0.946854,
+                          -0.312451 0 0.949934,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.297231 -0.101984 0.949344,
+                          -0.298657 0 0.95436,
+                          -0.27929 0 0.960207,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.297231 -0.101984 0.949344,
+                          -0.310138 -0.072878 0.947894,
+                          -0.298657 0 0.95436,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.279841 -0.131 0.951067,
+                          -0.27929 0 0.960207,
+                          -0.254336 0 0.967116,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.279841 -0.131 0.951067,
+                          -0.297231 -0.101984 0.949344,
+                          -0.27929 0 0.960207,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.257838 -0.159833 0.952876,
+                          -0.254336 0 0.967116,
+                          -0.223838 0 0.974626,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.257838 -0.159833 0.952876,
+                          -0.279841 -0.131 0.951067,
+                          -0.254336 0 0.967116,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.231087 -0.188339 0.95453,
+                          -0.223838 0 0.974626,
+                          -0.187938 0 0.982181,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.231087 -0.188339 0.95453,
+                          -0.257838 -0.159833 0.952876,
+                          -0.223838 0 0.974626,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.199474 -0.216309 0.95573,
+                          -0.187938 0 0.982181,
+                          -0.146923 0 0.989148,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.199474 -0.216309 0.95573,
+                          -0.231087 -0.188339 0.95453,
+                          -0.187938 0 0.982181,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.162938 -0.243456 0.956128,
+                          -0.146923 0 0.989148,
+                          -0.101268 0 0.994859,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.162938 -0.243456 0.956128,
+                          -0.199474 -0.216309 0.95573,
+                          -0.146923 0 0.989148,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.121508 -0.269411 0.955329,
+                          -0.101268 0 0.994859,
+                          -0.0516635 0 0.998665,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -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.121508 -0.269411 0.955329,
+                          -0.162938 -0.243456 0.956128,
+                          -0.101268 0 0.994859,
+                          -0.0928257 -0.991112 0.095287,
+                          -0.0883377 -0.996091 0,
+                          -0.122182 -0.992508 0,
+                          -0.075345 -0.293716 0.952919,
+                          -0.121508 -0.269411 0.955329,
+                          -0.0516635 0 0.998665,
+                          -0.130766 -0.991365 0.00976412,
+                          -0.122182 -0.992508 0,
+                          -0.130358 -0.991467 0,
+                          -0.0937875 -0.98854 0.118289,
+                          -0.0928257 -0.991112 0.095287,
+                          -0.122182 -0.992508 0,
+                          -0.120691 -0.990603 0.0643358,
+                          -0.0937875 -0.98854 0.118289,
+                          -0.122182 -0.992508 0,
+                          -0.130766 -0.991365 0.00976412,
+                          -0.120691 -0.990603 0.0643358,
+                          -0.122182 -0.992508 0,
+                          -0.12407 -0.991257 -0.0449069,
+                          -0.130358 -0.991467 0,
+                          -0.112639 -0.993636 0,
+                          -0.12407 -0.991257 -0.0449069,
+                          -0.130766 -0.991365 0.00976412,
+                          -0.130358 -0.991467 0,
+                          -0.100566 -0.989974 -0.0991901,
+                          -0.112639 -0.993636 0,
+                          -0.0695545 -0.997578 0,
+                          -0.100566 -0.989974 -0.0991901,
+                          -0.12407 -0.991257 -0.0449069,
+                          -0.112639 -0.993636 0,
+                          -0.0602187 -0.986488 -0.152367,
+                          -0.0695545 -0.997578 0,
+                          -0.00292088 -0.999996 0,
+                          -0.0602187 -0.986488 -0.152367,
+                          -0.100566 -0.989974 -0.0991901,
+                          -0.0695545 -0.997578 0,
+                          -0.00277184 -0.216815 -0.976209,
+                          -0.00219066 0 -0.999998,
+                          -0.0310915 0 -0.999517,
+                          -0.0602187 -0.986488 -0.152367,
+                          -0.00292088 -0.999996 0,
+                          -0.00330516 -0.979122 -0.203248,
+                          -0.0567799 -0.178256 -0.982345,
+                          -0.0310915 0 -0.999517,
+                          -0.0574448 0 -0.998349,
+                          -0.0311303 -0.197857 -0.979736,
+                          -0.00277184 -0.216815 -0.976209,
+                          -0.0310915 0 -0.999517,
+                          -0.0567799 -0.178256 -0.982345,
+                          -0.0311303 -0.197857 -0.979736,
+                          -0.0310915 0 -0.999517,
+                          -0.0796358 -0.158149 -0.984199,
+                          -0.0574448 0 -0.998349,
+                          -0.0810413 0 -0.996711,
+                          -0.0796358 -0.158149 -0.984199,
+                          -0.0567799 -0.178256 -0.982345,
+                          -0.0574448 0 -0.998349,
+                          -0.0996468 -0.13765 -0.985456,
+                          -0.0810413 0 -0.996711,
+                          -0.101719 0 -0.994813,
+                          -0.0996468 -0.13765 -0.985456,
+                          -0.0796358 -0.158149 -0.984199,
+                          -0.0810413 0 -0.996711,
+                          -0.116788 -0.116857 -0.986258,
+                          -0.101719 0 -0.994813,
+                          -0.119359 0 -0.992851,
+                          -0.116788 -0.116857 -0.986258,
+                          -0.0996468 -0.13765 -0.985456,
+                          -0.101719 0 -0.994813,
+                          -0.131051 -0.0958475 -0.986731,
+                          -0.119359 0 -0.992851,
+                          -0.133876 0 -0.990998,
+                          -0.131051 -0.0958475 -0.986731,
+                          -0.116788 -0.116857 -0.986258,
+                          -0.119359 0 -0.992851,
+                          -0.142442 -0.0746828 -0.986982,
+                          -0.133876 0 -0.990998,
+                          -0.145213 0 -0.9894,
+                          -0.142442 -0.0746828 -0.986982,
+                          -0.131051 -0.0958475 -0.986731,
+                          -0.133876 0 -0.990998,
+                          -0.15097 -0.0534118 -0.987094,
+                          -0.145213 0 -0.9894,
+                          -0.153331 0 -0.988175,
+                          -0.15097 -0.0534118 -0.987094,
+                          -0.142442 -0.0746828 -0.986982,
+                          -0.145213 0 -0.9894,
+                          -0.156647 -0.0320723 -0.987134,
+                          -0.153331 0 -0.988175,
+                          -0.15821 0 -0.987405,
+                          -0.156647 -0.0320723 -0.987134,
+                          -0.15097 -0.0534118 -0.987094,
+                          -0.153331 0 -0.988175,
+                          -0.159483 -0.0106948 -0.987143,
+                          -0.15821 0 -0.987405,
+                          -0.159837 0 -0.987143,
+                          -0.159483 -0.0106948 -0.987143,
+                          -0.156647 -0.0320723 -0.987134,
+                          -0.15821 0 -0.987405,
+                          -0.159483 0.0106948 -0.987143,
+                          -0.159837 0 -0.987143,
+                          -0.15821 0 -0.987405,
+                          -0.159483 0.0106948 -0.987143,
+                          -0.159483 -0.0106948 -0.987143,
+                          -0.159837 0 -0.987143,
+                          -0.156647 0.0320723 -0.987134,
+                          -0.15821 0 -0.987405,
+                          -0.153331 0 -0.988175,
+                          -0.156647 0.0320723 -0.987134,
+                          -0.159483 0.0106948 -0.987143,
+                          -0.15821 0 -0.987405,
+                          -0.15097 0.0534118 -0.987094,
+                          -0.153331 0 -0.988175,
+                          -0.145213 0 -0.9894,
+                          -0.15097 0.0534118 -0.987094,
+                          -0.156647 0.0320723 -0.987134,
+                          -0.153331 0 -0.988175,
+                          -0.142442 0.0746828 -0.986982,
+                          -0.145213 0 -0.9894,
+                          -0.133876 0 -0.990998,
+                          -0.142442 0.0746828 -0.986982,
+                          -0.15097 0.0534118 -0.987094,
+                          -0.145213 0 -0.9894,
+                          -0.131051 0.0958475 -0.986731,
+                          -0.133876 0 -0.990998,
+                          -0.119359 0 -0.992851,
+                          -0.131051 0.0958475 -0.986731,
+                          -0.142442 0.0746828 -0.986982,
+                          -0.133876 0 -0.990998,
+                          -0.116788 0.116857 -0.986258,
+                          -0.119359 0 -0.992851,
+                          -0.101719 0 -0.994813,
+                          -0.116788 0.116857 -0.986258,
+                          -0.131051 0.0958475 -0.986731,
+                          -0.119359 0 -0.992851,
+                          -0.0996468 0.13765 -0.985456,
+                          -0.101719 0 -0.994813,
+                          -0.0810413 0 -0.996711,
+                          -0.0996468 0.13765 -0.985456,
+                          -0.116788 0.116857 -0.986258,
+                          -0.101719 0 -0.994813,
+                          -0.0796358 0.158149 -0.984199,
+                          -0.0810413 0 -0.996711,
+                          -0.0574448 0 -0.998349,
+                          -0.0796358 0.158149 -0.984199,
+                          -0.0996468 0.13765 -0.985456,
+                          -0.0810413 0 -0.996711,
+                          -0.0567799 0.178256 -0.982345,
+                          -0.0574448 0 -0.998349,
+                          -0.0310915 0 -0.999517,
+                          -0.0567799 0.178256 -0.982345,
+                          -0.0796358 0.158149 -0.984199,
+                          -0.0574448 0 -0.998349,
+                          -0.0311303 0.197857 -0.979736,
+                          -0.0567799 0.178256 -0.982345,
+                          -0.0310915 0 -0.999517,
+                          -0.0744057 0.556935 -0.827216,
+                          -0.00351257 0.605941 -0.795502,
+                          -0.00363367 0.737642 -0.675182,
+                          -0.0570418 0.907216 -0.416781,
+                          -0.00363367 0.737642 -0.675182,
+                          -0.00364513 0.832943 -0.553347,
+                          -1.24008e-16 0.558483 -0.829516,
+                          -1.24008e-16 0.558483 -0.829516,
+                          -1.63791e-16 0.737647 -0.675187,
+                          -0.0634627 0.871732 -0.485857,
+                          -0.00363367 0.737642 -0.675182,
+                          -0.0570418 0.907216 -0.416781,
+                          -1.63791e-16 0.737647 -0.675187,
+                          -1.63791e-16 0.737647 -0.675187,
+                          -1.93954e-16 0.873492 -0.486838,
+                          -1.24008e-16 0.558483 -0.829516,
+                          -1.63791e-16 0.737647 -0.675187,
+                          -1.63791e-16 0.737647 -0.675187,
+                          -0.0744057 0.556935 -0.827216,
+                          -0.0302389 0.553907 -0.832029,
+                          -0.00351257 0.605941 -0.795502,
+                          -0.00323056 0.428292 -0.903634,
+                          -0.00351257 0.605941 -0.795502,
+                          -0.0302389 0.553907 -0.832029,
+                          -0.0591211 0.954122 -0.293522,
+                          -0.00364513 0.832943 -0.553347,
+                          -0.0035477 0.919112 -0.39398,
+                          -0.0591211 0.954122 -0.293522,
+                          -0.0570418 0.907216 -0.416781,
+                          -0.00364513 0.832943 -0.553347,
+                          -0.0744057 0.556935 -0.827216,
+                          -0.0550007 0.499809 -0.864388,
+                          -0.0302389 0.553907 -0.832029,
+                          -0.0312543 0.389387 -0.920544,
+                          -0.0302389 0.553907 -0.832029,
+                          -0.0550007 0.499809 -0.864388,
+                          -0.0312543 0.389387 -0.920544,
+                          -0.00323056 0.428292 -0.903634,
+                          -0.0302389 0.553907 -0.832029,
+                          -0.0744057 0.556935 -0.827216,
+                          -0.0775254 0.444031 -0.892651,
+                          -0.0550007 0.499809 -0.864388,
+                          -0.0566965 0.349679 -0.935153,
+                          -0.0550007 0.499809 -0.864388,
+                          -0.0775254 0.444031 -0.892651,
+                          -0.0312543 0.389387 -0.920544,
+                          -0.0550007 0.499809 -0.864388,
+                          -0.0566965 0.349679 -0.935153,
+                          -0.127811 0.345236 -0.929772,
+                          -0.0975943 0.38692 -0.916934,
+                          -0.0775254 0.444031 -0.892651,
+                          -0.0794443 0.309371 -0.947617,
+                          -0.0775254 0.444031 -0.892651,
+                          -0.0975943 0.38692 -0.916934,
+                          -0.0744057 0.556935 -0.827216,
+                          -0.127811 0.345236 -0.929772,
+                          -0.0775254 0.444031 -0.892651,
+                          -0.0566965 0.349679 -0.935153,
+                          -0.0775254 0.444031 -0.892651,
+                          -0.0794443 0.309371 -0.947617,
+                          -0.127811 0.345236 -0.929772,
+                          -0.115037 0.328779 -0.937374,
+                          -0.0975943 0.38692 -0.916934,
+                          -0.09942 0.268634 -0.958098,
+                          -0.0975943 0.38692 -0.916934,
+                          -0.115037 0.328779 -0.937374,
+                          -0.0794443 0.309371 -0.947617,
+                          -0.0975943 0.38692 -0.916934,
+                          -0.09942 0.268634 -0.958098,
+                          -0.127811 0.345236 -0.929772,
+                          -0.129726 0.269866 -0.954119,
+                          -0.115037 0.328779 -0.937374,
+                          -0.116575 0.227601 -0.966751,
+                          -0.115037 0.328779 -0.937374,
+                          -0.129726 0.269866 -0.954119,
+                          -0.09942 0.268634 -0.958098,
+                          -0.115037 0.328779 -0.937374,
+                          -0.116575 0.227601 -0.966751,
+                          -0.156213 0.116783 -0.980795,
+                          -0.141567 0.210392 -0.967313,
+                          -0.129726 0.269866 -0.954119,
+                          -0.130881 0.186376 -0.973722,
+                          -0.129726 0.269866 -0.954119,
+                          -0.141567 0.210392 -0.967313,
+                          -0.127811 0.345236 -0.929772,
+                          -0.156213 0.116783 -0.980795,
+                          -0.129726 0.269866 -0.954119,
+                          -0.116575 0.227601 -0.966751,
+                          -0.129726 0.269866 -0.954119,
+                          -0.130881 0.186376 -0.973722,
+                          -0.156213 0.116783 -0.980795,
+                          -0.150496 0.150528 -0.977084,
+                          -0.141567 0.210392 -0.967313,
+                          -0.142325 0.145034 -0.979137,
+                          -0.141567 0.210392 -0.967313,
+                          -0.150496 0.150528 -0.977084,
+                          -0.130881 0.186376 -0.973722,
+                          -0.141567 0.210392 -0.967313,
+                          -0.142325 0.145034 -0.979137,
+                          -0.156213 0.116783 -0.980795,
+                          -0.15647 0.0904109 -0.983536,
+                          -0.150496 0.150528 -0.977084,
+                          -0.150905 0.103626 -0.983102,
+                          -0.150496 0.150528 -0.977084,
+                          -0.15647 0.0904109 -0.983536,
+                          -0.142325 0.145034 -0.979137,
+                          -0.150496 0.150528 -0.977084,
+                          -0.150905 0.103626 -0.983102,
+                          -0.156213 -0.116783 -0.980795,
+                          -0.159463 0.0301521 -0.986743,
+                          -0.15647 0.0904109 -0.983536,
+                          -0.156623 0.0621853 -0.985699,
+                          -0.15647 0.0904109 -0.983536,
+                          -0.159463 0.0301521 -0.986743,
+                          -0.156213 0.116783 -0.980795,
+                          -0.156213 -0.116783 -0.980795,
+                          -0.15647 0.0904109 -0.983536,
+                          -0.150905 0.103626 -0.983102,
+                          -0.15647 0.0904109 -0.983536,
+                          -0.156623 0.0621853 -0.985699,
+                          -0.156213 -0.116783 -0.980795,
+                          -0.159463 -0.0301521 -0.986743,
+                          -0.159463 0.0301521 -0.986743,
+                          -0.15948 0.0207297 -0.986983,
+                          -0.159463 0.0301521 -0.986743,
+                          -0.159463 -0.0301521 -0.986743,
+                          -0.156623 0.0621853 -0.985699,
+                          -0.159463 0.0301521 -0.986743,
+                          -0.15948 0.0207297 -0.986983,
+                          -0.156213 -0.116783 -0.980795,
+                          -0.15647 -0.0904109 -0.983536,
+                          -0.159463 -0.0301521 -0.986743,
+                          -0.15948 -0.0207297 -0.986983,
+                          -0.159463 -0.0301521 -0.986743,
+                          -0.15647 -0.0904109 -0.983536,
+                          -0.15948 0.0207297 -0.986983,
+                          -0.159463 -0.0301521 -0.986743,
+                          -0.15948 -0.0207297 -0.986983,
+                          -0.127811 -0.345236 -0.929772,
+                          -0.150496 -0.150528 -0.977084,
+                          -0.15647 -0.0904109 -0.983536,
+                          -0.156623 -0.0621853 -0.985699,
+                          -0.15647 -0.0904109 -0.983536,
+                          -0.150496 -0.150528 -0.977084,
+                          -0.156213 -0.116783 -0.980795,
+                          -0.127811 -0.345236 -0.929772,
+                          -0.15647 -0.0904109 -0.983536,
+                          -0.15948 -0.0207297 -0.986983,
+                          -0.15647 -0.0904109 -0.983536,
+                          -0.156623 -0.0621853 -0.985699,
+                          -0.127811 -0.345236 -0.929772,
+                          -0.141567 -0.210392 -0.967313,
+                          -0.150496 -0.150528 -0.977084,
+                          -0.150905 -0.103626 -0.983102,
+                          -0.150496 -0.150528 -0.977084,
+                          -0.141567 -0.210392 -0.967313,
+                          -0.156623 -0.0621853 -0.985699,
+                          -0.150496 -0.150528 -0.977084,
+                          -0.150905 -0.103626 -0.983102,
+                          -0.127811 -0.345236 -0.929772,
+                          -0.129726 -0.269866 -0.954119,
+                          -0.141567 -0.210392 -0.967313,
+                          -0.142325 -0.145034 -0.979137,
+                          -0.141567 -0.210392 -0.967313,
+                          -0.129726 -0.269866 -0.954119,
+                          -0.150905 -0.103626 -0.983102,
+                          -0.141567 -0.210392 -0.967313,
+                          -0.142325 -0.145034 -0.979137,
+                          -0.0744057 -0.556935 -0.827216,
+                          -0.115037 -0.328779 -0.937374,
+                          -0.129726 -0.269866 -0.954119,
+                          -0.130881 -0.186376 -0.973722,
+                          -0.129726 -0.269866 -0.954119,
+                          -0.115037 -0.328779 -0.937374,
+                          -0.127811 -0.345236 -0.929772,
+                          -0.0744057 -0.556935 -0.827216,
+                          -0.129726 -0.269866 -0.954119,
+                          -0.142325 -0.145034 -0.979137,
+                          -0.129726 -0.269866 -0.954119,
+                          -0.130881 -0.186376 -0.973722,
+                          -0.0744057 -0.556935 -0.827216,
+                          -0.0975943 -0.38692 -0.916934,
+                          -0.115037 -0.328779 -0.937374,
+                          -0.116575 -0.227601 -0.966751,
+                          -0.115037 -0.328779 -0.937374,
+                          -0.0975943 -0.38692 -0.916934,
+                          -0.130881 -0.186376 -0.973722,
+                          -0.115037 -0.328779 -0.937374,
+                          -0.116575 -0.227601 -0.966751,
+                          -0.0744057 -0.556935 -0.827216,
+                          -0.0775254 -0.444031 -0.892651,
+                          -0.0975943 -0.38692 -0.916934,
+                          -0.09942 -0.268634 -0.958098,
+                          -0.0975943 -0.38692 -0.916934,
+                          -0.0775254 -0.444031 -0.892651,
+                          -0.116575 -0.227601 -0.966751,
+                          -0.0975943 -0.38692 -0.916934,
+                          -0.09942 -0.268634 -0.958098,
+                          -0.00363367 -0.737642 -0.675182,
+                          -0.0550007 -0.499809 -0.864388,
+                          -0.0775254 -0.444031 -0.892651,
+                          -0.0794443 -0.309371 -0.947617,
+                          -0.0775254 -0.444031 -0.892651,
+                          -0.0550007 -0.499809 -0.864388,
+                          -0.0744057 -0.556935 -0.827216,
+                          -0.00363367 -0.737642 -0.675182,
+                          -0.0775254 -0.444031 -0.892651,
+                          -0.09942 -0.268634 -0.958098,
+                          -0.0775254 -0.444031 -0.892651,
+                          -0.0794443 -0.309371 -0.947617,
+                          -0.00363367 -0.737642 -0.675182,
+                          -0.0302389 -0.553907 -0.832029,
+                          -0.0550007 -0.499809 -0.864388,
+                          -0.0566965 -0.349679 -0.935153,
+                          -0.0550007 -0.499809 -0.864388,
+                          -0.0302389 -0.553907 -0.832029,
+                          -0.0794443 -0.309371 -0.947617,
+                          -0.0550007 -0.499809 -0.864388,
+                          -0.0566965 -0.349679 -0.935153,
+                          -0.00363367 -0.737642 -0.675182,
+                          -0.00351257 -0.605941 -0.795502,
+                          -0.0302389 -0.553907 -0.832029,
+                          -0.0312543 -0.389387 -0.920544,
+                          -0.0302389 -0.553907 -0.832029,
+                          -0.00351257 -0.605941 -0.795502,
+                          -0.0566965 -0.349679 -0.935153,
+                          -0.0302389 -0.553907 -0.832029,
+                          -0.0312543 -0.389387 -0.920544,
+                          -0.0634627 -0.871732 -0.485857,
+                          -0.00364513 -0.832943 -0.553347,
+                          -0.00363367 -0.737642 -0.675182,
+                          -0.0312543 -0.389387 -0.920544,
+                          -0.00351257 -0.605941 -0.795502,
+                          -0.00323056 -0.428292 -0.903634,
+                          -0.0570418 -0.907216 -0.416781,
+                          -0.0035477 -0.919112 -0.39398,
+                          -0.00364513 -0.832943 -0.553347,
+                          -0.0634627 -0.871732 -0.485857,
+                          -0.0570418 -0.907216 -0.416781,
+                          -0.00364513 -0.832943 -0.553347,
+                          1.63791e-16 -0.737647 -0.675187,
+                          1.63791e-16 -0.737647 -0.675187,
+                          1.24008e-16 -0.558483 -0.829516,
+                          1.96507e-16 -0.884991 -0.465609,
+                          1.93954e-16 -0.873492 -0.486838,
+                          1.63791e-16 -0.737647 -0.675187,
+                          1.96507e-16 -0.884991 -0.465609,
+                          1.63791e-16 -0.737647 -0.675187,
+                          1.63791e-16 -0.737647 -0.675187,
+                          1.24008e-16 -0.558483 -0.829516,
+                          1.24008e-16 -0.558483 -0.829516,
+                          7.72917e-17 -0.348091 -0.937461,
+                          1.63791e-16 -0.737647 -0.675187,
+                          1.24008e-16 -0.558483 -0.829516,
+                          1.24008e-16 -0.558483 -0.829516,
+                          7.72917e-17 -0.348091 -0.937461,
+                          7.72917e-17 -0.348091 -0.937461,
+                          2.62532e-17 -0.118234 -0.992986,
+                          1.24008e-16 -0.558483 -0.829516,
+                          7.72917e-17 -0.348091 -0.937461,
+                          7.72917e-17 -0.348091 -0.937461,
+                          2.62532e-17 -0.118234 -0.992986,
+                          2.62532e-17 -0.118234 -0.992986,
+                          -2.62532e-17 0.118234 -0.992986,
+                          7.72917e-17 -0.348091 -0.937461,
+                          2.62532e-17 -0.118234 -0.992986,
+                          2.62532e-17 -0.118234 -0.992986,
+                          -2.62532e-17 0.118234 -0.992986,
+                          -2.62532e-17 0.118234 -0.992986,
+                          -7.72917e-17 0.348091 -0.937461,
+                          2.62532e-17 -0.118234 -0.992986,
+                          -2.62532e-17 0.118234 -0.992986,
+                          -2.62532e-17 0.118234 -0.992986,
+                          -7.72917e-17 0.348091 -0.937461,
+                          -7.72917e-17 0.348091 -0.937461,
+                          -1.24008e-16 0.558483 -0.829516,
+                          -2.62532e-17 0.118234 -0.992986,
+                          -7.72917e-17 0.348091 -0.937461,
+                          -7.72917e-17 0.348091 -0.937461,
+                          -7.72917e-17 0.348091 -0.937461,
+                          -1.24008e-16 0.558483 -0.829516,
+                          -1.24008e-16 0.558483 -0.829516,
+                          -0.00323056 -0.428292 -0.903634,
+                          -0.00277184 -0.216815 -0.976209,
+                          -0.0311303 -0.197857 -0.979736,
+                          -0.0591211 -0.954122 -0.293522,
+                          -0.00330516 -0.979122 -0.203248,
+                          -0.0035477 -0.919112 -0.39398,
+                          -0.0591211 -0.954122 -0.293522,
+                          -0.0602187 -0.986488 -0.152367,
+                          -0.00330516 -0.979122 -0.203248,
+                          -0.0312543 -0.389387 -0.920544,
+                          -0.0311303 -0.197857 -0.979736,
+                          -0.0567799 -0.178256 -0.982345,
+                          -0.0312543 -0.389387 -0.920544,
+                          -0.00323056 -0.428292 -0.903634,
+                          -0.0311303 -0.197857 -0.979736,
+                          -0.0566965 -0.349679 -0.935153,
+                          -0.0567799 -0.178256 -0.982345,
+                          -0.0796358 -0.158149 -0.984199,
+                          -0.0566965 -0.349679 -0.935153,
+                          -0.0312543 -0.389387 -0.920544,
+                          -0.0567799 -0.178256 -0.982345,
+                          -0.0794443 -0.309371 -0.947617,
+                          -0.0796358 -0.158149 -0.984199,
+                          -0.0996468 -0.13765 -0.985456,
+                          -0.0794443 -0.309371 -0.947617,
+                          -0.0566965 -0.349679 -0.935153,
+                          -0.0796358 -0.158149 -0.984199,
+                          -0.09942 -0.268634 -0.958098,
+                          -0.0996468 -0.13765 -0.985456,
+                          -0.116788 -0.116857 -0.986258,
+                          -0.09942 -0.268634 -0.958098,
+                          -0.0794443 -0.309371 -0.947617,
+                          -0.0996468 -0.13765 -0.985456,
+                          -0.116575 -0.227601 -0.966751,
+                          -0.116788 -0.116857 -0.986258,
+                          -0.131051 -0.0958475 -0.986731,
+                          -0.116575 -0.227601 -0.966751,
+                          -0.09942 -0.268634 -0.958098,
+                          -0.116788 -0.116857 -0.986258,
+                          -0.130881 -0.186376 -0.973722,
+                          -0.131051 -0.0958475 -0.986731,
+                          -0.142442 -0.0746828 -0.986982,
+                          -0.130881 -0.186376 -0.973722,
+                          -0.116575 -0.227601 -0.966751,
+                          -0.131051 -0.0958475 -0.986731,
+                          -0.142325 -0.145034 -0.979137,
+                          -0.142442 -0.0746828 -0.986982,
+                          -0.15097 -0.0534118 -0.987094,
+                          -0.142325 -0.145034 -0.979137,
+                          -0.130881 -0.186376 -0.973722,
+                          -0.142442 -0.0746828 -0.986982,
+                          -0.150905 -0.103626 -0.983102,
+                          -0.15097 -0.0534118 -0.987094,
+                          -0.156647 -0.0320723 -0.987134,
+                          -0.150905 -0.103626 -0.983102,
+                          -0.142325 -0.145034 -0.979137,
+                          -0.15097 -0.0534118 -0.987094,
+                          -0.156623 -0.0621853 -0.985699,
+                          -0.156647 -0.0320723 -0.987134,
+                          -0.159483 -0.0106948 -0.987143,
+                          -0.156623 -0.0621853 -0.985699,
+                          -0.150905 -0.103626 -0.983102,
+                          -0.156647 -0.0320723 -0.987134,
+                          -0.15948 -0.0207297 -0.986983,
+                          -0.159483 -0.0106948 -0.987143,
+                          -0.159483 0.0106948 -0.987143,
+                          -0.15948 -0.0207297 -0.986983,
+                          -0.156623 -0.0621853 -0.985699,
+                          -0.159483 -0.0106948 -0.987143,
+                          -0.15948 0.0207297 -0.986983,
+                          -0.159483 0.0106948 -0.987143,
+                          -0.156647 0.0320723 -0.987134,
+                          -0.15948 0.0207297 -0.986983,
+                          -0.15948 -0.0207297 -0.986983,
+                          -0.159483 0.0106948 -0.987143,
+                          -0.156623 0.0621853 -0.985699,
+                          -0.156647 0.0320723 -0.987134,
+                          -0.15097 0.0534118 -0.987094,
+                          -0.156623 0.0621853 -0.985699,
+                          -0.15948 0.0207297 -0.986983,
+                          -0.156647 0.0320723 -0.987134,
+                          -0.150905 0.103626 -0.983102,
+                          -0.15097 0.0534118 -0.987094,
+                          -0.142442 0.0746828 -0.986982,
+                          -0.150905 0.103626 -0.983102,
+                          -0.156623 0.0621853 -0.985699,
+                          -0.15097 0.0534118 -0.987094,
+                          -0.142325 0.145034 -0.979137,
+                          -0.142442 0.0746828 -0.986982,
+                          -0.131051 0.0958475 -0.986731,
+                          -0.142325 0.145034 -0.979137,
+                          -0.150905 0.103626 -0.983102,
+                          -0.142442 0.0746828 -0.986982,
+                          -0.130881 0.186376 -0.973722,
+                          -0.131051 0.0958475 -0.986731,
+                          -0.116788 0.116857 -0.986258,
+                          -0.130881 0.186376 -0.973722,
+                          -0.142325 0.145034 -0.979137,
+                          -0.131051 0.0958475 -0.986731,
+                          -0.116575 0.227601 -0.966751,
+                          -0.116788 0.116857 -0.986258,
+                          -0.0996468 0.13765 -0.985456,
+                          -0.116575 0.227601 -0.966751,
+                          -0.130881 0.186376 -0.973722,
+                          -0.116788 0.116857 -0.986258,
+                          -0.09942 0.268634 -0.958098,
+                          -0.0996468 0.13765 -0.985456,
+                          -0.0796358 0.158149 -0.984199,
+                          -0.09942 0.268634 -0.958098,
+                          -0.116575 0.227601 -0.966751,
+                          -0.0996468 0.13765 -0.985456,
+                          -0.0794443 0.309371 -0.947617,
+                          -0.0796358 0.158149 -0.984199,
+                          -0.0567799 0.178256 -0.982345,
+                          -0.0794443 0.309371 -0.947617,
+                          -0.09942 0.268634 -0.958098,
+                          -0.0796358 0.158149 -0.984199,
+                          -0.0566965 0.349679 -0.935153,
+                          -0.0567799 0.178256 -0.982345,
+                          -0.0311303 0.197857 -0.979736,
+                          -0.0566965 0.349679 -0.935153,
+                          -0.0794443 0.309371 -0.947617,
+                          -0.0567799 0.178256 -0.982345,
+                          -0.0312543 0.389387 -0.920544,
+                          -0.0311303 0.197857 -0.979736,
+                          -0.00277184 0.216815 -0.976209,
+                          -0.0312543 0.389387 -0.920544,
+                          -0.0566965 0.349679 -0.935153,
+                          -0.0311303 0.197857 -0.979736,
+                          -0.0312543 0.389387 -0.920544,
+                          -0.00277184 0.216815 -0.976209,
+                          -0.00323056 0.428292 -0.903634,
+                          -0.0602187 0.986488 -0.152367,
+                          -0.0035477 0.919112 -0.39398,
+                          -0.00330516 0.979122 -0.203248,
+                          -0.0591211 0.954122 -0.293522,
+                          -0.0035477 0.919112 -0.39398,
+                          -0.0602187 0.986488 -0.152367,
+                          -0.0591211 -0.954122 -0.293522,
+                          -0.0035477 -0.919112 -0.39398,
+                          -0.0570418 -0.907216 -0.416781,
+                          -0.127172 0.974071 0.187119,
+                          -0.100548 0.93436 0.341849,
+                          -0.101571 0.907333 0.407957,
+                          -0.137268 0.783835 0.605608,
+                          -0.101571 0.907333 0.407957,
+                          -0.102089 0.844084 0.526403,
+                          -2.13004e-16 0.959285 0.282441,
+                          -2.18058e-16 0.982044 0.188651,
+                          -2.02516e-16 0.91205 0.410078,
+                          -0.137268 0.783835 0.605608,
+                          -0.171201 0.716241 0.676527,
+                          -0.101571 0.907333 0.407957,
+                          -0.176901 0.766726 0.61712,
+                          -0.101571 0.907333 0.407957,
+                          -0.171201 0.716241 0.676527,
+                          -1.9008e-16 0.856045 0.516901,
+                          -2.02516e-16 0.91205 0.410078,
+                          -1.72975e-16 0.779012 0.627009,
+                          -2.13004e-16 0.959285 0.282441,
+                          -2.02516e-16 0.91205 0.410078,
+                          -1.9008e-16 0.856045 0.516901,
+                          -0.127172 0.974071 0.187119,
+                          -0.10019 0.940744 0.32398,
+                          -0.100548 0.93436 0.341849,
+                          -0.138409 0.672678 0.726875,
+                          -0.102089 0.844084 0.526403,
+                          -0.101883 0.821898 0.560449,
+                          -0.138409 0.672678 0.726875,
+                          -0.137268 0.783835 0.605608,
+                          -0.102089 0.844084 0.526403,
+                          -0.127172 0.974071 0.187119,
+                          -0.123664 0.976477 0.176632,
+                          -0.10019 0.940744 0.32398,
+                          -0.0988373 0.958506 0.267389,
+                          -0.10019 0.940744 0.32398,
+                          -0.123664 0.976477 0.176632,
+                          -0.138409 0.672678 0.726875,
+                          -0.101883 0.821898 0.560449,
+                          -0.0998536 0.734213 0.671536,
+                          -0.127172 0.974071 0.187119,
+                          -0.131179 0.990995 0.0268384,
+                          -0.123664 0.976477 0.176632,
+                          -0.12244 0.984801 0.123187,
+                          -0.123664 0.976477 0.176632,
+                          -0.131179 0.990995 0.0268384,
+                          -0.0976807 0.968957 0.227116,
+                          -0.123664 0.976477 0.176632,
+                          -0.12244 0.984801 0.123187,
+                          -0.0988373 0.958506 0.267389,
+                          -0.123664 0.976477 0.176632,
+                          -0.0976807 0.968957 0.227116,
+                          -0.129367 0.990682 -0.042589,
+                          -0.12232 0.984787 -0.123419,
+                          -0.131179 0.990995 0.0268384,
+                          -0.130987 0.991208 0.018678,
+                          -0.131179 0.990995 0.0268384,
+                          -0.12232 0.984787 -0.123419,
+                          -0.127172 0.974071 0.187119,
+                          -0.129367 0.990682 -0.042589,
+                          -0.131179 0.990995 0.0268384,
+                          -0.12244 0.984801 0.123187,
+                          -0.131179 0.990995 0.0268384,
+                          -0.130987 0.991208 0.018678,
+                          -0.107351 0.95667 -0.270661,
+                          -0.0972889 0.957315 -0.27218,
+                          -0.12232 0.984787 -0.123419,
+                          -0.123252 0.988645 -0.0859612,
+                          -0.12232 0.984787 -0.123419,
+                          -0.0972889 0.957315 -0.27218,
+                          -0.129367 0.990682 -0.042589,
+                          -0.107351 0.95667 -0.270661,
+                          -0.12232 0.984787 -0.123419,
+                          -0.130987 0.991208 0.018678,
+                          -0.12232 0.984787 -0.123419,
+                          -0.123252 0.988645 -0.0859612,
+                          -0.0634627 0.871732 -0.485857,
+                          -0.0570418 0.907216 -0.416781,
+                          -0.0972889 0.957315 -0.27218,
+                          -0.0992384 0.976696 -0.190306,
+                          -0.0972889 0.957315 -0.27218,
+                          -0.0570418 0.907216 -0.416781,
+                          -0.107351 0.95667 -0.270661,
+                          -0.0634627 0.871732 -0.485857,
+                          -0.0972889 0.957315 -0.27218,
+                          -0.123252 0.988645 -0.0859612,
+                          -0.0972889 0.957315 -0.27218,
+                          -0.0992384 0.976696 -0.190306,
+                          -0.0992384 0.976696 -0.190306,
+                          -0.0570418 0.907216 -0.416781,
+                          -0.0591211 0.954122 -0.293522,
+                          -1.96507e-16 0.884988 -0.465614,
+                          -1.93954e-16 0.873492 -0.486838,
+                          -2.13658e-16 0.962231 -0.272235,
+                          -1.96507e-16 0.884988 -0.465614,
+                          -1.63791e-16 0.737647 -0.675187,
+                          -1.93954e-16 0.873492 -0.486838,
+                          -2.16326e-16 0.974247 -0.225484,
+                          -2.13658e-16 0.962231 -0.272235,
+                          -2.2184e-16 0.999077 -0.0429499,
+                          -1.96507e-16 0.884988 -0.465614,
+                          -2.13658e-16 0.962231 -0.272235,
+                          -2.16326e-16 0.974247 -0.225484,
+                          -2.21948e-16 0.999566 0.0294449,
+                          -2.2184e-16 0.999077 -0.0429499,
+                          -2.18058e-16 0.982044 0.188651,
+                          -2.16326e-16 0.974247 -0.225484,
+                          -2.2184e-16 0.999077 -0.0429499,
+                          -2.21948e-16 0.999566 0.0294449,
+                          -2.21948e-16 0.999566 0.0294449,
+                          -2.18058e-16 0.982044 0.188651,
+                          -2.13004e-16 0.959285 0.282441,
+                          -0.0591211 0.954122 -0.293522,
+                          -0.0602187 0.986488 -0.152367,
+                          -0.100566 0.989974 -0.0991901,
+                          -0.0992384 0.976696 -0.190306,
+                          -0.100566 0.989974 -0.0991901,
+                          -0.12407 0.991257 -0.0449069,
+                          -0.0992384 0.976696 -0.190306,
+                          -0.0591211 0.954122 -0.293522,
+                          -0.100566 0.989974 -0.0991901,
+                          -0.123252 0.988645 -0.0859612,
+                          -0.12407 0.991257 -0.0449069,
+                          -0.130766 0.991365 0.00976412,
+                          -0.123252 0.988645 -0.0859612,
+                          -0.0992384 0.976696 -0.190306,
+                          -0.12407 0.991257 -0.0449069,
+                          -0.130987 0.991208 0.018678,
+                          -0.130766 0.991365 0.00976412,
+                          -0.120691 0.990603 0.0643358,
+                          -0.130987 0.991208 0.018678,
+                          -0.123252 0.988645 -0.0859612,
+                          -0.130766 0.991365 0.00976412,
+                          -0.0928257 0.991112 0.095287,
+                          -0.0937875 0.98854 0.118289,
+                          -0.120691 0.990603 0.0643358,
+                          -0.12244 0.984801 0.123187,
+                          -0.120691 0.990603 0.0643358,
+                          -0.0937875 0.98854 0.118289,
+                          -0.12244 0.984801 0.123187,
+                          -0.130987 0.991208 0.018678,
+                          -0.120691 0.990603 0.0643358,
+                          -0.121508 0.269411 0.955329,
+                          -0.0803157 0.364445 0.927755,
+                          -0.075345 0.293716 0.952919,
+                          -0.12244 0.984801 0.123187,
+                          -0.0937875 0.98854 0.118289,
+                          -0.0963029 0.978018 0.18495,
+                          -0.121508 0.269411 0.955329,
+                          -0.0918918 0.553177 0.82798,
+                          -0.0803157 0.364445 0.927755,
+                          -0.0976807 0.968957 0.227116,
+                          -0.12244 0.984801 0.123187,
+                          -0.0963029 0.978018 0.18495,
+                          -0.134366 0.503166 0.85368,
+                          -0.0968077 0.653871 0.750387,
+                          -0.0918918 0.553177 0.82798,
+                          -0.134366 0.503166 0.85368,
+                          -0.0918918 0.553177 0.82798,
+                          -0.121508 0.269411 0.955329,
+                          -0.134366 0.503166 0.85368,
+                          -0.0998536 0.734213 0.671536,
+                          -0.0968077 0.653871 0.750387,
+                          -0.138409 0.672678 0.726875,
+                          -0.0998536 0.734213 0.671536,
+                          -0.134366 0.503166 0.85368,
+                          -0.176901 -0.766726 0.61712,
+                          -0.102089 -0.844084 0.526403,
+                          -0.101571 -0.907333 0.407957,
+                          -0.123664 -0.976477 0.176632,
+                          -0.101571 -0.907333 0.407957,
+                          -0.100548 -0.93436 0.341849,
+                          1.90077e-16 -0.856032 0.516924,
+                          1.72975e-16 -0.779012 0.627009,
+                          2.02516e-16 -0.91205 0.410078,
+                          -0.127172 -0.974071 0.187119,
+                          -0.101571 -0.907333 0.407957,
+                          -0.123664 -0.976477 0.176632,
+                          2.13003e-16 -0.959278 0.282464,
+                          2.02516e-16 -0.91205 0.410078,
+                          2.18058e-16 -0.982044 0.188651,
+                          1.90077e-16 -0.856032 0.516924,
+                          2.02516e-16 -0.91205 0.410078,
+                          2.13003e-16 -0.959278 0.282464,
+                          -0.176901 -0.766726 0.61712,
+                          -0.137268 -0.783835 0.605608,
+                          -0.102089 -0.844084 0.526403,
+                          -0.101883 -0.821898 0.560449,
+                          -0.102089 -0.844084 0.526403,
+                          -0.137268 -0.783835 0.605608,
+                          -0.123664 -0.976477 0.176632,
+                          -0.100548 -0.93436 0.341849,
+                          -0.10019 -0.940744 0.32398,
+                          -0.176901 -0.766726 0.61712,
+                          -0.171201 -0.716241 0.676527,
+                          -0.137268 -0.783835 0.605608,
+                          -0.138409 -0.672678 0.726875,
+                          -0.137268 -0.783835 0.605608,
+                          -0.171201 -0.716241 0.676527,
+                          -0.0998536 -0.734213 0.671536,
+                          -0.137268 -0.783835 0.605608,
+                          -0.138409 -0.672678 0.726875,
+                          -0.101883 -0.821898 0.560449,
+                          -0.137268 -0.783835 0.605608,
+                          -0.0998536 -0.734213 0.671536,
+                          -0.176901 -0.766726 0.61712,
+                          -0.202974 -0.642591 0.738836,
+                          -0.171201 -0.716241 0.676527,
+                          -0.174225 -0.60748 0.774993,
+                          -0.171201 -0.716241 0.676527,
+                          -0.202974 -0.642591 0.738836,
+                          -0.138409 -0.672678 0.726875,
+                          -0.171201 -0.716241 0.676527,
+                          -0.174225 -0.60748 0.774993,
+                          -0.244605 -0.577436 0.778933,
+                          -0.231855 -0.564135 0.792462,
+                          -0.202974 -0.642591 0.738836,
+                          -0.206749 -0.539546 0.816177,
+                          -0.202974 -0.642591 0.738836,
+                          -0.231855 -0.564135 0.792462,
+                          -0.176901 -0.766726 0.61712,
+                          -0.244605 -0.577436 0.778933,
+                          -0.202974 -0.642591 0.738836,
+                          -0.174225 -0.60748 0.774993,
+                          -0.202974 -0.642591 0.738836,
+                          -0.206749 -0.539546 0.816177,
+                          -0.244605 -0.577436 0.778933,
+                          -0.257291 -0.482012 0.837536,
+                          -0.231855 -0.564135 0.792462,
+                          -0.235588 -0.469676 0.850824,
+                          -0.231855 -0.564135 0.792462,
+                          -0.257291 -0.482012 0.837536,
+                          -0.206749 -0.539546 0.816177,
+                          -0.231855 -0.564135 0.792462,
+                          -0.235588 -0.469676 0.850824,
+                          -0.294252 -0.35694 0.886572,
+                          -0.278889 -0.397201 0.87433,
+                          -0.257291 -0.482012 0.837536,
+                          -0.26049 -0.398524 0.879388,
+                          -0.257291 -0.482012 0.837536,
+                          -0.278889 -0.397201 0.87433,
+                          -0.244605 -0.577436 0.778933,
+                          -0.294252 -0.35694 0.886572,
+                          -0.257291 -0.482012 0.837536,
+                          -0.235588 -0.469676 0.850824,
+                          -0.257291 -0.482012 0.837536,
+                          -0.26049 -0.398524 0.879388,
+                          -0.294252 -0.35694 0.886572,
+                          -0.296382 -0.310505 0.903186,
+                          -0.278889 -0.397201 0.87433,
+                          -0.281309 -0.326585 0.902334,
+                          -0.278889 -0.397201 0.87433,
+                          -0.296382 -0.310505 0.903186,
+                          -0.26049 -0.398524 0.879388,
+                          -0.278889 -0.397201 0.87433,
+                          -0.281309 -0.326585 0.902334,
+                          -0.32017 -0.12054 0.93966,
+                          -0.309604 -0.222549 0.924455,
+                          -0.296382 -0.310505 0.903186,
+                          -0.297975 -0.254214 0.920101,
+                          -0.296382 -0.310505 0.903186,
+                          -0.309604 -0.222549 0.924455,
+                          -0.294252 -0.35694 0.886572,
+                          -0.32017 -0.12054 0.93966,
+                          -0.296382 -0.310505 0.903186,
+                          -0.281309 -0.326585 0.902334,
+                          -0.296382 -0.310505 0.903186,
+                          -0.297975 -0.254214 0.920101,
+                          -0.32017 -0.12054 0.93966,
+                          -0.31846 -0.133809 0.938445,
+                          -0.309604 -0.222549 0.924455,
+                          -0.310465 -0.18164 0.933069,
+                          -0.309604 -0.222549 0.924455,
+                          -0.31846 -0.133809 0.938445,
+                          -0.297975 -0.254214 0.920101,
+                          -0.309604 -0.222549 0.924455,
+                          -0.310465 -0.18164 0.933069,
+                          -0.32017 -0.12054 0.93966,
+                          -0.322898 -0.0446473 0.94538,
+                          -0.31846 -0.133809 0.938445,
+                          -0.318781 -0.108993 0.941541,
+                          -0.31846 -0.133809 0.938445,
+                          -0.322898 -0.0446473 0.94538,
+                          -0.310465 -0.18164 0.933069,
+                          -0.31846 -0.133809 0.938445,
+                          -0.318781 -0.108993 0.941541,
+                          -0.32017 0.12054 0.93966,
+                          -0.322898 0.0446473 0.94538,
+                          -0.322898 -0.0446473 0.94538,
+                          -0.322935 -0.0363311 0.945724,
+                          -0.322898 -0.0446473 0.94538,
+                          -0.322898 0.0446473 0.94538,
+                          -0.32017 -0.12054 0.93966,
+                          -0.32017 0.12054 0.93966,
+                          -0.322898 -0.0446473 0.94538,
+                          -0.318781 -0.108993 0.941541,
+                          -0.322898 -0.0446473 0.94538,
+                          -0.322935 -0.0363311 0.945724,
+                          -0.32017 0.12054 0.93966,
+                          -0.31846 0.133809 0.938445,
+                          -0.322898 0.0446473 0.94538,
+                          -0.322935 0.0363311 0.945724,
+                          -0.322898 0.0446473 0.94538,
+                          -0.31846 0.133809 0.938445,
+                          -0.322935 -0.0363311 0.945724,
+                          -0.322898 0.0446473 0.94538,
+                          -0.322935 0.0363311 0.945724,
+                          -0.294252 0.35694 0.886572,
+                          -0.309604 0.222549 0.924455,
+                          -0.31846 0.133809 0.938445,
+                          -0.318781 0.108993 0.941541,
+                          -0.31846 0.133809 0.938445,
+                          -0.309604 0.222549 0.924455,
+                          -0.32017 0.12054 0.93966,
+                          -0.294252 0.35694 0.886572,
+                          -0.31846 0.133809 0.938445,
+                          -0.322935 0.0363311 0.945724,
+                          -0.31846 0.133809 0.938445,
+                          -0.318781 0.108993 0.941541,
+                          -0.294252 0.35694 0.886572,
+                          -0.296382 0.310505 0.903186,
+                          -0.309604 0.222549 0.924455,
+                          -0.310465 0.18164 0.933069,
+                          -0.309604 0.222549 0.924455,
+                          -0.296382 0.310505 0.903186,
+                          -0.318781 0.108993 0.941541,
+                          -0.309604 0.222549 0.924455,
+                          -0.310465 0.18164 0.933069,
+                          -0.244605 0.577436 0.778933,
+                          -0.278889 0.397201 0.87433,
+                          -0.296382 0.310505 0.903186,
+                          -0.297975 0.254214 0.920101,
+                          -0.296382 0.310505 0.903186,
+                          -0.278889 0.397201 0.87433,
+                          -0.294252 0.35694 0.886572,
+                          -0.244605 0.577436 0.778933,
+                          -0.296382 0.310505 0.903186,
+                          -0.310465 0.18164 0.933069,
+                          -0.296382 0.310505 0.903186,
+                          -0.297975 0.254214 0.920101,
+                          -0.244605 0.577436 0.778933,
+                          -0.257291 0.482012 0.837536,
+                          -0.278889 0.397201 0.87433,
+                          -0.281309 0.326585 0.902334,
+                          -0.278889 0.397201 0.87433,
+                          -0.257291 0.482012 0.837536,
+                          -0.297975 0.254214 0.920101,
+                          -0.278889 0.397201 0.87433,
+                          -0.281309 0.326585 0.902334,
+                          -0.244605 0.577436 0.778933,
+                          -0.231855 0.564135 0.792462,
+                          -0.257291 0.482012 0.837536,
+                          -0.26049 0.398524 0.879388,
+                          -0.257291 0.482012 0.837536,
+                          -0.231855 0.564135 0.792462,
+                          -0.281309 0.326585 0.902334,
+                          -0.257291 0.482012 0.837536,
+                          -0.26049 0.398524 0.879388,
+                          -0.176901 0.766726 0.61712,
+                          -0.202974 0.642591 0.738836,
+                          -0.231855 0.564135 0.792462,
+                          -0.235588 0.469676 0.850824,
+                          -0.231855 0.564135 0.792462,
+                          -0.202974 0.642591 0.738836,
+                          -0.244605 0.577436 0.778933,
+                          -0.176901 0.766726 0.61712,
+                          -0.231855 0.564135 0.792462,
+                          -0.26049 0.398524 0.879388,
+                          -0.231855 0.564135 0.792462,
+                          -0.235588 0.469676 0.850824,
+                          -0.176901 0.766726 0.61712,
+                          -0.171201 0.716241 0.676527,
+                          -0.202974 0.642591 0.738836,
+                          -0.206749 0.539546 0.816177,
+                          -0.202974 0.642591 0.738836,
+                          -0.171201 0.716241 0.676527,
+                          -0.235588 0.469676 0.850824,
+                          -0.202974 0.642591 0.738836,
+                          -0.206749 0.539546 0.816177,
+                          -0.174225 0.60748 0.774993,
+                          -0.171201 0.716241 0.676527,
+                          -0.137268 0.783835 0.605608,
+                          -0.206749 0.539546 0.816177,
+                          -0.171201 0.716241 0.676527,
+                          -0.174225 0.60748 0.774993,
+                          -0.174225 0.60748 0.774993,
+                          -0.137268 0.783835 0.605608,
+                          -0.138409 0.672678 0.726875,
+                          -1.54681e-16 0.696623 0.717437,
+                          -1.72975e-16 0.779012 0.627009,
+                          -1.32233e-16 0.595526 0.803336,
+                          -1.9008e-16 0.856045 0.516901,
+                          -1.72975e-16 0.779012 0.627009,
+                          -1.54681e-16 0.696623 0.717437,
+                          -1.09131e-16 0.491482 0.870887,
+                          -1.32233e-16 0.595526 0.803336,
+                          -8.29281e-17 0.373475 0.92764,
+                          -1.54681e-16 0.696623 0.717437,
+                          -1.32233e-16 0.595526 0.803336,
+                          -1.09131e-16 0.491482 0.870887,
+                          -5.64183e-17 0.254086 0.967182,
+                          -8.29281e-17 0.373475 0.92764,
+                          -2.82526e-17 0.127238 0.991872,
+                          -1.09131e-16 0.491482 0.870887,
+                          -8.29281e-17 0.373475 0.92764,
+                          -5.64183e-17 0.254086 0.967182,
+                          -2.92412e-21 1.31691e-05 1,
+                          -2.82526e-17 0.127238 0.991872,
+                          2.82526e-17 -0.127238 0.991872,
+                          -5.64183e-17 0.254086 0.967182,
+                          -2.82526e-17 0.127238 0.991872,
+                          -2.92412e-21 1.31691e-05 1,
+                          5.64127e-17 -0.25406 0.967188,
+                          2.82526e-17 -0.127238 0.991872,
+                          8.29281e-17 -0.373475 0.92764,
+                          -2.92412e-21 1.31691e-05 1,
+                          2.82526e-17 -0.127238 0.991872,
+                          5.64127e-17 -0.25406 0.967188,
+                          1.09126e-16 -0.49146 0.8709,
+                          8.29281e-17 -0.373475 0.92764,
+                          1.32233e-16 -0.595526 0.803336,
+                          5.64127e-17 -0.25406 0.967188,
+                          8.29281e-17 -0.373475 0.92764,
+                          1.09126e-16 -0.49146 0.8709,
+                          1.54677e-16 -0.696605 0.717455,
+                          1.32233e-16 -0.595526 0.803336,
+                          1.72975e-16 -0.779012 0.627009,
+                          1.09126e-16 -0.49146 0.8709,
+                          1.32233e-16 -0.595526 0.803336,
+                          1.54677e-16 -0.696605 0.717455,
+                          1.54677e-16 -0.696605 0.717455,
+                          1.72975e-16 -0.779012 0.627009,
+                          1.90077e-16 -0.856032 0.516924,
+                          -0.134366 0.503166 0.85368,
+                          -0.121508 0.269411 0.955329,
+                          -0.162938 0.243456 0.956128,
+                          -0.17268 0.451604 0.875349,
+                          -0.162938 0.243456 0.956128,
+                          -0.199474 0.216309 0.95573,
+                          -0.17268 0.451604 0.875349,
+                          -0.134366 0.503166 0.85368,
+                          -0.162938 0.243456 0.956128,
+                          -0.206648 0.399036 0.893346,
+                          -0.199474 0.216309 0.95573,
+                          -0.231087 0.188339 0.95453,
+                          -0.206648 0.399036 0.893346,
+                          -0.17268 0.451604 0.875349,
+                          -0.199474 0.216309 0.95573,
+                          -0.236193 0.345893 0.908059,
+                          -0.231087 0.188339 0.95453,
+                          -0.257838 0.159833 0.952876,
+                          -0.236193 0.345893 0.908059,
+                          -0.206648 0.399036 0.893346,
+                          -0.231087 0.188339 0.95453,
+                          -0.261315 0.292495 0.91987,
+                          -0.257838 0.159833 0.952876,
+                          -0.279841 0.131 0.951067,
+                          -0.261315 0.292495 0.91987,
+                          -0.236193 0.345893 0.908059,
+                          -0.257838 0.159833 0.952876,
+                          -0.282067 0.239057 0.929134,
+                          -0.279841 0.131 0.951067,
+                          -0.297231 0.101984 0.949344,
+                          -0.282067 0.239057 0.929134,
+                          -0.261315 0.292495 0.91987,
+                          -0.279841 0.131 0.951067,
+                          -0.298528 0.185708 0.936159,
+                          -0.297231 0.101984 0.949344,
+                          -0.310138 0.072878 0.947894,
+                          -0.298528 0.185708 0.936159,
+                          -0.282067 0.239057 0.929134,
+                          -0.297231 0.101984 0.949344,
+                          -0.310781 0.132501 0.941201,
+                          -0.310138 0.072878 0.947894,
+                          -0.318676 0.0437343 0.946854,
+                          -0.310781 0.132501 0.941201,
+                          -0.298528 0.185708 0.936159,
+                          -0.310138 0.072878 0.947894,
+                          -0.318903 0.0794338 0.944453,
+                          -0.318676 0.0437343 0.946854,
+                          -0.322924 0.0145788 0.946313,
+                          -0.318903 0.0794338 0.944453,
+                          -0.310781 0.132501 0.941201,
+                          -0.318676 0.0437343 0.946854,
+                          -0.322949 0.026466 0.946046,
+                          -0.322924 0.0145788 0.946313,
+                          -0.322924 -0.0145788 0.946313,
+                          -0.322949 0.026466 0.946046,
+                          -0.318903 0.0794338 0.944453,
+                          -0.322924 0.0145788 0.946313,
+                          -0.322949 -0.026466 0.946046,
+                          -0.322924 -0.0145788 0.946313,
+                          -0.318676 -0.0437343 0.946854,
+                          -0.322949 -0.026466 0.946046,
+                          -0.322949 0.026466 0.946046,
+                          -0.322924 -0.0145788 0.946313,
+                          -0.318903 -0.0794338 0.944453,
+                          -0.318676 -0.0437343 0.946854,
+                          -0.310138 -0.072878 0.947894,
+                          -0.318903 -0.0794338 0.944453,
+                          -0.322949 -0.026466 0.946046,
+                          -0.318676 -0.0437343 0.946854,
+                          -0.310781 -0.132501 0.941201,
+                          -0.310138 -0.072878 0.947894,
+                          -0.297231 -0.101984 0.949344,
+                          -0.310781 -0.132501 0.941201,
+                          -0.318903 -0.0794338 0.944453,
+                          -0.310138 -0.072878 0.947894,
+                          -0.298528 -0.185708 0.936159,
+                          -0.297231 -0.101984 0.949344,
+                          -0.279841 -0.131 0.951067,
+                          -0.298528 -0.185708 0.936159,
+                          -0.310781 -0.132501 0.941201,
+                          -0.297231 -0.101984 0.949344,
+                          -0.282067 -0.239057 0.929134,
+                          -0.279841 -0.131 0.951067,
+                          -0.257838 -0.159833 0.952876,
+                          -0.282067 -0.239057 0.929134,
+                          -0.298528 -0.185708 0.936159,
+                          -0.279841 -0.131 0.951067,
+                          -0.261315 -0.292495 0.91987,
+                          -0.257838 -0.159833 0.952876,
+                          -0.231087 -0.188339 0.95453,
+                          -0.261315 -0.292495 0.91987,
+                          -0.282067 -0.239057 0.929134,
+                          -0.257838 -0.159833 0.952876,
+                          -0.236193 -0.345893 0.908059,
+                          -0.231087 -0.188339 0.95453,
+                          -0.199474 -0.216309 0.95573,
+                          -0.236193 -0.345893 0.908059,
+                          -0.261315 -0.292495 0.91987,
+                          -0.231087 -0.188339 0.95453,
+                          -0.206648 -0.399036 0.893346,
+                          -0.199474 -0.216309 0.95573,
+                          -0.162938 -0.243456 0.956128,
+                          -0.206648 -0.399036 0.893346,
+                          -0.236193 -0.345893 0.908059,
+                          -0.199474 -0.216309 0.95573,
+                          -0.17268 -0.451604 0.875349,
+                          -0.162938 -0.243456 0.956128,
+                          -0.121508 -0.269411 0.955329,
+                          -0.17268 -0.451604 0.875349,
+                          -0.206648 -0.399036 0.893346,
+                          -0.162938 -0.243456 0.956128,
+                          -0.134366 -0.503166 0.85368,
+                          -0.121508 -0.269411 0.955329,
+                          -0.075345 -0.293716 0.952919,
+                          -0.134366 -0.503166 0.85368,
+                          -0.17268 -0.451604 0.875349,
+                          -0.121508 -0.269411 0.955329,
+                          -0.134366 -0.503166 0.85368,
+                          -0.075345 -0.293716 0.952919,
+                          -0.0803157 -0.364445 0.927755,
+                          -0.0918918 -0.553177 0.82798,
+                          -0.134366 -0.503166 0.85368,
+                          -0.0803157 -0.364445 0.927755,
+                          -0.120691 -0.990603 0.0643358,
+                          -0.0963029 -0.978018 0.18495,
+                          -0.0937875 -0.98854 0.118289,
+                          -0.138409 0.672678 0.726875,
+                          -0.134366 0.503166 0.85368,
+                          -0.17268 0.451604 0.875349,
+                          -0.174225 0.60748 0.774993,
+                          -0.17268 0.451604 0.875349,
+                          -0.206648 0.399036 0.893346,
+                          -0.174225 0.60748 0.774993,
+                          -0.138409 0.672678 0.726875,
+                          -0.17268 0.451604 0.875349,
+                          -0.206749 0.539546 0.816177,
+                          -0.206648 0.399036 0.893346,
+                          -0.236193 0.345893 0.908059,
+                          -0.206749 0.539546 0.816177,
+                          -0.174225 0.60748 0.774993,
+                          -0.206648 0.399036 0.893346,
+                          -0.235588 0.469676 0.850824,
+                          -0.236193 0.345893 0.908059,
+                          -0.261315 0.292495 0.91987,
+                          -0.235588 0.469676 0.850824,
+                          -0.206749 0.539546 0.816177,
+                          -0.236193 0.345893 0.908059,
+                          -0.26049 0.398524 0.879388,
+                          -0.261315 0.292495 0.91987,
+                          -0.282067 0.239057 0.929134,
+                          -0.26049 0.398524 0.879388,
+                          -0.235588 0.469676 0.850824,
+                          -0.261315 0.292495 0.91987,
+                          -0.281309 0.326585 0.902334,
+                          -0.282067 0.239057 0.929134,
+                          -0.298528 0.185708 0.936159,
+                          -0.281309 0.326585 0.902334,
+                          -0.26049 0.398524 0.879388,
+                          -0.282067 0.239057 0.929134,
+                          -0.297975 0.254214 0.920101,
+                          -0.298528 0.185708 0.936159,
+                          -0.310781 0.132501 0.941201,
+                          -0.297975 0.254214 0.920101,
+                          -0.281309 0.326585 0.902334,
+                          -0.298528 0.185708 0.936159,
+                          -0.310465 0.18164 0.933069,
+                          -0.310781 0.132501 0.941201,
+                          -0.318903 0.0794338 0.944453,
+                          -0.310465 0.18164 0.933069,
+                          -0.297975 0.254214 0.920101,
+                          -0.310781 0.132501 0.941201,
+                          -0.318781 0.108993 0.941541,
+                          -0.318903 0.0794338 0.944453,
+                          -0.322949 0.026466 0.946046,
+                          -0.318781 0.108993 0.941541,
+                          -0.310465 0.18164 0.933069,
+                          -0.318903 0.0794338 0.944453,
+                          -0.322935 0.0363311 0.945724,
+                          -0.322949 0.026466 0.946046,
+                          -0.322949 -0.026466 0.946046,
+                          -0.322935 0.0363311 0.945724,
+                          -0.318781 0.108993 0.941541,
+                          -0.322949 0.026466 0.946046,
+                          -0.322935 -0.0363311 0.945724,
+                          -0.322949 -0.026466 0.946046,
+                          -0.318903 -0.0794338 0.944453,
+                          -0.322935 -0.0363311 0.945724,
+                          -0.322935 0.0363311 0.945724,
+                          -0.322949 -0.026466 0.946046,
+                          -0.318781 -0.108993 0.941541,
+                          -0.318903 -0.0794338 0.944453,
+                          -0.310781 -0.132501 0.941201,
+                          -0.318781 -0.108993 0.941541,
+                          -0.322935 -0.0363311 0.945724,
+                          -0.318903 -0.0794338 0.944453,
+                          -0.310465 -0.18164 0.933069,
+                          -0.310781 -0.132501 0.941201,
+                          -0.298528 -0.185708 0.936159,
+                          -0.310465 -0.18164 0.933069,
+                          -0.318781 -0.108993 0.941541,
+                          -0.310781 -0.132501 0.941201,
+                          -0.297975 -0.254214 0.920101,
+                          -0.298528 -0.185708 0.936159,
+                          -0.282067 -0.239057 0.929134,
+                          -0.297975 -0.254214 0.920101,
+                          -0.310465 -0.18164 0.933069,
+                          -0.298528 -0.185708 0.936159,
+                          -0.281309 -0.326585 0.902334,
+                          -0.282067 -0.239057 0.929134,
+                          -0.261315 -0.292495 0.91987,
+                          -0.281309 -0.326585 0.902334,
+                          -0.297975 -0.254214 0.920101,
+                          -0.282067 -0.239057 0.929134,
+                          -0.26049 -0.398524 0.879388,
+                          -0.261315 -0.292495 0.91987,
+                          -0.236193 -0.345893 0.908059,
+                          -0.26049 -0.398524 0.879388,
+                          -0.281309 -0.326585 0.902334,
+                          -0.261315 -0.292495 0.91987,
+                          -0.235588 -0.469676 0.850824,
+                          -0.236193 -0.345893 0.908059,
+                          -0.206648 -0.399036 0.893346,
+                          -0.235588 -0.469676 0.850824,
+                          -0.26049 -0.398524 0.879388,
+                          -0.236193 -0.345893 0.908059,
+                          -0.206749 -0.539546 0.816177,
+                          -0.206648 -0.399036 0.893346,
+                          -0.17268 -0.451604 0.875349,
+                          -0.206749 -0.539546 0.816177,
+                          -0.235588 -0.469676 0.850824,
+                          -0.206648 -0.399036 0.893346,
+                          -0.174225 -0.60748 0.774993,
+                          -0.17268 -0.451604 0.875349,
+                          -0.134366 -0.503166 0.85368,
+                          -0.174225 -0.60748 0.774993,
+                          -0.206749 -0.539546 0.816177,
+                          -0.17268 -0.451604 0.875349,
+                          -0.138409 -0.672678 0.726875,
+                          -0.134366 -0.503166 0.85368,
+                          -0.0918918 -0.553177 0.82798,
+                          -0.138409 -0.672678 0.726875,
+                          -0.174225 -0.60748 0.774993,
+                          -0.134366 -0.503166 0.85368,
+                          -0.138409 -0.672678 0.726875,
+                          -0.0918918 -0.553177 0.82798,
+                          -0.0968077 -0.653871 0.750387,
+                          -0.120691 -0.990603 0.0643358,
+                          -0.0976807 -0.968957 0.227116,
+                          -0.0963029 -0.978018 0.18495,
+                          -0.0998536 -0.734213 0.671536,
+                          -0.138409 -0.672678 0.726875,
+                          -0.0968077 -0.653871 0.750387,
+                          -0.12244 -0.984801 0.123187,
+                          -0.0988373 -0.958506 0.267389,
+                          -0.0976807 -0.968957 0.227116,
+                          -0.12244 -0.984801 0.123187,
+                          -0.0976807 -0.968957 0.227116,
+                          -0.120691 -0.990603 0.0643358,
+                          -0.12244 -0.984801 0.123187,
+                          -0.10019 -0.940744 0.32398,
+                          -0.0988373 -0.958506 0.267389,
+                          -0.12244 -0.984801 0.123187,
+                          -0.123664 -0.976477 0.176632,
+                          -0.10019 -0.940744 0.32398,
+                          -0.0634627 -0.871732 -0.485857,
+                          -0.0972889 -0.957315 -0.27218,
+                          -0.0570418 -0.907216 -0.416781,
+                          -0.0591211 -0.954122 -0.293522,
+                          -0.0570418 -0.907216 -0.416781,
+                          -0.0972889 -0.957315 -0.27218,
+                          -0.107351 -0.95667 -0.270661,
+                          -0.12232 -0.984787 -0.123419,
+                          -0.0972889 -0.957315 -0.27218,
+                          -0.0992384 -0.976696 -0.190306,
+                          -0.0972889 -0.957315 -0.27218,
+                          -0.12232 -0.984787 -0.123419,
+                          -0.0634627 -0.871732 -0.485857,
+                          -0.107351 -0.95667 -0.270661,
+                          -0.0972889 -0.957315 -0.27218,
+                          -0.0591211 -0.954122 -0.293522,
+                          -0.0972889 -0.957315 -0.27218,
+                          -0.0992384 -0.976696 -0.190306,
+                          -0.129367 -0.990682 -0.042589,
+                          -0.131179 -0.990995 0.0268384,
+                          -0.12232 -0.984787 -0.123419,
+                          -0.123252 -0.988645 -0.0859612,
+                          -0.12232 -0.984787 -0.123419,
+                          -0.131179 -0.990995 0.0268384,
+                          -0.107351 -0.95667 -0.270661,
+                          -0.129367 -0.990682 -0.042589,
+                          -0.12232 -0.984787 -0.123419,
+                          -0.0992384 -0.976696 -0.190306,
+                          -0.12232 -0.984787 -0.123419,
+                          -0.123252 -0.988645 -0.0859612,
+                          -0.127172 -0.974071 0.187119,
+                          -0.123664 -0.976477 0.176632,
+                          -0.131179 -0.990995 0.0268384,
+                          -0.130987 -0.991208 0.018678,
+                          -0.131179 -0.990995 0.0268384,
+                          -0.123664 -0.976477 0.176632,
+                          -0.129367 -0.990682 -0.042589,
+                          -0.127172 -0.974071 0.187119,
+                          -0.131179 -0.990995 0.0268384,
+                          -0.123252 -0.988645 -0.0859612,
+                          -0.131179 -0.990995 0.0268384,
+                          -0.130987 -0.991208 0.018678,
+                          -0.130987 -0.991208 0.018678,
+                          -0.123664 -0.976477 0.176632,
+                          -0.12244 -0.984801 0.123187,
+                          2.21948e-16 -0.999566 0.0294626,
+                          2.18058e-16 -0.982044 0.188651,
+                          2.2184e-16 -0.999077 -0.0429499,
+                          2.13003e-16 -0.959278 0.282464,
+                          2.18058e-16 -0.982044 0.188651,
+                          2.21948e-16 -0.999566 0.0294626,
+                          2.16327e-16 -0.97425 -0.225472,
+                          2.2184e-16 -0.999077 -0.0429499,
+                          2.13658e-16 -0.962231 -0.272235,
+                          2.21948e-16 -0.999566 0.0294626,
+                          2.2184e-16 -0.999077 -0.0429499,
+                          2.16327e-16 -0.97425 -0.225472,
+                          1.96507e-16 -0.884991 -0.465609,
+                          2.13658e-16 -0.962231 -0.272235,
+                          1.93954e-16 -0.873492 -0.486838,
+                          2.16327e-16 -0.97425 -0.225472,
+                          2.13658e-16 -0.962231 -0.272235,
+                          1.96507e-16 -0.884991 -0.465609,
+                          -0.12244 -0.984801 0.123187,
+                          -0.120691 -0.990603 0.0643358,
+                          -0.130766 -0.991365 0.00976412,
+                          -0.130987 -0.991208 0.018678,
+                          -0.130766 -0.991365 0.00976412,
+                          -0.12407 -0.991257 -0.0449069,
+                          -0.130987 -0.991208 0.018678,
+                          -0.12244 -0.984801 0.123187,
+                          -0.130766 -0.991365 0.00976412,
+                          -0.123252 -0.988645 -0.0859612,
+                          -0.12407 -0.991257 -0.0449069,
+                          -0.100566 -0.989974 -0.0991901,
+                          -0.123252 -0.988645 -0.0859612,
+                          -0.130987 -0.991208 0.018678,
+                          -0.12407 -0.991257 -0.0449069,
+                          -0.0992384 -0.976696 -0.190306,
+                          -0.100566 -0.989974 -0.0991901,
+                          -0.0602187 -0.986488 -0.152367,
+                          -0.0992384 -0.976696 -0.190306,
+                          -0.123252 -0.988645 -0.0859612,
+                          -0.100566 -0.989974 -0.0991901,
+                          -0.0591211 -0.954122 -0.293522,
+                          -0.0992384 -0.976696 -0.190306,
+                          -0.0602187 -0.986488 -0.152367,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -777 216 -230,
+                          -777 240 -166,
+                          -777 240 -230,
+                          -610.25 240.487 -230.365,
+                          -777 240 -230,
+                          -777 240 -166,
+                          -610.25 218.786 -234.967,
+                          -777 216 -230,
+                          -777 240 -230,
+                          -610.25 240.487 -230.365,
+                          -610.25 218.786 -234.967,
+                          -777 240 -230,
+                          -777 216 -230,
+                          -777 240 -102,
+                          -777 240 -166,
+                          -610.25 256.935 -123.372,
+                          -777 240 -166,
+                          -777 240 -102,
+                          -610.25 250.024 -177.669,
+                          -610.25 240.487 -230.365,
+                          -777 240 -166,
+                          -610.25 256.935 -123.372,
+                          -610.25 250.024 -177.669,
+                          -777 240 -166,
+                          -777 216 -230,
+                          -777 240 -38,
+                          -777 240 -102,
+                          -610.25 260.961 -68.0106,
+                          -777 240 -102,
+                          -777 240 -38,
+                          -610.25 260.961 -68.0106,
+                          -610.25 256.935 -123.372,
+                          -777 240 -102,
+                          -777 216 -230,
+                          -777 240 26,
+                          -777 240 -38,
+                          -610.25 261.951 -12.1617,
+                          -777 240 -38,
+                          -777 240 26,
+                          -610.25 261.951 -12.1617,
+                          -610.25 260.961 -68.0106,
+                          -777 240 -38,
+                          -777 216 -230,
+                          -777 240 90,
+                          -777 240 26,
+                          -610.25 259.867 43.5808,
+                          -777 240 26,
+                          -777 240 90,
+                          -610.25 259.867 43.5808,
+                          -610.25 261.951 -12.1617,
+                          -777 240 26,
+                          -777 216 -230,
+                          -777 216 90,
+                          -777 240 90,
+                          -643.6 251.831 96.9011,
+                          -777 240 90,
+                          -777 216 90,
+                          -643.6 251.831 96.9011,
+                          -610.25 259.867 43.5808,
+                          -777 240 90,
+                          -777 192 -230,
+                          -777 192 90,
+                          -777 216 90,
+                          -643.6 207.997 109.242,
+                          -777 216 90,
+                          -777 192 90,
+                          -777 216 -230,
+                          -777 192 -230,
+                          -777 216 90,
+                          -643.6 230.251 103.27,
+                          -643.6 251.831 96.9011,
+                          -777 216 90,
+                          -643.6 207.997 109.242,
+                          -643.6 230.251 103.27,
+                          -777 216 90,
+                          -777 168 -230,
+                          -777 168 90,
+                          -777 192 90,
+                          -643.6 185.114 114.745,
+                          -777 192 90,
+                          -777 168 90,
+                          -777 192 -230,
+                          -777 168 -230,
+                          -777 192 90,
+                          -643.6 185.114 114.745,
+                          -643.6 207.997 109.242,
+                          -777 192 90,
+                          -777 144 -230,
+                          -777 144 90,
+                          -777 168 90,
+                          -643.6 161.658 119.713,
+                          -777 168 90,
+                          -777 144 90,
+                          -777 168 -230,
+                          -777 144 -230,
+                          -777 168 90,
+                          -643.6 161.658 119.713,
+                          -643.6 185.114 114.745,
+                          -777 168 90,
+                          -777 120 -230,
+                          -777 120 90,
+                          -777 144 90,
+                          -643.6 137.691 124.088,
+                          -777 144 90,
+                          -777 120 90,
+                          -777 144 -230,
+                          -777 120 -230,
+                          -777 144 90,
+                          -643.6 137.691 124.088,
+                          -643.6 161.658 119.713,
+                          -777 144 90,
+                          -777 96 -230,
+                          -777 96 90,
+                          -777 120 90,
+                          -643.6 113.281 127.816,
+                          -777 120 90,
+                          -777 96 90,
+                          -777 120 -230,
+                          -777 96 -230,
+                          -777 120 90,
+                          -643.6 113.281 127.816,
+                          -643.6 137.691 124.088,
+                          -777 120 90,
+                          -777 72 -230,
+                          -777 72 90,
+                          -777 96 90,
+                          -643.6 88.5 130.853,
+                          -777 96 90,
+                          -777 72 90,
+                          -777 96 -230,
+                          -777 72 -230,
+                          -777 96 90,
+                          -643.6 88.5 130.853,
+                          -643.6 113.281 127.816,
+                          -777 96 90,
+                          -777 48 -230,
+                          -777 48 90,
+                          -777 72 90,
+                          -643.6 63.4264 133.164,
+                          -777 72 90,
+                          -777 48 90,
+                          -777 72 -230,
+                          -777 48 -230,
+                          -777 72 90,
+                          -643.6 63.4264 133.164,
+                          -643.6 88.5 130.853,
+                          -777 72 90,
+                          -777 24 -230,
+                          -777 24 90,
+                          -777 48 90,
+                          -643.6 38.1412 134.719,
+                          -777 48 90,
+                          -777 24 90,
+                          -777 48 -230,
+                          -777 24 -230,
+                          -777 48 90,
+                          -643.6 38.1412 134.719,
+                          -643.6 63.4264 133.164,
+                          -777 48 90,
+                          -777 -1.71418e-13 -230,
+                          -777 -1.71418e-13 90,
+                          -777 24 90,
+                          -643.6 12.728 135.502,
+                          -777 24 90,
+                          -777 -1.71418e-13 90,
+                          -777 24 -230,
+                          -777 -1.71418e-13 -230,
+                          -777 24 90,
+                          -643.6 12.728 135.502,
+                          -643.6 38.1412 134.719,
+                          -777 24 90,
+                          -777 -24 -230,
+                          -777 -24 90,
+                          -777 -1.71418e-13 90,
+                          -643.6 -12.728 135.502,
+                          -777 -1.71418e-13 90,
+                          -777 -24 90,
+                          -777 -1.71418e-13 -230,
+                          -777 -24 -230,
+                          -777 -1.71418e-13 90,
+                          -643.6 -12.728 135.502,
+                          -643.6 12.728 135.502,
+                          -777 -1.71418e-13 90,
+                          -777 -48 -230,
+                          -777 -48 90,
+                          -777 -24 90,
+                          -643.6 -38.1412 134.719,
+                          -777 -24 90,
+                          -777 -48 90,
+                          -777 -24 -230,
+                          -777 -48 -230,
+                          -777 -24 90,
+                          -643.6 -38.1412 134.719,
+                          -643.6 -12.728 135.502,
+                          -777 -24 90,
+                          -777 -72 -230,
+                          -777 -72 90,
+                          -777 -48 90,
+                          -643.6 -63.4264 133.164,
+                          -777 -48 90,
+                          -777 -72 90,
+                          -777 -48 -230,
+                          -777 -72 -230,
+                          -777 -48 90,
+                          -643.6 -63.4264 133.164,
+                          -643.6 -38.1412 134.719,
+                          -777 -48 90,
+                          -777 -96 -230,
+                          -777 -96 90,
+                          -777 -72 90,
+                          -643.6 -88.5 130.853,
+                          -777 -72 90,
+                          -777 -96 90,
+                          -777 -72 -230,
+                          -777 -96 -230,
+                          -777 -72 90,
+                          -643.6 -88.5 130.853,
+                          -643.6 -63.4264 133.164,
+                          -777 -72 90,
+                          -777 -120 -230,
+                          -777 -120 90,
+                          -777 -96 90,
+                          -643.6 -113.281 127.816,
+                          -777 -96 90,
+                          -777 -120 90,
+                          -777 -96 -230,
+                          -777 -120 -230,
+                          -777 -96 90,
+                          -643.6 -113.281 127.816,
+                          -643.6 -88.5 130.853,
+                          -777 -96 90,
+                          -777 -144 -230,
+                          -777 -144 90,
+                          -777 -120 90,
+                          -643.6 -137.691 124.088,
+                          -777 -120 90,
+                          -777 -144 90,
+                          -777 -120 -230,
+                          -777 -144 -230,
+                          -777 -120 90,
+                          -643.6 -137.691 124.088,
+                          -643.6 -113.281 127.816,
+                          -777 -120 90,
+                          -777 -168 -230,
+                          -777 -168 90,
+                          -777 -144 90,
+                          -643.6 -161.658 119.713,
+                          -777 -144 90,
+                          -777 -168 90,
+                          -777 -144 -230,
+                          -777 -168 -230,
+                          -777 -144 90,
+                          -643.6 -161.658 119.713,
+                          -643.6 -137.691 124.088,
+                          -777 -144 90,
+                          -777 -192 -230,
+                          -777 -192 90,
+                          -777 -168 90,
+                          -643.6 -185.114 114.745,
+                          -777 -168 90,
+                          -777 -192 90,
+                          -777 -168 -230,
+                          -777 -192 -230,
+                          -777 -168 90,
+                          -643.6 -185.114 114.745,
+                          -643.6 -161.658 119.713,
+                          -777 -168 90,
+                          -777 -216 -230,
+                          -777 -216 90,
+                          -777 -192 90,
+                          -643.6 -207.997 109.242,
+                          -777 -192 90,
+                          -777 -216 90,
+                          -777 -192 -230,
+                          -777 -216 -230,
+                          -777 -192 90,
+                          -643.6 -207.997 109.242,
+                          -643.6 -185.114 114.745,
+                          -777 -192 90,
+                          -777 -240 26,
+                          -777 -240 90,
+                          -777 -216 90,
+                          -643.6 -230.251 103.27,
+                          -777 -216 90,
+                          -777 -240 90,
+                          -777 -240 -38,
+                          -777 -240 26,
+                          -777 -216 90,
+                          -777 -240 -102,
+                          -777 -240 -38,
+                          -777 -216 90,
+                          -777 -240 -166,
+                          -777 -240 -102,
+                          -777 -216 90,
+                          -777 -240 -230,
+                          -777 -240 -166,
+                          -777 -216 90,
+                          -777 -216 -230,
+                          -777 -240 -230,
+                          -777 -216 90,
+                          -643.6 -230.251 103.27,
+                          -643.6 -207.997 109.242,
+                          -777 -216 90,
+                          -643.6 -251.831 96.9011,
+                          -777 -240 90,
+                          -777 -240 26,
+                          -643.6 -251.831 96.9011,
+                          -643.6 -230.251 103.27,
+                          -777 -240 90,
+                          -610.25 -261.951 -12.1617,
+                          -777 -240 26,
+                          -777 -240 -38,
+                          -610.25 -254.788 98.6264,
+                          -643.6 -251.831 96.9011,
+                          -777 -240 26,
+                          -610.25 -259.867 43.5808,
+                          -610.25 -254.788 98.6264,
+                          -777 -240 26,
+                          -610.25 -261.951 -12.1617,
+                          -610.25 -259.867 43.5808,
+                          -777 -240 26,
+                          -610.25 -260.961 -68.0106,
+                          -777 -240 -38,
+                          -777 -240 -102,
+                          -610.25 -260.961 -68.0106,
+                          -610.25 -261.951 -12.1617,
+                          -777 -240 -38,
+                          -610.25 -256.935 -123.372,
+                          -777 -240 -102,
+                          -777 -240 -166,
+                          -610.25 -256.935 -123.372,
+                          -610.25 -260.961 -68.0106,
+                          -777 -240 -102,
+                          -610.25 -250.024 -177.669,
+                          -777 -240 -166,
+                          -777 -240 -230,
+                          -610.25 -250.024 -177.669,
+                          -610.25 -256.935 -123.372,
+                          -777 -240 -166,
+                          -610.25 -240.487 -230.365,
+                          -777 -240 -230,
+                          -777 -216 -230,
+                          -610.25 -250.024 -177.669,
+                          -777 -240 -230,
+                          -610.25 -240.487 -230.365,
+                          -610.25 -196.736 -239.194,
+                          -777 -216 -230,
+                          -777 -192 -230,
+                          -610.25 -218.786 -234.967,
+                          -610.25 -240.487 -230.365,
+                          -777 -216 -230,
+                          -610.25 -196.736 -239.194,
+                          -610.25 -218.786 -234.967,
+                          -777 -216 -230,
+                          -610.25 -174.367 -243.02,
+                          -777 -192 -230,
+                          -777 -168 -230,
+                          -610.25 -174.367 -243.02,
+                          -610.25 -196.736 -239.194,
+                          -777 -192 -230,
+                          -610.25 -151.713 -246.423,
+                          -777 -168 -230,
+                          -777 -144 -230,
+                          -610.25 -151.713 -246.423,
+                          -610.25 -174.367 -243.02,
+                          -777 -168 -230,
+                          -610.25 -128.807 -249.379,
+                          -777 -144 -230,
+                          -777 -120 -230,
+                          -610.25 -128.807 -249.379,
+                          -610.25 -151.713 -246.423,
+                          -777 -144 -230,
+                          -610.25 -105.686 -251.872,
+                          -777 -120 -230,
+                          -777 -96 -230,
+                          -610.25 -105.686 -251.872,
+                          -610.25 -128.807 -249.379,
+                          -777 -120 -230,
+                          -610.25 -82.3873 -253.885,
+                          -777 -96 -230,
+                          -777 -72 -230,
+                          -610.25 -82.3873 -253.885,
+                          -610.25 -105.686 -251.872,
+                          -777 -96 -230,
+                          -610.25 -58.9486 -255.406,
+                          -777 -72 -230,
+                          -777 -48 -230,
+                          -610.25 -58.9486 -255.406,
+                          -610.25 -82.3873 -253.885,
+                          -777 -72 -230,
+                          -610.25 -35.4095 -256.425,
+                          -777 -48 -230,
+                          -777 -24 -230,
+                          -610.25 -35.4095 -256.425,
+                          -610.25 -58.9486 -255.406,
+                          -777 -48 -230,
+                          -610.25 -11.8099 -256.936,
+                          -777 -24 -230,
+                          -777 -1.71418e-13 -230,
+                          -610.25 -11.8099 -256.936,
+                          -610.25 -35.4095 -256.425,
+                          -777 -24 -230,
+                          -610.25 11.8099 -256.936,
+                          -777 -1.71418e-13 -230,
+                          -777 24 -230,
+                          -610.25 11.8099 -256.936,
+                          -610.25 -11.8099 -256.936,
+                          -777 -1.71418e-13 -230,
+                          -610.25 35.4095 -256.425,
+                          -777 24 -230,
+                          -777 48 -230,
+                          -610.25 35.4095 -256.425,
+                          -610.25 11.8099 -256.936,
+                          -777 24 -230,
+                          -610.25 58.9486 -255.406,
+                          -777 48 -230,
+                          -777 72 -230,
+                          -610.25 58.9486 -255.406,
+                          -610.25 35.4095 -256.425,
+                          -777 48 -230,
+                          -610.25 82.3873 -253.885,
+                          -777 72 -230,
+                          -777 96 -230,
+                          -610.25 82.3873 -253.885,
+                          -610.25 58.9486 -255.406,
+                          -777 72 -230,
+                          -610.25 105.686 -251.872,
+                          -777 96 -230,
+                          -777 120 -230,
+                          -610.25 105.686 -251.872,
+                          -610.25 82.3873 -253.885,
+                          -777 96 -230,
+                          -610.25 128.807 -249.379,
+                          -777 120 -230,
+                          -777 144 -230,
+                          -610.25 128.807 -249.379,
+                          -610.25 105.686 -251.872,
+                          -777 120 -230,
+                          -610.25 151.713 -246.423,
+                          -777 144 -230,
+                          -777 168 -230,
+                          -610.25 151.713 -246.423,
+                          -610.25 128.807 -249.379,
+                          -777 144 -230,
+                          -610.25 174.367 -243.02,
+                          -777 168 -230,
+                          -777 192 -230,
+                          -610.25 174.367 -243.02,
+                          -610.25 151.713 -246.423,
+                          -777 168 -230,
+                          -610.25 196.736 -239.194,
+                          -777 192 -230,
+                          -777 216 -230,
+                          -610.25 196.736 -239.194,
+                          -610.25 174.367 -243.02,
+                          -777 192 -230,
+                          -610.25 218.786 -234.967,
+                          -610.25 196.736 -239.194,
+                          -777 216 -230,
+                          -110 183.183 -282.081,
+                          -276.417 241.462 -231.097,
+                          -110 241.948 -231.461,
+                          -276.417 270.093 -179.674,
+                          -110 241.948 -231.461,
+                          -276.417 241.462 -231.097,
+                          0 183.175 -282.082,
+                          -110 183.183 -282.081,
+                          -110 241.948 -231.461,
+                          -110 286.505 -169.683,
+                          -110 241.948 -231.461,
+                          -276.417 270.093 -179.674,
+                          0 241.948 -231.461,
+                          -110 241.948 -231.461,
+                          -110 286.505 -169.683,
+                          0 183.175 -282.082,
+                          -110 241.948 -231.461,
+                          0 241.948 -231.461,
+                          -110 183.183 -282.081,
+                          -276.417 222.075 -244.91,
+                          -276.417 241.462 -231.097,
+                          -443.333 240.975 -230.731,
+                          -276.417 241.462 -231.097,
+                          -276.417 222.075 -244.91,
+                          -443.333 260.059 -178.671,
+                          -276.417 241.462 -231.097,
+                          -443.333 240.975 -230.731,
+                          -443.333 260.059 -178.671,
+                          -276.417 270.093 -179.674,
+                          -276.417 241.462 -231.097,
+                          -110 183.183 -282.081,
+                          -276.417 201.64 -257.599,
+                          -276.417 222.075 -244.91,
+                          -443.333 220.43 -239.938,
+                          -276.417 222.075 -244.91,
+                          -276.417 201.64 -257.599,
+                          -443.333 220.43 -239.938,
+                          -443.333 240.975 -230.731,
+                          -276.417 222.075 -244.91,
+                          -110 183.183 -282.081,
+                          -276.417 180.25 -269.087,
+                          -276.417 201.64 -257.599,
+                          -443.333 199.188 -248.397,
+                          -276.417 201.64 -257.599,
+                          -276.417 180.25 -269.087,
+                          -443.333 220.43 -239.938,
+                          -276.417 201.64 -257.599,
+                          -443.333 199.188 -248.397,
+                          -110 114.174 -317.487,
+                          -276.417 158.002 -279.3,
+                          -276.417 180.25 -269.087,
+                          -443.333 177.308 -256.054,
+                          -276.417 180.25 -269.087,
+                          -276.417 158.002 -279.3,
+                          -110 183.183 -282.081,
+                          -110 114.174 -317.487,
+                          -276.417 180.25 -269.087,
+                          -443.333 199.188 -248.397,
+                          -276.417 180.25 -269.087,
+                          -443.333 177.308 -256.054,
+                          -110 114.174 -317.487,
+                          -276.417 134.999 -288.176,
+                          -276.417 158.002 -279.3,
+                          -443.333 154.857 -262.862,
+                          -276.417 158.002 -279.3,
+                          -276.417 134.999 -288.176,
+                          -443.333 177.308 -256.054,
+                          -276.417 158.002 -279.3,
+                          -443.333 154.857 -262.862,
+                          -110 114.174 -317.487,
+                          -276.417 111.35 -295.659,
+                          -276.417 134.999 -288.176,
+                          -443.333 131.903 -268.778,
+                          -276.417 134.999 -288.176,
+                          -276.417 111.35 -295.659,
+                          -443.333 154.857 -262.862,
+                          -276.417 134.999 -288.176,
+                          -443.333 131.903 -268.778,
+                          -110 38.7808 -335.699,
+                          -276.417 87.1666 -301.702,
+                          -276.417 111.35 -295.659,
+                          -443.333 108.518 -273.765,
+                          -276.417 111.35 -295.659,
+                          -276.417 87.1666 -301.702,
+                          -110 114.174 -317.487,
+                          -110 38.7808 -335.699,
+                          -276.417 111.35 -295.659,
+                          -443.333 131.903 -268.778,
+                          -276.417 111.35 -295.659,
+                          -443.333 108.518 -273.765,
+                          -110 38.7808 -335.699,
+                          -276.417 62.5636 -306.268,
+                          -276.417 87.1666 -301.702,
+                          -443.333 84.7769 -277.793,
+                          -276.417 87.1666 -301.702,
+                          -276.417 62.5636 -306.268,
+                          -443.333 108.518 -273.765,
+                          -276.417 87.1666 -301.702,
+                          -443.333 84.7769 -277.793,
+                          -110 38.7808 -335.699,
+                          -276.417 37.6592 -309.327,
+                          -276.417 62.5636 -306.268,
+                          -443.333 60.7561 -280.837,
+                          -276.417 62.5636 -306.268,
+                          -276.417 37.6592 -309.327,
+                          -443.333 84.7769 -277.793,
+                          -276.417 62.5636 -306.268,
+                          -443.333 60.7561 -280.837,
+                          -110 -38.7808 -335.699,
+                          -276.417 12.5733 -310.862,
+                          -276.417 37.6592 -309.327,
+                          -443.333 36.5344 -282.876,
+                          -276.417 37.6592 -309.327,
+                          -276.417 12.5733 -310.862,
+                          -110 38.7808 -335.699,
+                          -110 -38.7808 -335.699,
+                          -276.417 37.6592 -309.327,
+                          -443.333 60.7561 -280.837,
+                          -276.417 37.6592 -309.327,
+                          -443.333 36.5344 -282.876,
+                          -110 -38.7808 -335.699,
+                          -276.417 -12.5733 -310.862,
+                          -276.417 12.5733 -310.862,
+                          -443.333 12.1916 -283.899,
+                          -276.417 12.5733 -310.862,
+                          -276.417 -12.5733 -310.862,
+                          -443.333 36.5344 -282.876,
+                          -276.417 12.5733 -310.862,
+                          -443.333 12.1916 -283.899,
+                          -110 -38.7808 -335.699,
+                          -276.417 -37.6592 -309.327,
+                          -276.417 -12.5733 -310.862,
+                          -443.333 -12.1916 -283.899,
+                          -276.417 -12.5733 -310.862,
+                          -276.417 -37.6592 -309.327,
+                          -443.333 12.1916 -283.899,
+                          -276.417 -12.5733 -310.862,
+                          -443.333 -12.1916 -283.899,
+                          -110 -114.174 -317.487,
+                          -276.417 -62.5636 -306.268,
+                          -276.417 -37.6592 -309.327,
+                          -443.333 -36.5344 -282.876,
+                          -276.417 -37.6592 -309.327,
+                          -276.417 -62.5636 -306.268,
+                          -110 -38.7808 -335.699,
+                          -110 -114.174 -317.487,
+                          -276.417 -37.6592 -309.327,
+                          -443.333 -12.1916 -283.899,
+                          -276.417 -37.6592 -309.327,
+                          -443.333 -36.5344 -282.876,
+                          -110 -114.174 -317.487,
+                          -276.417 -87.1666 -301.702,
+                          -276.417 -62.5636 -306.268,
+                          -443.333 -60.7561 -280.837,
+                          -276.417 -62.5636 -306.268,
+                          -276.417 -87.1666 -301.702,
+                          -443.333 -36.5344 -282.876,
+                          -276.417 -62.5636 -306.268,
+                          -443.333 -60.7561 -280.837,
+                          -110 -114.174 -317.487,
+                          -276.417 -111.35 -295.659,
+                          -276.417 -87.1666 -301.702,
+                          -443.333 -84.7769 -277.793,
+                          -276.417 -87.1666 -301.702,
+                          -276.417 -111.35 -295.659,
+                          -443.333 -60.7561 -280.837,
+                          -276.417 -87.1666 -301.702,
+                          -443.333 -84.7769 -277.793,
+                          -110 -183.183 -282.081,
+                          -276.417 -134.999 -288.176,
+                          -276.417 -111.35 -295.659,
+                          -443.333 -108.518 -273.765,
+                          -276.417 -111.35 -295.659,
+                          -276.417 -134.999 -288.176,
+                          -110 -114.174 -317.487,
+                          -110 -183.183 -282.081,
+                          -276.417 -111.35 -295.659,
+                          -443.333 -84.7769 -277.793,
+                          -276.417 -111.35 -295.659,
+                          -443.333 -108.518 -273.765,
+                          -110 -183.183 -282.081,
+                          -276.417 -158.002 -279.3,
+                          -276.417 -134.999 -288.176,
+                          -443.333 -131.903 -268.778,
+                          -276.417 -134.999 -288.176,
+                          -276.417 -158.002 -279.3,
+                          -443.333 -108.518 -273.765,
+                          -276.417 -134.999 -288.176,
+                          -443.333 -131.903 -268.778,
+                          -110 -183.183 -282.081,
+                          -276.417 -180.25 -269.087,
+                          -276.417 -158.002 -279.3,
+                          -443.333 -154.857 -262.862,
+                          -276.417 -158.002 -279.3,
+                          -276.417 -180.25 -269.087,
+                          -443.333 -131.903 -268.778,
+                          -276.417 -158.002 -279.3,
+                          -443.333 -154.857 -262.862,
+                          -110 -241.948 -231.461,
+                          -276.417 -201.64 -257.599,
+                          -276.417 -180.25 -269.087,
+                          -443.333 -177.308 -256.054,
+                          -276.417 -180.25 -269.087,
+                          -276.417 -201.64 -257.599,
+                          -110 -183.183 -282.081,
+                          -110 -241.948 -231.461,
+                          -276.417 -180.25 -269.087,
+                          -443.333 -154.857 -262.862,
+                          -276.417 -180.25 -269.087,
+                          -443.333 -177.308 -256.054,
+                          -110 -241.948 -231.461,
+                          -276.417 -222.075 -244.91,
+                          -276.417 -201.64 -257.599,
+                          -443.333 -199.188 -248.397,
+                          -276.417 -201.64 -257.599,
+                          -276.417 -222.075 -244.91,
+                          -443.333 -177.308 -256.054,
+                          -276.417 -201.64 -257.599,
+                          -443.333 -199.188 -248.397,
+                          -110 -241.948 -231.461,
+                          -276.417 -241.462 -231.097,
+                          -276.417 -222.075 -244.91,
+                          -443.333 -220.43 -239.938,
+                          -276.417 -222.075 -244.91,
+                          -276.417 -241.462 -231.097,
+                          -443.333 -199.188 -248.397,
+                          -276.417 -222.075 -244.91,
+                          -443.333 -220.43 -239.938,
+                          -110 -286.505 -169.683,
+                          -276.417 -241.462 -231.097,
+                          -110 -241.948 -231.461,
+                          -443.333 -220.43 -239.938,
+                          -276.417 -241.462 -231.097,
+                          -443.333 -240.975 -230.731,
+                          -276.417 -270.093 -179.674,
+                          -443.333 -240.975 -230.731,
+                          -276.417 -241.462 -231.097,
+                          -110 -286.505 -169.683,
+                          -276.417 -270.093 -179.674,
+                          -276.417 -241.462 -231.097,
+                          0 -241.948 -231.461,
+                          -110 -241.948 -231.461,
+                          -110 -183.183 -282.081,
+                          1.13687e-13 -290.283 -162.705,
+                          -110 -286.505 -169.683,
+                          -110 -241.948 -231.461,
+                          1.13687e-13 -290.283 -162.705,
+                          -110 -241.948 -231.461,
+                          0 -241.948 -231.461,
+                          0 -183.175 -282.082,
+                          -110 -183.183 -282.081,
+                          -110 -114.174 -317.487,
+                          0 -241.948 -231.461,
+                          -110 -183.183 -282.081,
+                          0 -183.175 -282.082,
+                          0 -114.189 -317.481,
+                          -110 -114.174 -317.487,
+                          -110 -38.7808 -335.699,
+                          0 -183.175 -282.082,
+                          -110 -114.174 -317.487,
+                          0 -114.189 -317.481,
+                          0 -38.7641 -335.699,
+                          -110 -38.7808 -335.699,
+                          -110 38.7808 -335.699,
+                          0 -114.189 -317.481,
+                          -110 -38.7808 -335.699,
+                          0 -38.7641 -335.699,
+                          0 38.7641 -335.699,
+                          -110 38.7808 -335.699,
+                          -110 114.174 -317.487,
+                          0 -38.7641 -335.699,
+                          -110 38.7808 -335.699,
+                          0 38.7641 -335.699,
+                          0 114.189 -317.481,
+                          -110 114.174 -317.487,
+                          -110 183.183 -282.081,
+                          0 38.7641 -335.699,
+                          -110 114.174 -317.487,
+                          0 114.189 -317.481,
+                          0 114.189 -317.481,
+                          -110 183.183 -282.081,
+                          0 183.175 -282.082,
+                          -443.333 -240.975 -230.731,
+                          -610.25 -240.487 -230.365,
+                          -610.25 -218.786 -234.967,
+                          -443.333 -260.059 -178.671,
+                          -610.25 -240.487 -230.365,
+                          -443.333 -240.975 -230.731,
+                          -443.333 -260.059 -178.671,
+                          -610.25 -250.024 -177.669,
+                          -610.25 -240.487 -230.365,
+                          -443.333 -220.43 -239.938,
+                          -610.25 -218.786 -234.967,
+                          -610.25 -196.736 -239.194,
+                          -443.333 -220.43 -239.938,
+                          -443.333 -240.975 -230.731,
+                          -610.25 -218.786 -234.967,
+                          -443.333 -199.188 -248.397,
+                          -610.25 -196.736 -239.194,
+                          -610.25 -174.367 -243.02,
+                          -443.333 -199.188 -248.397,
+                          -443.333 -220.43 -239.938,
+                          -610.25 -196.736 -239.194,
+                          -443.333 -177.308 -256.054,
+                          -610.25 -174.367 -243.02,
+                          -610.25 -151.713 -246.423,
+                          -443.333 -177.308 -256.054,
+                          -443.333 -199.188 -248.397,
+                          -610.25 -174.367 -243.02,
+                          -443.333 -154.857 -262.862,
+                          -610.25 -151.713 -246.423,
+                          -610.25 -128.807 -249.379,
+                          -443.333 -154.857 -262.862,
+                          -443.333 -177.308 -256.054,
+                          -610.25 -151.713 -246.423,
+                          -443.333 -131.903 -268.778,
+                          -610.25 -128.807 -249.379,
+                          -610.25 -105.686 -251.872,
+                          -443.333 -131.903 -268.778,
+                          -443.333 -154.857 -262.862,
+                          -610.25 -128.807 -249.379,
+                          -443.333 -108.518 -273.765,
+                          -610.25 -105.686 -251.872,
+                          -610.25 -82.3873 -253.885,
+                          -443.333 -108.518 -273.765,
+                          -443.333 -131.903 -268.778,
+                          -610.25 -105.686 -251.872,
+                          -443.333 -84.7769 -277.793,
+                          -610.25 -82.3873 -253.885,
+                          -610.25 -58.9486 -255.406,
+                          -443.333 -84.7769 -277.793,
+                          -443.333 -108.518 -273.765,
+                          -610.25 -82.3873 -253.885,
+                          -443.333 -60.7561 -280.837,
+                          -610.25 -58.9486 -255.406,
+                          -610.25 -35.4095 -256.425,
+                          -443.333 -60.7561 -280.837,
+                          -443.333 -84.7769 -277.793,
+                          -610.25 -58.9486 -255.406,
+                          -443.333 -36.5344 -282.876,
+                          -610.25 -35.4095 -256.425,
+                          -610.25 -11.8099 -256.936,
+                          -443.333 -36.5344 -282.876,
+                          -443.333 -60.7561 -280.837,
+                          -610.25 -35.4095 -256.425,
+                          -443.333 -12.1916 -283.899,
+                          -610.25 -11.8099 -256.936,
+                          -610.25 11.8099 -256.936,
+                          -443.333 -12.1916 -283.899,
+                          -443.333 -36.5344 -282.876,
+                          -610.25 -11.8099 -256.936,
+                          -443.333 12.1916 -283.899,
+                          -610.25 11.8099 -256.936,
+                          -610.25 35.4095 -256.425,
+                          -443.333 12.1916 -283.899,
+                          -443.333 -12.1916 -283.899,
+                          -610.25 11.8099 -256.936,
+                          -443.333 36.5344 -282.876,
+                          -610.25 35.4095 -256.425,
+                          -610.25 58.9486 -255.406,
+                          -443.333 36.5344 -282.876,
+                          -443.333 12.1916 -283.899,
+                          -610.25 35.4095 -256.425,
+                          -443.333 60.7561 -280.837,
+                          -610.25 58.9486 -255.406,
+                          -610.25 82.3873 -253.885,
+                          -443.333 60.7561 -280.837,
+                          -443.333 36.5344 -282.876,
+                          -610.25 58.9486 -255.406,
+                          -443.333 84.7769 -277.793,
+                          -610.25 82.3873 -253.885,
+                          -610.25 105.686 -251.872,
+                          -443.333 84.7769 -277.793,
+                          -443.333 60.7561 -280.837,
+                          -610.25 82.3873 -253.885,
+                          -443.333 108.518 -273.765,
+                          -610.25 105.686 -251.872,
+                          -610.25 128.807 -249.379,
+                          -443.333 108.518 -273.765,
+                          -443.333 84.7769 -277.793,
+                          -610.25 105.686 -251.872,
+                          -443.333 131.903 -268.778,
+                          -610.25 128.807 -249.379,
+                          -610.25 151.713 -246.423,
+                          -443.333 131.903 -268.778,
+                          -443.333 108.518 -273.765,
+                          -610.25 128.807 -249.379,
+                          -443.333 154.857 -262.862,
+                          -610.25 151.713 -246.423,
+                          -610.25 174.367 -243.02,
+                          -443.333 154.857 -262.862,
+                          -443.333 131.903 -268.778,
+                          -610.25 151.713 -246.423,
+                          -443.333 177.308 -256.054,
+                          -610.25 174.367 -243.02,
+                          -610.25 196.736 -239.194,
+                          -443.333 177.308 -256.054,
+                          -443.333 154.857 -262.862,
+                          -610.25 174.367 -243.02,
+                          -443.333 199.188 -248.397,
+                          -610.25 196.736 -239.194,
+                          -610.25 218.786 -234.967,
+                          -443.333 199.188 -248.397,
+                          -443.333 177.308 -256.054,
+                          -610.25 196.736 -239.194,
+                          -443.333 220.43 -239.938,
+                          -610.25 218.786 -234.967,
+                          -610.25 240.487 -230.365,
+                          -443.333 220.43 -239.938,
+                          -443.333 199.188 -248.397,
+                          -610.25 218.786 -234.967,
+                          -443.333 220.43 -239.938,
+                          -610.25 240.487 -230.365,
+                          -443.333 240.975 -230.731,
+                          -610.25 250.024 -177.669,
+                          -443.333 240.975 -230.731,
+                          -610.25 240.487 -230.365,
+                          -443.333 260.059 -178.671,
+                          -443.333 240.975 -230.731,
+                          -610.25 250.024 -177.669,
+                          -443.333 -260.059 -178.671,
+                          -443.333 -240.975 -230.731,
+                          -276.417 -270.093 -179.674,
+                          -110 322.111 51.8775,
+                          -243 287.358 117.625,
+                          -110 299.153 124.506,
+                          -243 269.616 143.121,
+                          -110 299.153 124.506,
+                          -243 287.358 117.625,
+                          -1.13687e-13 314.648 82.6285,
+                          -110 322.111 51.8775,
+                          -110 299.153 124.506,
+                          -243 269.616 143.121,
+                          -243 249.171 167.026,
+                          -110 299.153 124.506,
+                          -110 255.516 195.659,
+                          -110 299.153 124.506,
+                          -243 249.171 167.026,
+                          -1.13687e-13 280.776 159.554,
+                          -110 299.153 124.506,
+                          -110 255.516 195.659,
+                          -1.13687e-13 314.648 82.6285,
+                          -110 299.153 124.506,
+                          -1.13687e-13 280.776 159.554,
+                          -110 322.111 51.8775,
+                          -276.417 284.394 115.896,
+                          -243 287.358 117.625,
+                          -376.533 256.495 129.838,
+                          -243 287.358 117.625,
+                          -276.417 284.394 115.896,
+                          -376.533 256.495 129.838,
+                          -243 269.616 143.121,
+                          -243 287.358 117.625,
+                          -110 322.111 51.8775,
+                          -276.417 299.641 57.4228,
+                          -276.417 284.394 115.896,
+                          -376.533 275.515 110.717,
+                          -276.417 284.394 115.896,
+                          -276.417 299.641 57.4228,
+                          -376.533 256.495 129.838,
+                          -276.417 284.394 115.896,
+                          -376.533 275.515 110.717,
+                          -110 322.111 51.8775,
+                          -276.417 305.896 -3.14267,
+                          -276.417 299.641 57.4228,
+                          -443.333 279.754 50.5018,
+                          -276.417 299.641 57.4228,
+                          -276.417 305.896 -3.14267,
+                          -443.333 269.591 107.261,
+                          -276.417 299.641 57.4228,
+                          -443.333 279.754 50.5018,
+                          -376.533 275.515 110.717,
+                          -276.417 299.641 57.4228,
+                          -443.333 269.591 107.261,
+                          -110 327.697 -24.0876,
+                          -276.417 302.926 -64.0277,
+                          -276.417 305.896 -3.14267,
+                          -443.333 283.924 -7.65217,
+                          -276.417 305.896 -3.14267,
+                          -276.417 302.926 -64.0277,
+                          -110 322.111 51.8775,
+                          -110 327.697 -24.0876,
+                          -276.417 305.896 -3.14267,
+                          -443.333 279.754 50.5018,
+                          -276.417 305.896 -3.14267,
+                          -443.333 283.924 -7.65217,
+                          -110 315.612 -99.293,
+                          -276.417 290.84 -123.448,
+                          -276.417 302.926 -64.0277,
+                          -443.333 281.943 -66.0191,
+                          -276.417 302.926 -64.0277,
+                          -276.417 290.84 -123.448,
+                          -110 327.697 -24.0876,
+                          -110 315.612 -99.293,
+                          -276.417 302.926 -64.0277,
+                          -443.333 283.924 -7.65217,
+                          -276.417 302.926 -64.0277,
+                          -443.333 281.943 -66.0191,
+                          -110 286.505 -169.683,
+                          -276.417 270.093 -179.674,
+                          -276.417 290.84 -123.448,
+                          -443.333 273.888 -123.41,
+                          -276.417 290.84 -123.448,
+                          -276.417 270.093 -179.674,
+                          -110 315.612 -99.293,
+                          -110 286.505 -169.683,
+                          -276.417 290.84 -123.448,
+                          -443.333 281.943 -66.0191,
+                          -276.417 290.84 -123.448,
+                          -443.333 273.888 -123.41,
+                          -443.333 273.888 -123.41,
+                          -276.417 270.093 -179.674,
+                          -443.333 260.059 -178.671,
+                          -1.13687e-13 290.282 -162.707,
+                          -110 286.505 -169.683,
+                          -110 315.612 -99.293,
+                          -1.13687e-13 290.282 -162.707,
+                          0 241.948 -231.461,
+                          -110 286.505 -169.683,
+                          -1.13687e-13 319.551 -83.9536,
+                          -110 315.612 -99.293,
+                          -110 327.697 -24.0876,
+                          -1.13687e-13 290.282 -162.707,
+                          -110 315.612 -99.293,
+                          -1.13687e-13 319.551 -83.9536,
+                          -1.13687e-13 327.855 -0.354372,
+                          -110 327.697 -24.0876,
+                          -110 322.111 51.8775,
+                          -1.13687e-13 319.551 -83.9536,
+                          -110 327.697 -24.0876,
+                          -1.13687e-13 327.855 -0.354372,
+                          -1.13687e-13 327.855 -0.354372,
+                          -110 322.111 51.8775,
+                          -1.13687e-13 314.648 82.6285,
+                          -443.333 260.059 -178.671,
+                          -610.25 250.024 -177.669,
+                          -610.25 256.935 -123.372,
+                          -443.333 273.888 -123.41,
+                          -610.25 256.935 -123.372,
+                          -610.25 260.961 -68.0106,
+                          -443.333 273.888 -123.41,
+                          -443.333 260.059 -178.671,
+                          -610.25 256.935 -123.372,
+                          -443.333 281.943 -66.0191,
+                          -610.25 260.961 -68.0106,
+                          -610.25 261.951 -12.1617,
+                          -443.333 281.943 -66.0191,
+                          -443.333 273.888 -123.41,
+                          -610.25 260.961 -68.0106,
+                          -443.333 283.924 -7.65217,
+                          -610.25 261.951 -12.1617,
+                          -610.25 259.867 43.5808,
+                          -443.333 283.924 -7.65217,
+                          -443.333 281.943 -66.0191,
+                          -610.25 261.951 -12.1617,
+                          -643.6 251.831 96.9011,
+                          -610.25 254.788 98.6264,
+                          -610.25 259.867 43.5808,
+                          -443.333 279.754 50.5018,
+                          -610.25 259.867 43.5808,
+                          -610.25 254.788 98.6264,
+                          -443.333 279.754 50.5018,
+                          -443.333 283.924 -7.65217,
+                          -610.25 259.867 43.5808,
+                          -643.6 230.251 103.27,
+                          -610.25 254.788 98.6264,
+                          -643.6 251.831 96.9011,
+                          -443.333 279.754 50.5018,
+                          -610.25 254.788 98.6264,
+                          -510.067 263.673 103.809,
+                          -643.6 230.251 103.27,
+                          -510.067 263.673 103.809,
+                          -610.25 254.788 98.6264,
+                          -443.333 269.591 107.261,
+                          -443.333 279.754 50.5018,
+                          -510.067 263.673 103.809,
+                          -510.067 243.373 116.554,
+                          -443.333 269.591 107.261,
+                          -510.067 263.673 103.809,
+                          -510.067 243.373 116.554,
+                          -510.067 263.673 103.809,
+                          -643.6 230.251 103.27,
+                          -510.067 243.373 116.554,
+                          -376.533 275.515 110.717,
+                          -443.333 269.591 107.261,
+                          -376.533 256.495 129.838,
+                          -376.533 275.515 110.717,
+                          -510.067 243.373 116.554,
+                          -110 -255.516 195.659,
+                          -243 -287.358 117.625,
+                          -110 -299.153 124.506,
+                          -276.417 -299.641 57.4228,
+                          -110 -299.153 124.506,
+                          -243 -287.358 117.625,
+                          1.13687e-13 -280.771 159.562,
+                          -110 -255.516 195.659,
+                          -110 -299.153 124.506,
+                          -110 -322.111 51.8775,
+                          -110 -299.153 124.506,
+                          -276.417 -299.641 57.4228,
+                          1.13687e-13 -314.646 82.6358,
+                          -110 -299.153 124.506,
+                          -110 -322.111 51.8775,
+                          1.13687e-13 -280.771 159.562,
+                          -110 -299.153 124.506,
+                          1.13687e-13 -314.646 82.6358,
+                          -110 -255.516 195.659,
+                          -243 -269.616 143.121,
+                          -243 -287.358 117.625,
+                          -276.417 -284.394 115.896,
+                          -243 -287.358 117.625,
+                          -243 -269.616 143.121,
+                          -276.417 -299.641 57.4228,
+                          -243 -287.358 117.625,
+                          -276.417 -284.394 115.896,
+                          -110 -255.516 195.659,
+                          -243 -249.171 167.026,
+                          -243 -269.616 143.121,
+                          -376.533 -256.495 129.838,
+                          -243 -269.616 143.121,
+                          -243 -249.171 167.026,
+                          -376.533 -275.515 110.717,
+                          -243 -269.616 143.121,
+                          -376.533 -256.495 129.838,
+                          -276.417 -284.394 115.896,
+                          -243 -269.616 143.121,
+                          -376.533 -275.515 110.717,
+                          -110 -255.516 195.659,
+                          -243 -226.212 189.054,
+                          -243 -249.171 167.026,
+                          -376.533 -235.447 147.765,
+                          -243 -249.171 167.026,
+                          -243 -226.212 189.054,
+                          -376.533 -256.495 129.838,
+                          -243 -249.171 167.026,
+                          -376.533 -235.447 147.765,
+                          -110 -195.333 253.494,
+                          -243 -200.959 208.942,
+                          -243 -226.212 189.054,
+                          -376.533 -212.513 164.284,
+                          -243 -226.212 189.054,
+                          -243 -200.959 208.942,
+                          -110 -255.516 195.659,
+                          -110 -195.333 253.494,
+                          -243 -226.212 189.054,
+                          -376.533 -235.447 147.765,
+                          -243 -226.212 189.054,
+                          -376.533 -212.513 164.284,
+                          -110 -195.333 253.494,
+                          -243 -173.659 226.453,
+                          -243 -200.959 208.942,
+                          -376.533 -187.859 179.199,
+                          -243 -200.959 208.942,
+                          -243 -173.659 226.453,
+                          -376.533 -212.513 164.284,
+                          -243 -200.959 208.942,
+                          -376.533 -187.859 179.199,
+                          -110 -122.5 294.266,
+                          -243 -144.583 241.377,
+                          -243 -173.659 226.453,
+                          -376.533 -161.67 192.331,
+                          -243 -173.659 226.453,
+                          -243 -144.583 241.377,
+                          -110 -195.333 253.494,
+                          -110 -122.5 294.266,
+                          -243 -173.659 226.453,
+                          -376.533 -187.859 179.199,
+                          -243 -173.659 226.453,
+                          -376.533 -161.67 192.331,
+                          -110 -122.5 294.266,
+                          -243 -114.025 253.535,
+                          -243 -144.583 241.377,
+                          -376.533 -134.149 203.523,
+                          -243 -144.583 241.377,
+                          -243 -114.025 253.535,
+                          -376.533 -161.67 192.331,
+                          -243 -144.583 241.377,
+                          -376.533 -134.149 203.523,
+                          -110 -41.7341 315.334,
+                          -243 -82.2958 262.784,
+                          -243 -114.025 253.535,
+                          -376.533 -105.517 212.641,
+                          -243 -114.025 253.535,
+                          -243 -82.2958 262.784,
+                          -110 -122.5 294.266,
+                          -110 -41.7341 315.334,
+                          -243 -114.025 253.535,
+                          -376.533 -134.149 203.523,
+                          -243 -114.025 253.535,
+                          -376.533 -105.517 212.641,
+                          -110 -41.7341 315.334,
+                          -243 -49.7192 269.012,
+                          -243 -82.2958 262.784,
+                          -376.533 -76.006 219.577,
+                          -243 -82.2958 262.784,
+                          -243 -49.7192 269.012,
+                          -376.533 -105.517 212.641,
+                          -243 -82.2958 262.784,
+                          -376.533 -76.006 219.577,
+                          -110 -41.7341 315.334,
+                          -243 -16.6302 272.144,
+                          -243 -49.7192 269.012,
+                          -376.533 -45.8598 224.248,
+                          -243 -49.7192 269.012,
+                          -243 -16.6302 272.144,
+                          -376.533 -76.006 219.577,
+                          -243 -49.7192 269.012,
+                          -376.533 -45.8598 224.248,
+                          -110 41.7341 315.334,
+                          -243 16.6302 272.144,
+                          -243 -16.6302 272.144,
+                          -376.533 -15.3295 226.597,
+                          -243 -16.6302 272.144,
+                          -243 16.6302 272.144,
+                          -110 -41.7341 315.334,
+                          -110 41.7341 315.334,
+                          -243 -16.6302 272.144,
+                          -376.533 -45.8598 224.248,
+                          -243 -16.6302 272.144,
+                          -376.533 -15.3295 226.597,
+                          -110 41.7341 315.334,
+                          -243 49.7192 269.012,
+                          -243 16.6302 272.144,
+                          -376.533 15.3295 226.597,
+                          -243 16.6302 272.144,
+                          -243 49.7192 269.012,
+                          -376.533 -15.3295 226.597,
+                          -243 16.6302 272.144,
+                          -376.533 15.3295 226.597,
+                          -110 122.5 294.266,
+                          -243 82.2958 262.784,
+                          -243 49.7192 269.012,
+                          -376.533 45.8598 224.248,
+                          -243 49.7192 269.012,
+                          -243 82.2958 262.784,
+                          -110 41.7341 315.334,
+                          -110 122.5 294.266,
+                          -243 49.7192 269.012,
+                          -376.533 15.3295 226.597,
+                          -243 49.7192 269.012,
+                          -376.533 45.8598 224.248,
+                          -110 122.5 294.266,
+                          -243 114.025 253.535,
+                          -243 82.2958 262.784,
+                          -376.533 76.006 219.577,
+                          -243 82.2958 262.784,
+                          -243 114.025 253.535,
+                          -376.533 45.8598 224.248,
+                          -243 82.2958 262.784,
+                          -376.533 76.006 219.577,
+                          -110 195.333 253.494,
+                          -243 144.583 241.377,
+                          -243 114.025 253.535,
+                          -376.533 105.517 212.641,
+                          -243 114.025 253.535,
+                          -243 144.583 241.377,
+                          -110 122.5 294.266,
+                          -110 195.333 253.494,
+                          -243 114.025 253.535,
+                          -376.533 76.006 219.577,
+                          -243 114.025 253.535,
+                          -376.533 105.517 212.641,
+                          -110 195.333 253.494,
+                          -243 173.659 226.453,
+                          -243 144.583 241.377,
+                          -376.533 134.149 203.523,
+                          -243 144.583 241.377,
+                          -243 173.659 226.453,
+                          -376.533 105.517 212.641,
+                          -243 144.583 241.377,
+                          -376.533 134.149 203.523,
+                          -110 195.333 253.494,
+                          -243 200.959 208.942,
+                          -243 173.659 226.453,
+                          -376.533 161.67 192.331,
+                          -243 173.659 226.453,
+                          -243 200.959 208.942,
+                          -376.533 134.149 203.523,
+                          -243 173.659 226.453,
+                          -376.533 161.67 192.331,
+                          -110 255.516 195.659,
+                          -243 226.212 189.054,
+                          -243 200.959 208.942,
+                          -376.533 187.859 179.199,
+                          -243 200.959 208.942,
+                          -243 226.212 189.054,
+                          -110 195.333 253.494,
+                          -110 255.516 195.659,
+                          -243 200.959 208.942,
+                          -376.533 161.67 192.331,
+                          -243 200.959 208.942,
+                          -376.533 187.859 179.199,
+                          -110 255.516 195.659,
+                          -243 249.171 167.026,
+                          -243 226.212 189.054,
+                          -376.533 212.513 164.284,
+                          -243 226.212 189.054,
+                          -243 249.171 167.026,
+                          -376.533 187.859 179.199,
+                          -243 226.212 189.054,
+                          -376.533 212.513 164.284,
+                          -376.533 235.447 147.765,
+                          -243 249.171 167.026,
+                          -243 269.616 143.121,
+                          -376.533 212.513 164.284,
+                          -243 249.171 167.026,
+                          -376.533 235.447 147.765,
+                          -376.533 235.447 147.765,
+                          -243 269.616 143.121,
+                          -376.533 256.495 129.838,
+                          0 228.482 225.326,
+                          -110 255.516 195.659,
+                          -110 195.333 253.494,
+                          -1.13687e-13 280.776 159.554,
+                          -110 255.516 195.659,
+                          0 228.482 225.326,
+                          0 161.209 275.646,
+                          -110 195.333 253.494,
+                          -110 122.5 294.266,
+                          0 228.482 225.326,
+                          -110 195.333 253.494,
+                          0 161.209 275.646,
+                          0 83.355 307.23,
+                          -110 122.5 294.266,
+                          -110 41.7341 315.334,
+                          0 161.209 275.646,
+                          -110 122.5 294.266,
+                          0 83.355 307.23,
+                          0 0.00431946 318,
+                          -110 41.7341 315.334,
+                          -110 -41.7341 315.334,
+                          0 83.355 307.23,
+                          -110 41.7341 315.334,
+                          0 0.00431946 318,
+                          0 -83.3467 307.232,
+                          -110 -41.7341 315.334,
+                          -110 -122.5 294.266,
+                          0 0.00431946 318,
+                          -110 -41.7341 315.334,
+                          0 -83.3467 307.232,
+                          0 -161.201 275.65,
+                          -110 -122.5 294.266,
+                          -110 -195.333 253.494,
+                          0 -83.3467 307.232,
+                          -110 -122.5 294.266,
+                          0 -161.201 275.65,
+                          0 -228.476 225.332,
+                          -110 -195.333 253.494,
+                          -110 -255.516 195.659,
+                          0 -161.201 275.65,
+                          -110 -195.333 253.494,
+                          0 -228.476 225.332,
+                          0 -228.476 225.332,
+                          -110 -255.516 195.659,
+                          1.13687e-13 -280.771 159.562,
+                          -510.067 243.373 116.554,
+                          -643.6 230.251 103.27,
+                          -643.6 207.997 109.242,
+                          -510.067 221.722 128.503,
+                          -643.6 207.997 109.242,
+                          -643.6 185.114 114.745,
+                          -510.067 221.722 128.503,
+                          -510.067 243.373 116.554,
+                          -643.6 207.997 109.242,
+                          -510.067 198.814 139.515,
+                          -643.6 185.114 114.745,
+                          -643.6 161.658 119.713,
+                          -510.067 198.814 139.515,
+                          -510.067 221.722 128.503,
+                          -643.6 185.114 114.745,
+                          -510.067 174.759 149.456,
+                          -643.6 161.658 119.713,
+                          -643.6 137.691 124.088,
+                          -510.067 174.759 149.456,
+                          -510.067 198.814 139.515,
+                          -643.6 161.658 119.713,
+                          -510.067 149.68 158.209,
+                          -643.6 137.691 124.088,
+                          -643.6 113.281 127.816,
+                          -510.067 149.68 158.209,
+                          -510.067 174.759 149.456,
+                          -643.6 137.691 124.088,
+                          -510.067 123.715 165.669,
+                          -643.6 113.281 127.816,
+                          -643.6 88.5 130.853,
+                          -510.067 123.715 165.669,
+                          -510.067 149.68 158.209,
+                          -643.6 113.281 127.816,
+                          -510.067 97.0084 171.747,
+                          -643.6 88.5 130.853,
+                          -643.6 63.4264 133.164,
+                          -510.067 97.0084 171.747,
+                          -510.067 123.715 165.669,
+                          -643.6 88.5 130.853,
+                          -510.067 69.7162 176.37,
+                          -643.6 63.4264 133.164,
+                          -643.6 38.1412 134.719,
+                          -510.067 69.7162 176.37,
+                          -510.067 97.0084 171.747,
+                          -643.6 63.4264 133.164,
+                          -510.067 42.0005 179.484,
+                          -643.6 38.1412 134.719,
+                          -643.6 12.728 135.502,
+                          -510.067 42.0005 179.484,
+                          -510.067 69.7162 176.37,
+                          -643.6 38.1412 134.719,
+                          -510.067 14.0287 181.049,
+                          -643.6 12.728 135.502,
+                          -643.6 -12.728 135.502,
+                          -510.067 14.0287 181.049,
+                          -510.067 42.0005 179.484,
+                          -643.6 12.728 135.502,
+                          -510.067 -14.0287 181.049,
+                          -643.6 -12.728 135.502,
+                          -643.6 -38.1412 134.719,
+                          -510.067 -14.0287 181.049,
+                          -510.067 14.0287 181.049,
+                          -643.6 -12.728 135.502,
+                          -510.067 -42.0005 179.484,
+                          -643.6 -38.1412 134.719,
+                          -643.6 -63.4264 133.164,
+                          -510.067 -42.0005 179.484,
+                          -510.067 -14.0287 181.049,
+                          -643.6 -38.1412 134.719,
+                          -510.067 -69.7162 176.37,
+                          -643.6 -63.4264 133.164,
+                          -643.6 -88.5 130.853,
+                          -510.067 -69.7162 176.37,
+                          -510.067 -42.0005 179.484,
+                          -643.6 -63.4264 133.164,
+                          -510.067 -97.0084 171.747,
+                          -643.6 -88.5 130.853,
+                          -643.6 -113.281 127.816,
+                          -510.067 -97.0084 171.747,
+                          -510.067 -69.7162 176.37,
+                          -643.6 -88.5 130.853,
+                          -510.067 -123.715 165.669,
+                          -643.6 -113.281 127.816,
+                          -643.6 -137.691 124.088,
+                          -510.067 -123.715 165.669,
+                          -510.067 -97.0084 171.747,
+                          -643.6 -113.281 127.816,
+                          -510.067 -149.68 158.209,
+                          -643.6 -137.691 124.088,
+                          -643.6 -161.658 119.713,
+                          -510.067 -149.68 158.209,
+                          -510.067 -123.715 165.669,
+                          -643.6 -137.691 124.088,
+                          -510.067 -174.759 149.456,
+                          -643.6 -161.658 119.713,
+                          -643.6 -185.114 114.745,
+                          -510.067 -174.759 149.456,
+                          -510.067 -149.68 158.209,
+                          -643.6 -161.658 119.713,
+                          -510.067 -198.814 139.515,
+                          -643.6 -185.114 114.745,
+                          -643.6 -207.997 109.242,
+                          -510.067 -198.814 139.515,
+                          -510.067 -174.759 149.456,
+                          -643.6 -185.114 114.745,
+                          -510.067 -221.722 128.503,
+                          -643.6 -207.997 109.242,
+                          -643.6 -230.251 103.27,
+                          -510.067 -221.722 128.503,
+                          -510.067 -198.814 139.515,
+                          -643.6 -207.997 109.242,
+                          -510.067 -243.373 116.554,
+                          -643.6 -230.251 103.27,
+                          -643.6 -251.831 96.9011,
+                          -510.067 -243.373 116.554,
+                          -510.067 -221.722 128.503,
+                          -643.6 -230.251 103.27,
+                          -510.067 -243.373 116.554,
+                          -643.6 -251.831 96.9011,
+                          -610.25 -254.788 98.6264,
+                          -510.067 -263.673 103.809,
+                          -510.067 -243.373 116.554,
+                          -610.25 -254.788 98.6264,
+                          -610.25 -259.867 43.5808,
+                          -510.067 -263.673 103.809,
+                          -610.25 -254.788 98.6264,
+                          -376.533 256.495 129.838,
+                          -510.067 243.373 116.554,
+                          -510.067 221.722 128.503,
+                          -376.533 235.447 147.765,
+                          -510.067 221.722 128.503,
+                          -510.067 198.814 139.515,
+                          -376.533 235.447 147.765,
+                          -376.533 256.495 129.838,
+                          -510.067 221.722 128.503,
+                          -376.533 212.513 164.284,
+                          -510.067 198.814 139.515,
+                          -510.067 174.759 149.456,
+                          -376.533 212.513 164.284,
+                          -376.533 235.447 147.765,
+                          -510.067 198.814 139.515,
+                          -376.533 187.859 179.199,
+                          -510.067 174.759 149.456,
+                          -510.067 149.68 158.209,
+                          -376.533 187.859 179.199,
+                          -376.533 212.513 164.284,
+                          -510.067 174.759 149.456,
+                          -376.533 161.67 192.331,
+                          -510.067 149.68 158.209,
+                          -510.067 123.715 165.669,
+                          -376.533 161.67 192.331,
+                          -376.533 187.859 179.199,
+                          -510.067 149.68 158.209,
+                          -376.533 134.149 203.523,
+                          -510.067 123.715 165.669,
+                          -510.067 97.0084 171.747,
+                          -376.533 134.149 203.523,
+                          -376.533 161.67 192.331,
+                          -510.067 123.715 165.669,
+                          -376.533 105.517 212.641,
+                          -510.067 97.0084 171.747,
+                          -510.067 69.7162 176.37,
+                          -376.533 105.517 212.641,
+                          -376.533 134.149 203.523,
+                          -510.067 97.0084 171.747,
+                          -376.533 76.006 219.577,
+                          -510.067 69.7162 176.37,
+                          -510.067 42.0005 179.484,
+                          -376.533 76.006 219.577,
+                          -376.533 105.517 212.641,
+                          -510.067 69.7162 176.37,
+                          -376.533 45.8598 224.248,
+                          -510.067 42.0005 179.484,
+                          -510.067 14.0287 181.049,
+                          -376.533 45.8598 224.248,
+                          -376.533 76.006 219.577,
+                          -510.067 42.0005 179.484,
+                          -376.533 15.3295 226.597,
+                          -510.067 14.0287 181.049,
+                          -510.067 -14.0287 181.049,
+                          -376.533 15.3295 226.597,
+                          -376.533 45.8598 224.248,
+                          -510.067 14.0287 181.049,
+                          -376.533 -15.3295 226.597,
+                          -510.067 -14.0287 181.049,
+                          -510.067 -42.0005 179.484,
+                          -376.533 -15.3295 226.597,
+                          -376.533 15.3295 226.597,
+                          -510.067 -14.0287 181.049,
+                          -376.533 -45.8598 224.248,
+                          -510.067 -42.0005 179.484,
+                          -510.067 -69.7162 176.37,
+                          -376.533 -45.8598 224.248,
+                          -376.533 -15.3295 226.597,
+                          -510.067 -42.0005 179.484,
+                          -376.533 -76.006 219.577,
+                          -510.067 -69.7162 176.37,
+                          -510.067 -97.0084 171.747,
+                          -376.533 -76.006 219.577,
+                          -376.533 -45.8598 224.248,
+                          -510.067 -69.7162 176.37,
+                          -376.533 -105.517 212.641,
+                          -510.067 -97.0084 171.747,
+                          -510.067 -123.715 165.669,
+                          -376.533 -105.517 212.641,
+                          -376.533 -76.006 219.577,
+                          -510.067 -97.0084 171.747,
+                          -376.533 -134.149 203.523,
+                          -510.067 -123.715 165.669,
+                          -510.067 -149.68 158.209,
+                          -376.533 -134.149 203.523,
+                          -376.533 -105.517 212.641,
+                          -510.067 -123.715 165.669,
+                          -376.533 -161.67 192.331,
+                          -510.067 -149.68 158.209,
+                          -510.067 -174.759 149.456,
+                          -376.533 -161.67 192.331,
+                          -376.533 -134.149 203.523,
+                          -510.067 -149.68 158.209,
+                          -376.533 -187.859 179.199,
+                          -510.067 -174.759 149.456,
+                          -510.067 -198.814 139.515,
+                          -376.533 -187.859 179.199,
+                          -376.533 -161.67 192.331,
+                          -510.067 -174.759 149.456,
+                          -376.533 -212.513 164.284,
+                          -510.067 -198.814 139.515,
+                          -510.067 -221.722 128.503,
+                          -376.533 -212.513 164.284,
+                          -376.533 -187.859 179.199,
+                          -510.067 -198.814 139.515,
+                          -376.533 -235.447 147.765,
+                          -510.067 -221.722 128.503,
+                          -510.067 -243.373 116.554,
+                          -376.533 -235.447 147.765,
+                          -376.533 -212.513 164.284,
+                          -510.067 -221.722 128.503,
+                          -376.533 -256.495 129.838,
+                          -510.067 -243.373 116.554,
+                          -510.067 -263.673 103.809,
+                          -376.533 -256.495 129.838,
+                          -376.533 -235.447 147.765,
+                          -510.067 -243.373 116.554,
+                          -376.533 -256.495 129.838,
+                          -510.067 -263.673 103.809,
+                          -443.333 -269.591 107.261,
+                          -610.25 -259.867 43.5808,
+                          -443.333 -269.591 107.261,
+                          -510.067 -263.673 103.809,
+                          -376.533 -275.515 110.717,
+                          -376.533 -256.495 129.838,
+                          -443.333 -269.591 107.261,
+                          -443.333 -279.754 50.5018,
+                          -376.533 -275.515 110.717,
+                          -443.333 -269.591 107.261,
+                          -443.333 -279.754 50.5018,
+                          -443.333 -269.591 107.261,
+                          -610.25 -259.867 43.5808,
+                          -443.333 -279.754 50.5018,
+                          -276.417 -284.394 115.896,
+                          -376.533 -275.515 110.717,
+                          -443.333 -279.754 50.5018,
+                          -276.417 -299.641 57.4228,
+                          -276.417 -284.394 115.896,
+                          -110 -286.505 -169.683,
+                          -276.417 -290.84 -123.448,
+                          -276.417 -270.093 -179.674,
+                          -443.333 -260.059 -178.671,
+                          -276.417 -270.093 -179.674,
+                          -276.417 -290.84 -123.448,
+                          -110 -315.612 -99.293,
+                          -276.417 -302.926 -64.0277,
+                          -276.417 -290.84 -123.448,
+                          -443.333 -273.888 -123.41,
+                          -276.417 -290.84 -123.448,
+                          -276.417 -302.926 -64.0277,
+                          -110 -286.505 -169.683,
+                          -110 -315.612 -99.293,
+                          -276.417 -290.84 -123.448,
+                          -443.333 -260.059 -178.671,
+                          -276.417 -290.84 -123.448,
+                          -443.333 -273.888 -123.41,
+                          -110 -327.697 -24.0876,
+                          -276.417 -305.896 -3.14267,
+                          -276.417 -302.926 -64.0277,
+                          -443.333 -281.943 -66.0191,
+                          -276.417 -302.926 -64.0277,
+                          -276.417 -305.896 -3.14267,
+                          -110 -315.612 -99.293,
+                          -110 -327.697 -24.0876,
+                          -276.417 -302.926 -64.0277,
+                          -443.333 -273.888 -123.41,
+                          -276.417 -302.926 -64.0277,
+                          -443.333 -281.943 -66.0191,
+                          -110 -322.111 51.8775,
+                          -276.417 -299.641 57.4228,
+                          -276.417 -305.896 -3.14267,
+                          -443.333 -283.924 -7.65217,
+                          -276.417 -305.896 -3.14267,
+                          -276.417 -299.641 57.4228,
+                          -110 -327.697 -24.0876,
+                          -110 -322.111 51.8775,
+                          -276.417 -305.896 -3.14267,
+                          -443.333 -281.943 -66.0191,
+                          -276.417 -305.896 -3.14267,
+                          -443.333 -283.924 -7.65217,
+                          -443.333 -283.924 -7.65217,
+                          -276.417 -299.641 57.4228,
+                          -443.333 -279.754 50.5018,
+                          1.13687e-13 -327.855 -0.34859,
+                          -110 -322.111 51.8775,
+                          -110 -327.697 -24.0876,
+                          1.13687e-13 -314.646 82.6358,
+                          -110 -322.111 51.8775,
+                          1.13687e-13 -327.855 -0.34859,
+                          1.13687e-13 -319.552 -83.9498,
+                          -110 -327.697 -24.0876,
+                          -110 -315.612 -99.293,
+                          1.13687e-13 -327.855 -0.34859,
+                          -110 -327.697 -24.0876,
+                          1.13687e-13 -319.552 -83.9498,
+                          1.13687e-13 -290.283 -162.705,
+                          -110 -315.612 -99.293,
+                          -110 -286.505 -169.683,
+                          1.13687e-13 -319.552 -83.9498,
+                          -110 -315.612 -99.293,
+                          1.13687e-13 -290.283 -162.705,
+                          -443.333 -279.754 50.5018,
+                          -610.25 -259.867 43.5808,
+                          -610.25 -261.951 -12.1617,
+                          -443.333 -283.924 -7.65217,
+                          -610.25 -261.951 -12.1617,
+                          -610.25 -260.961 -68.0106,
+                          -443.333 -283.924 -7.65217,
+                          -443.333 -279.754 50.5018,
+                          -610.25 -261.951 -12.1617,
+                          -443.333 -281.943 -66.0191,
+                          -610.25 -260.961 -68.0106,
+                          -610.25 -256.935 -123.372,
+                          -443.333 -281.943 -66.0191,
+                          -443.333 -283.924 -7.65217,
+                          -610.25 -260.961 -68.0106,
+                          -443.333 -273.888 -123.41,
+                          -610.25 -256.935 -123.372,
+                          -610.25 -250.024 -177.669,
+                          -443.333 -273.888 -123.41,
+                          -443.333 -281.943 -66.0191,
+                          -610.25 -256.935 -123.372,
+                          -443.333 -260.059 -178.671,
+                          -443.333 -273.888 -123.41,
+                          -610.25 -250.024 -177.669,
+                          0 -183.175 -282.082,
+                          0 183.175 -282.082,
+                          0 241.948 -231.461,
+                          0 -241.948 -231.461,
+                          0 -183.175 -282.082,
+                          0 241.948 -231.461,
+                          -1.13687e-13 290.282 -162.707,
+                          0 -241.948 -231.461,
+                          0 241.948 -231.461,
+                          0 -114.189 -317.481,
+                          0 114.189 -317.481,
+                          0 183.175 -282.082,
+                          0 -183.175 -282.082,
+                          0 -114.189 -317.481,
+                          0 183.175 -282.082,
+                          0 -38.7641 -335.699,
+                          0 38.7641 -335.699,
+                          0 114.189 -317.481,
+                          0 -114.189 -317.481,
+                          0 -38.7641 -335.699,
+                          0 114.189 -317.481,
+                          -1.13687e-13 290.282 -162.707,
+                          1.13687e-13 -290.283 -162.705,
+                          0 -241.948 -231.461,
+                          -1.13687e-13 319.551 -83.9536,
+                          1.13687e-13 -319.552 -83.9498,
+                          1.13687e-13 -290.283 -162.705,
+                          -1.13687e-13 290.282 -162.707,
+                          -1.13687e-13 319.551 -83.9536,
+                          1.13687e-13 -290.283 -162.705,
+                          -1.13687e-13 327.855 -0.354372,
+                          1.13687e-13 -327.855 -0.34859,
+                          1.13687e-13 -319.552 -83.9498,
+                          -1.13687e-13 319.551 -83.9536,
+                          -1.13687e-13 327.855 -0.354372,
+                          1.13687e-13 -319.552 -83.9498,
+                          -1.13687e-13 314.648 82.6285,
+                          1.13687e-13 -314.646 82.6358,
+                          1.13687e-13 -327.855 -0.34859,
+                          -1.13687e-13 327.855 -0.354372,
+                          -1.13687e-13 314.648 82.6285,
+                          1.13687e-13 -327.855 -0.34859,
+                          -1.13687e-13 280.776 159.554,
+                          1.13687e-13 -280.771 159.562,
+                          1.13687e-13 -314.646 82.6358,
+                          -1.13687e-13 314.648 82.6285,
+                          -1.13687e-13 280.776 159.554,
+                          1.13687e-13 -314.646 82.6358,
+                          0 228.482 225.326,
+                          0 -228.476 225.332,
+                          1.13687e-13 -280.771 159.562,
+                          -1.13687e-13 280.776 159.554,
+                          0 228.482 225.326,
+                          1.13687e-13 -280.771 159.562,
+                          0 161.209 275.646,
+                          0 -161.201 275.65,
+                          0 -228.476 225.332,
+                          0 228.482 225.326,
+                          0 161.209 275.646,
+                          0 -228.476 225.332,
+                          0 83.355 307.23,
+                          0 -83.3467 307.232,
+                          0 -161.201 275.65,
+                          0 161.209 275.646,
+                          0 83.355 307.23,
+                          0 -161.201 275.65,
+                          0 83.355 307.23,
+                          0 0.00431946 318,
+                          0 -83.3467 307.232 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          -1 2.22045e-16 6.12303e-17,
+                          -1 2.22045e-16 6.12303e-17,
+                          -0.707107 2.00306e-16 0.707107,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          -0.707107 2.00306e-16 0.707107,
+                          -0.707107 2.00306e-16 0.707107,
+                          0 6.12303e-17 1,
+                          -0.707107 2.00306e-16 0.707107,
+                          -1 2.22045e-16 6.12303e-17,
+                          -0.707107 2.00306e-16 0.707107,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          -0.707107 2.00306e-16 0.707107,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0.707107 -1.13713e-16 0.707107,
+                          0.707107 -1.13713e-16 0.707107,
+                          0.707107 -1.13713e-16 0.707107,
+                          1 -2.22045e-16 6.12303e-17,
+                          0 6.12303e-17 1,
+                          0.707107 -1.13713e-16 0.707107,
+                          0.707107 -1.13713e-16 0.707107,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          0.707107 -1.13713e-16 0.707107,
+                          1 -2.22045e-16 6.12303e-17,
+                          1 -2.22045e-16 6.12303e-17,
+                          1 -2.22045e-16 6.12303e-17,
+                          1 -2.22045e-16 6.12303e-17,
+                          0.707107 -2.00306e-16 -0.707107,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          0.707107 -2.00306e-16 -0.707107,
+                          0.707107 -2.00306e-16 -0.707107,
+                          1.22461e-16 -6.12303e-17 -1,
+                          1 -2.22045e-16 6.12303e-17,
+                          0.707107 -2.00306e-16 -0.707107,
+                          0.707107 -2.00306e-16 -0.707107,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          0.707107 -2.00306e-16 -0.707107,
+                          1.22461e-16 -6.12303e-17 -1,
+                          1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -0.707107 1.13713e-16 -0.707107,
+                          -0.707107 1.13713e-16 -0.707107,
+                          -0.707107 1.13713e-16 -0.707107,
+                          -1 2.22045e-16 6.12303e-17,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -0.707107 1.13713e-16 -0.707107,
+                          -0.707107 1.13713e-16 -0.707107,
+                          -0.707107 1.13713e-16 -0.707107,
+                          -1 2.22045e-16 6.12303e-17,
+                          -1 2.22045e-16 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -805.828 -159 -186.828,
+                          -777 -159 -200,
+                          -817 -159 -200,
+                          -817 -181 -200,
+                          -817 -159 -200,
+                          -777 -159 -200,
+                          -807 -159 -184,
+                          -817 -159 -200,
+                          -817 -159 -24,
+                          -817 -181 -24,
+                          -817 -159 -24,
+                          -817 -159 -200,
+                          -807 -159 -184,
+                          -805.828 -159 -186.828,
+                          -817 -159 -200,
+                          -817 -181 -24,
+                          -817 -159 -200,
+                          -817 -181 -200,
+                          -787 -159 -40,
+                          -777 -159 -24,
+                          -777 -159 -200,
+                          -777 -181 -200,
+                          -777 -159 -200,
+                          -777 -159 -24,
+                          -788.172 -159 -186.828,
+                          -787 -159 -184,
+                          -777 -159 -200,
+                          -787 -159 -40,
+                          -777 -159 -200,
+                          -787 -159 -184,
+                          -791 -159 -188,
+                          -788.172 -159 -186.828,
+                          -777 -159 -200,
+                          -803 -159 -188,
+                          -791 -159 -188,
+                          -777 -159 -200,
+                          -805.828 -159 -186.828,
+                          -803 -159 -188,
+                          -777 -159 -200,
+                          -777 -181 -200,
+                          -817 -181 -200,
+                          -777 -159 -200,
+                          -788.172 -159 -37.1722,
+                          -817 -159 -24,
+                          -777 -159 -24,
+                          -777 -181 -24,
+                          -777 -159 -24,
+                          -817 -159 -24,
+                          -787 -159 -40,
+                          -788.172 -159 -37.1722,
+                          -777 -159 -24,
+                          -777 -181 -24,
+                          -777 -181 -200,
+                          -777 -159 -24,
+                          -807 -159 -40,
+                          -807 -159 -184,
+                          -817 -159 -24,
+                          -805.828 -159 -37.1722,
+                          -807 -159 -40,
+                          -817 -159 -24,
+                          -803 -159 -36,
+                          -805.828 -159 -37.1722,
+                          -817 -159 -24,
+                          -791 -159 -36,
+                          -803 -159 -36,
+                          -817 -159 -24,
+                          -788.172 -159 -37.1722,
+                          -791 -159 -36,
+                          -817 -159 -24,
+                          -817 -181 -24,
+                          -777 -181 -24,
+                          -817 -159 -24,
+                          -787 -181 -184,
+                          -787 -159 -184,
+                          -788.172 -159 -186.828,
+                          -787 -181 -40,
+                          -787 -159 -40,
+                          -787 -159 -184,
+                          -787 -181 -40,
+                          -787 -159 -184,
+                          -787 -181 -184,
+                          -788.172 -181 -186.828,
+                          -788.172 -159 -186.828,
+                          -791 -159 -188,
+                          -788.172 -181 -186.828,
+                          -787 -181 -184,
+                          -788.172 -159 -186.828,
+                          -803 -181 -188,
+                          -791 -159 -188,
+                          -803 -159 -188,
+                          -791 -181 -188,
+                          -791 -159 -188,
+                          -803 -181 -188,
+                          -788.172 -181 -186.828,
+                          -791 -159 -188,
+                          -791 -181 -188,
+                          -803 -181 -188,
+                          -803 -159 -188,
+                          -805.828 -159 -186.828,
+                          -805.828 -181 -186.828,
+                          -805.828 -159 -186.828,
+                          -807 -159 -184,
+                          -803 -181 -188,
+                          -805.828 -159 -186.828,
+                          -805.828 -181 -186.828,
+                          -807 -181 -184,
+                          -807 -159 -184,
+                          -807 -159 -40,
+                          -805.828 -181 -186.828,
+                          -807 -159 -184,
+                          -807 -181 -184,
+                          -807 -181 -40,
+                          -807 -159 -40,
+                          -805.828 -159 -37.1722,
+                          -807 -181 -184,
+                          -807 -159 -40,
+                          -807 -181 -40,
+                          -805.828 -181 -37.1722,
+                          -805.828 -159 -37.1722,
+                          -803 -159 -36,
+                          -807 -181 -40,
+                          -805.828 -159 -37.1722,
+                          -805.828 -181 -37.1722,
+                          -791 -181 -36,
+                          -803 -159 -36,
+                          -791 -159 -36,
+                          -803 -181 -36,
+                          -803 -159 -36,
+                          -791 -181 -36,
+                          -805.828 -181 -37.1722,
+                          -803 -159 -36,
+                          -803 -181 -36,
+                          -791 -181 -36,
+                          -791 -159 -36,
+                          -788.172 -159 -37.1722,
+                          -788.172 -181 -37.1722,
+                          -788.172 -159 -37.1722,
+                          -787 -159 -40,
+                          -791 -181 -36,
+                          -788.172 -159 -37.1722,
+                          -788.172 -181 -37.1722,
+                          -788.172 -181 -37.1722,
+                          -787 -159 -40,
+                          -787 -181 -40,
+                          -788.172 -181 -186.828,
+                          -817 -181 -200,
+                          -777 -181 -200,
+                          -807 -181 -40,
+                          -817 -181 -24,
+                          -817 -181 -200,
+                          -807 -181 -184,
+                          -807 -181 -40,
+                          -817 -181 -200,
+                          -805.828 -181 -186.828,
+                          -807 -181 -184,
+                          -817 -181 -200,
+                          -803 -181 -188,
+                          -805.828 -181 -186.828,
+                          -817 -181 -200,
+                          -791 -181 -188,
+                          -803 -181 -188,
+                          -817 -181 -200,
+                          -788.172 -181 -186.828,
+                          -791 -181 -188,
+                          -817 -181 -200,
+                          -787 -181 -184,
+                          -777 -181 -200,
+                          -777 -181 -24,
+                          -788.172 -181 -186.828,
+                          -777 -181 -200,
+                          -787 -181 -184,
+                          -805.828 -181 -37.1722,
+                          -777 -181 -24,
+                          -817 -181 -24,
+                          -787 -181 -40,
+                          -787 -181 -184,
+                          -777 -181 -24,
+                          -788.172 -181 -37.1722,
+                          -787 -181 -40,
+                          -777 -181 -24,
+                          -791 -181 -36,
+                          -788.172 -181 -37.1722,
+                          -777 -181 -24,
+                          -803 -181 -36,
+                          -791 -181 -36,
+                          -777 -181 -24,
+                          -805.828 -181 -37.1722,
+                          -803 -181 -36,
+                          -777 -181 -24,
+                          -807 -181 -40,
+                          -805.828 -181 -37.1722,
+                          -817 -181 -24 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -817 181 -200,
+                          -817 -181 -24,
+                          -817 -181 -200,
+                          -823 -181 -200,
+                          -817 -181 -200,
+                          -817 -181 -24,
+                          -823 181 -200,
+                          -817 181 -200,
+                          -817 -181 -200,
+                          -823 181 -200,
+                          -817 -181 -200,
+                          -823 -181 -200,
+                          -817 181 -200,
+                          -817 181 -24,
+                          -817 -181 -24,
+                          -823 -181 -24,
+                          -817 -181 -24,
+                          -817 181 -24,
+                          -823 -181 -200,
+                          -817 -181 -24,
+                          -823 -181 -24,
+                          -823 181 -24,
+                          -817 181 -24,
+                          -817 181 -200,
+                          -823 -181 -24,
+                          -817 181 -24,
+                          -823 181 -24,
+                          -823 181 -200,
+                          -823 181 -24,
+                          -817 181 -200,
+                          -823 -181 -200,
+                          -823 -181 -24,
+                          -823 181 -24,
+                          -823 181 -200,
+                          -823 -181 -200,
+                          -823 181 -24 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -0.587785 8.09782e-17 -0.809017,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          -0.587785 8.09782e-17 -0.809017,
+                          -0.587785 8.09782e-17 -0.809017,
+                          -0.951057 1.92256e-16 -0.309017,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -0.587785 8.09782e-17 -0.809017,
+                          -0.587785 8.09782e-17 -0.809017,
+                          -0.951057 1.92256e-16 -0.309017,
+                          -0.951057 1.92256e-16 -0.309017,
+                          -0.951057 2.30098e-16 0.309017,
+                          -0.587785 8.09782e-17 -0.809017,
+                          -0.951057 1.92256e-16 -0.309017,
+                          -0.951057 1.92256e-16 -0.309017,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          -0.951057 2.30098e-16 0.309017,
+                          -0.951057 2.30098e-16 0.309017,
+                          -0.587785 1.80051e-16 0.809017,
+                          -0.951057 1.92256e-16 -0.309017,
+                          -0.951057 2.30098e-16 0.309017,
+                          -0.951057 2.30098e-16 0.309017,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          -0.587785 1.80051e-16 0.809017,
+                          -0.587785 1.80051e-16 0.809017,
+                          0 6.12303e-17 1,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          -0.951057 2.30098e-16 0.309017,
+                          -0.587785 1.80051e-16 0.809017,
+                          -0.587785 1.80051e-16 0.809017,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          -0.587785 1.80051e-16 0.809017,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          -1.01064e-15 6.12303e-17 1,
+                          -1.22461e-16 6.12303e-17 1,
+                          -0.707107 2.00306e-16 0.707107,
+                          0.707107 -1.13713e-16 0.707107,
+                          0.707107 -1.13713e-16 0.707107,
+                          -3.35954e-16 6.12303e-17 1,
+                          0.707107 -1.13713e-16 0.707107,
+                          -3.35954e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          -0.707107 2.00306e-16 0.707107,
+                          -0.707107 2.00306e-16 0.707107,
+                          -1 2.22045e-16 -6.12303e-17,
+                          -0.707107 2.00306e-16 0.707107,
+                          -1.01064e-15 6.12303e-17 1,
+                          -0.707107 2.00306e-16 0.707107,
+                          -1 2.22045e-16 -6.12303e-17,
+                          -1 2.22045e-16 -6.12303e-17,
+                          -0.707107 1.13713e-16 -0.707107,
+                          -0.707107 2.00306e-16 0.707107,
+                          -1 2.22045e-16 -6.12303e-17,
+                          -1 2.22045e-16 -6.12303e-17,
+                          -0.707107 1.13713e-16 -0.707107,
+                          -0.707107 1.13713e-16 -0.707107,
+                          0 -6.12303e-17 -1,
+                          -1 2.22045e-16 -6.12303e-17,
+                          -0.707107 1.13713e-16 -0.707107,
+                          -0.707107 1.13713e-16 -0.707107,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0.707107 -2.00306e-16 -0.707107,
+                          -0.707107 1.13713e-16 -0.707107,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          0.707107 -2.00306e-16 -0.707107,
+                          0.707107 -2.00306e-16 -0.707107,
+                          1 -2.22045e-16 1.60814e-16,
+                          0 -6.12303e-17 -1,
+                          0.707107 -2.00306e-16 -0.707107,
+                          0.707107 -2.00306e-16 -0.707107,
+                          1 -2.22045e-16 1.60814e-16,
+                          1 -2.22045e-16 1.60814e-16,
+                          0.707107 -1.13713e-16 0.707107,
+                          0.707107 -2.00306e-16 -0.707107,
+                          1 -2.22045e-16 1.60814e-16,
+                          1 -2.22045e-16 1.60814e-16,
+                          1 -2.22045e-16 1.60814e-16,
+                          0.707107 -1.13713e-16 0.707107,
+                          0.707107 -1.13713e-16 0.707107,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          0.707107 -1.13713e-16 0.707107,
+                          -0.707107 2.00306e-16 0.707107,
+                          -0.707107 2.00306e-16 0.707107,
+                          -1.22461e-16 6.12303e-17 1,
+                          -0.707107 2.00306e-16 0.707107,
+                          -1.22461e-16 6.12303e-17 1,
+                          -1.22461e-16 6.12303e-17 1,
+                          0.707107 -1.13713e-16 0.707107,
+                          0.707107 -1.13713e-16 0.707107,
+                          1 -2.22045e-16 3.82859e-16,
+                          0.707107 -1.13713e-16 0.707107,
+                          1.22461e-16 6.12303e-17 1,
+                          0.707107 -1.13713e-16 0.707107,
+                          1 -2.22045e-16 -6.12303e-17,
+                          1 -2.22045e-16 3.82859e-16,
+                          0.707107 -2.00306e-16 -0.707107,
+                          0.707107 -1.13713e-16 0.707107,
+                          1 -2.22045e-16 3.82859e-16,
+                          1 -2.22045e-16 -6.12303e-17,
+                          0.707107 -2.00306e-16 -0.707107,
+                          0.707107 -2.00306e-16 -0.707107,
+                          0 -6.12303e-17 -1,
+                          1 -2.22045e-16 -6.12303e-17,
+                          0.707107 -2.00306e-16 -0.707107,
+                          0.707107 -2.00306e-16 -0.707107,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.707107 1.13713e-16 -0.707107,
+                          0.707107 -2.00306e-16 -0.707107,
+                          0 -6.12303e-17 -1,
+                          0 -6.12303e-17 -1,
+                          -0.707107 1.13713e-16 -0.707107,
+                          -0.707107 1.13713e-16 -0.707107,
+                          -1 2.22045e-16 -6.12303e-17,
+                          0 -6.12303e-17 -1,
+                          -0.707107 1.13713e-16 -0.707107,
+                          -0.707107 1.13713e-16 -0.707107,
+                          -1 2.22045e-16 -6.12303e-17,
+                          -1 2.22045e-16 -6.12303e-17,
+                          -0.707107 2.00306e-16 0.707107,
+                          -0.707107 1.13713e-16 -0.707107,
+                          -1 2.22045e-16 -6.12303e-17,
+                          -1 2.22045e-16 -6.12303e-17,
+                          -1 2.22045e-16 -6.12303e-17,
+                          -0.707107 2.00306e-16 0.707107,
+                          -0.707107 2.00306e-16 0.707107,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -868.081 -181 -135.079,
+                          -823 -181 -200,
+                          -823 -181 -114,
+                          -823 -159 -114,
+                          -823 -181 -114,
+                          -823 -181 -200,
+                          -868.081 -181 -135.079,
+                          -823 -181 -114,
+                          -890 -181 -114,
+                          -890 -159 -114,
+                          -890 -181 -114,
+                          -823 -181 -114,
+                          -890 -159 -114,
+                          -823 -181 -114,
+                          -823 -159 -114,
+                          -890 -181 -188,
+                          -890 -181 -200,
+                          -823 -181 -200,
+                          -823 -159 -200,
+                          -823 -181 -200,
+                          -890 -181 -200,
+                          -868.081 -181 -178.921,
+                          -890 -181 -188,
+                          -823 -181 -200,
+                          -859 -181 -157,
+                          -868.081 -181 -178.921,
+                          -823 -181 -200,
+                          -868.081 -181 -135.079,
+                          -859 -181 -157,
+                          -823 -181 -200,
+                          -823 -159 -200,
+                          -823 -159 -114,
+                          -823 -181 -200,
+                          -911.919 -181 -178.921,
+                          -915.273 -181 -191.789,
+                          -890 -181 -200,
+                          -890 -159 -200,
+                          -890 -181 -200,
+                          -915.273 -181 -191.789,
+                          -911.919 -181 -178.921,
+                          -890 -181 -200,
+                          -890 -181 -188,
+                          -823 -159 -200,
+                          -890 -181 -200,
+                          -890 -159 -200,
+                          -930.895 -181 -143.711,
+                          -930.895 -181 -170.289,
+                          -915.273 -181 -191.789,
+                          -915.273 -159 -191.789,
+                          -915.273 -181 -191.789,
+                          -930.895 -181 -170.289,
+                          -921 -181 -157,
+                          -930.895 -181 -143.711,
+                          -915.273 -181 -191.789,
+                          -911.919 -181 -178.921,
+                          -921 -181 -157,
+                          -915.273 -181 -191.789,
+                          -890 -159 -200,
+                          -915.273 -181 -191.789,
+                          -915.273 -159 -191.789,
+                          -930.895 -159 -170.289,
+                          -930.895 -181 -170.289,
+                          -930.895 -181 -143.711,
+                          -915.273 -159 -191.789,
+                          -930.895 -181 -170.289,
+                          -930.895 -159 -170.289,
+                          -921 -181 -157,
+                          -915.273 -181 -122.211,
+                          -930.895 -181 -143.711,
+                          -930.895 -159 -143.711,
+                          -930.895 -181 -143.711,
+                          -915.273 -181 -122.211,
+                          -930.895 -159 -170.289,
+                          -930.895 -181 -143.711,
+                          -930.895 -159 -143.711,
+                          -890 -181 -126,
+                          -890 -181 -114,
+                          -915.273 -181 -122.211,
+                          -915.273 -159 -122.211,
+                          -915.273 -181 -122.211,
+                          -890 -181 -114,
+                          -911.919 -181 -135.079,
+                          -890 -181 -126,
+                          -915.273 -181 -122.211,
+                          -921 -181 -157,
+                          -911.919 -181 -135.079,
+                          -915.273 -181 -122.211,
+                          -930.895 -159 -143.711,
+                          -915.273 -181 -122.211,
+                          -915.273 -159 -122.211,
+                          -890 -181 -126,
+                          -868.081 -181 -135.079,
+                          -890 -181 -114,
+                          -915.273 -159 -122.211,
+                          -890 -181 -114,
+                          -890 -159 -114,
+                          -890 -178 -188,
+                          -890 -181 -188,
+                          -868.081 -181 -178.921,
+                          -911.919 -178 -178.921,
+                          -911.919 -181 -178.921,
+                          -890 -181 -188,
+                          -911.919 -178 -178.921,
+                          -890 -181 -188,
+                          -890 -178 -188,
+                          -868.081 -178 -178.921,
+                          -868.081 -181 -178.921,
+                          -859 -181 -157,
+                          -868.081 -178 -178.921,
+                          -890 -178 -188,
+                          -868.081 -181 -178.921,
+                          -859 -178 -157,
+                          -859 -181 -157,
+                          -868.081 -181 -135.079,
+                          -868.081 -178 -178.921,
+                          -859 -181 -157,
+                          -859 -178 -157,
+                          -868.081 -178 -135.079,
+                          -868.081 -181 -135.079,
+                          -890 -181 -126,
+                          -859 -178 -157,
+                          -868.081 -181 -135.079,
+                          -868.081 -178 -135.079,
+                          -890 -178 -126,
+                          -890 -181 -126,
+                          -911.919 -181 -135.079,
+                          -868.081 -178 -135.079,
+                          -890 -181 -126,
+                          -890 -178 -126,
+                          -911.919 -178 -135.079,
+                          -911.919 -181 -135.079,
+                          -921 -181 -157,
+                          -890 -178 -126,
+                          -911.919 -181 -135.079,
+                          -911.919 -178 -135.079,
+                          -921 -178 -157,
+                          -921 -181 -157,
+                          -911.919 -181 -178.921,
+                          -911.919 -178 -135.079,
+                          -921 -181 -157,
+                          -921 -178 -157,
+                          -921 -178 -157,
+                          -911.919 -181 -178.921,
+                          -911.919 -178 -178.921,
+                          -890 -159 -123,
+                          -890 -159 -114,
+                          -823 -159 -114,
+                          -865.96 -159 -181.043,
+                          -823 -159 -114,
+                          -823 -159 -200,
+                          -865.96 -159 -132.957,
+                          -890 -159 -123,
+                          -823 -159 -114,
+                          -856 -159 -157,
+                          -865.96 -159 -132.957,
+                          -823 -159 -114,
+                          -865.96 -159 -181.043,
+                          -856 -159 -157,
+                          -823 -159 -114,
+                          -914.04 -159 -132.957,
+                          -915.273 -159 -122.211,
+                          -890 -159 -114,
+                          -890 -159 -123,
+                          -914.04 -159 -132.957,
+                          -890 -159 -114,
+                          -930.895 -159 -170.289,
+                          -930.895 -159 -143.711,
+                          -915.273 -159 -122.211,
+                          -924 -159 -157,
+                          -930.895 -159 -170.289,
+                          -915.273 -159 -122.211,
+                          -914.04 -159 -132.957,
+                          -924 -159 -157,
+                          -915.273 -159 -122.211,
+                          -924 -159 -157,
+                          -915.273 -159 -191.789,
+                          -930.895 -159 -170.289,
+                          -890 -159 -191,
+                          -890 -159 -200,
+                          -915.273 -159 -191.789,
+                          -914.04 -159 -181.043,
+                          -890 -159 -191,
+                          -915.273 -159 -191.789,
+                          -924 -159 -157,
+                          -914.04 -159 -181.043,
+                          -915.273 -159 -191.789,
+                          -865.96 -159 -181.043,
+                          -823 -159 -200,
+                          -890 -159 -200,
+                          -865.96 -159 -181.043,
+                          -890 -159 -200,
+                          -890 -159 -191,
+                          -890 -178 -191,
+                          -890 -159 -191,
+                          -914.04 -159 -181.043,
+                          -865.958 -178 -181.042,
+                          -865.96 -159 -181.043,
+                          -890 -159 -191,
+                          -865.958 -178 -181.042,
+                          -890 -159 -191,
+                          -890 -178 -191,
+                          -914.042 -178 -181.042,
+                          -914.04 -159 -181.043,
+                          -924 -159 -157,
+                          -914.042 -178 -181.042,
+                          -890 -178 -191,
+                          -914.04 -159 -181.043,
+                          -924 -178 -157,
+                          -924 -159 -157,
+                          -914.04 -159 -132.957,
+                          -914.042 -178 -181.042,
+                          -924 -159 -157,
+                          -924 -178 -157,
+                          -914.042 -178 -132.958,
+                          -914.04 -159 -132.957,
+                          -890 -159 -123,
+                          -924 -178 -157,
+                          -914.04 -159 -132.957,
+                          -914.042 -178 -132.958,
+                          -890 -178 -123,
+                          -890 -159 -123,
+                          -865.96 -159 -132.957,
+                          -914.042 -178 -132.958,
+                          -890 -159 -123,
+                          -890 -178 -123,
+                          -865.958 -178 -132.958,
+                          -865.96 -159 -132.957,
+                          -856 -159 -157,
+                          -890 -178 -123,
+                          -865.96 -159 -132.957,
+                          -865.958 -178 -132.958,
+                          -856 -178 -157,
+                          -856 -159 -157,
+                          -865.96 -159 -181.043,
+                          -865.958 -178 -132.958,
+                          -856 -159 -157,
+                          -856 -178 -157,
+                          -856 -178 -157,
+                          -865.96 -159 -181.043,
+                          -865.958 -178 -181.042,
+                          -868.081 -178 -178.921,
+                          -865.958 -178 -181.042,
+                          -890 -178 -191,
+                          -890 -178 -188,
+                          -890 -178 -191,
+                          -914.042 -178 -181.042,
+                          -868.081 -178 -178.921,
+                          -890 -178 -191,
+                          -890 -178 -188,
+                          -859 -178 -157,
+                          -856 -178 -157,
+                          -865.958 -178 -181.042,
+                          -868.081 -178 -178.921,
+                          -859 -178 -157,
+                          -865.958 -178 -181.042,
+                          -859 -178 -157,
+                          -865.958 -178 -132.958,
+                          -856 -178 -157,
+                          -890 -178 -126,
+                          -890 -178 -123,
+                          -865.958 -178 -132.958,
+                          -868.081 -178 -135.079,
+                          -890 -178 -126,
+                          -865.958 -178 -132.958,
+                          -859 -178 -157,
+                          -868.081 -178 -135.079,
+                          -865.958 -178 -132.958,
+                          -911.919 -178 -135.079,
+                          -914.042 -178 -132.958,
+                          -890 -178 -123,
+                          -890 -178 -126,
+                          -911.919 -178 -135.079,
+                          -890 -178 -123,
+                          -921 -178 -157,
+                          -924 -178 -157,
+                          -914.042 -178 -132.958,
+                          -911.919 -178 -135.079,
+                          -921 -178 -157,
+                          -914.042 -178 -132.958,
+                          -921 -178 -157,
+                          -914.042 -178 -181.042,
+                          -924 -178 -157,
+                          -911.919 -178 -178.921,
+                          -890 -178 -188,
+                          -914.042 -178 -181.042,
+                          -921 -178 -157,
+                          -911.919 -178 -178.921,
+                          -914.042 -178 -181.042 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          -0.587785 1.80051e-16 0.809017,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          -0.587785 1.80051e-16 0.809017,
+                          -0.587785 1.80051e-16 0.809017,
+                          -0.951057 2.30098e-16 0.309017,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          1.22461e-16 6.12303e-17 1,
+                          -0.587785 1.80051e-16 0.809017,
+                          -0.587785 1.80051e-16 0.809017,
+                          -0.951057 2.30098e-16 0.309017,
+                          -0.951057 2.30098e-16 0.309017,
+                          -0.951057 1.92256e-16 -0.309017,
+                          -0.587785 1.80051e-16 0.809017,
+                          -0.951057 2.30098e-16 0.309017,
+                          -0.951057 2.30098e-16 0.309017,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          -0.951057 1.92256e-16 -0.309017,
+                          -0.951057 1.92256e-16 -0.309017,
+                          -0.587785 8.09782e-17 -0.809017,
+                          -0.951057 2.30098e-16 0.309017,
+                          -0.951057 1.92256e-16 -0.309017,
+                          -0.951057 1.92256e-16 -0.309017,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          -0.587785 8.09782e-17 -0.809017,
+                          -0.587785 8.09782e-17 -0.809017,
+                          -2.44921e-16 -6.12303e-17 -1,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          -0.951057 1.92256e-16 -0.309017,
+                          -0.587785 8.09782e-17 -0.809017,
+                          -0.587785 8.09782e-17 -0.809017,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          -0.587785 8.09782e-17 -0.809017,
+                          -2.44921e-16 -6.12303e-17 -1,
+                          -2.44921e-16 -6.12303e-17 -1,
+                          -3.67382e-16 -6.12303e-17 -1,
+                          -3.67382e-16 -6.12303e-17 -1,
+                          -0.707107 1.13713e-16 -0.707107,
+                          0.707107 -2.00306e-16 -0.707107,
+                          0.707107 -2.00306e-16 -0.707107,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          0.707107 -2.00306e-16 -0.707107,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -0.707107 1.13713e-16 -0.707107,
+                          -0.707107 1.13713e-16 -0.707107,
+                          -1 2.22045e-16 3.06152e-16,
+                          -0.707107 1.13713e-16 -0.707107,
+                          -3.67382e-16 -6.12303e-17 -1,
+                          -0.707107 1.13713e-16 -0.707107,
+                          -1 2.22045e-16 3.06152e-16,
+                          -1 2.22045e-16 3.06152e-16,
+                          -0.707107 2.00306e-16 0.707107,
+                          -0.707107 1.13713e-16 -0.707107,
+                          -1 2.22045e-16 3.06152e-16,
+                          -1 2.22045e-16 3.06152e-16,
+                          -0.707107 2.00306e-16 0.707107,
+                          -0.707107 2.00306e-16 0.707107,
+                          -1.99168e-16 6.12303e-17 1,
+                          -1 2.22045e-16 3.06152e-16,
+                          -0.707107 2.00306e-16 0.707107,
+                          -0.707107 2.00306e-16 0.707107,
+                          2.44921e-16 6.12303e-17 1,
+                          -1.99168e-16 6.12303e-17 1,
+                          0.707107 -1.13713e-16 0.707107,
+                          -0.707107 2.00306e-16 0.707107,
+                          -1.99168e-16 6.12303e-17 1,
+                          2.44921e-16 6.12303e-17 1,
+                          0.707107 -1.13713e-16 0.707107,
+                          0.707107 -1.13713e-16 0.707107,
+                          1 -2.22045e-16 -1.83691e-16,
+                          2.44921e-16 6.12303e-17 1,
+                          0.707107 -1.13713e-16 0.707107,
+                          0.707107 -1.13713e-16 0.707107,
+                          1 -2.22045e-16 -1.83691e-16,
+                          1 -2.22045e-16 -1.83691e-16,
+                          0.707107 -2.00306e-16 -0.707107,
+                          0.707107 -1.13713e-16 0.707107,
+                          1 -2.22045e-16 -1.83691e-16,
+                          1 -2.22045e-16 -1.83691e-16,
+                          1 -2.22045e-16 -1.83691e-16,
+                          0.707107 -2.00306e-16 -0.707107,
+                          0.707107 -2.00306e-16 -0.707107,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -865.96 181 -181.043,
+                          -823 181 -114,
+                          -823 181 -200,
+                          -823 159 -200,
+                          -823 181 -200,
+                          -823 181 -114,
+                          -865.96 181 -181.043,
+                          -823 181 -200,
+                          -890 181 -200,
+                          -890 159 -200,
+                          -890 181 -200,
+                          -823 181 -200,
+                          -890 159 -200,
+                          -823 181 -200,
+                          -823 159 -200,
+                          -890 181 -123,
+                          -890 181 -114,
+                          -823 181 -114,
+                          -823 159 -114,
+                          -823 181 -114,
+                          -890 181 -114,
+                          -865.96 181 -132.957,
+                          -890 181 -123,
+                          -823 181 -114,
+                          -856 181 -157,
+                          -865.96 181 -132.957,
+                          -823 181 -114,
+                          -865.96 181 -181.043,
+                          -856 181 -157,
+                          -823 181 -114,
+                          -823 159 -114,
+                          -823 159 -200,
+                          -823 181 -114,
+                          -914.04 181 -132.957,
+                          -915.273 181 -122.211,
+                          -890 181 -114,
+                          -890 159 -114,
+                          -890 181 -114,
+                          -915.273 181 -122.211,
+                          -914.04 181 -132.957,
+                          -890 181 -114,
+                          -890 181 -123,
+                          -823 159 -114,
+                          -890 181 -114,
+                          -890 159 -114,
+                          -930.895 181 -170.289,
+                          -930.895 181 -143.711,
+                          -915.273 181 -122.211,
+                          -915.273 159 -122.211,
+                          -915.273 181 -122.211,
+                          -930.895 181 -143.711,
+                          -924 181 -157,
+                          -930.895 181 -170.289,
+                          -915.273 181 -122.211,
+                          -914.04 181 -132.957,
+                          -924 181 -157,
+                          -915.273 181 -122.211,
+                          -890 159 -114,
+                          -915.273 181 -122.211,
+                          -915.273 159 -122.211,
+                          -930.895 159 -143.711,
+                          -930.895 181 -143.711,
+                          -930.895 181 -170.289,
+                          -915.273 159 -122.211,
+                          -930.895 181 -143.711,
+                          -930.895 159 -143.711,
+                          -924 181 -157,
+                          -915.273 181 -191.789,
+                          -930.895 181 -170.289,
+                          -930.895 159 -170.289,
+                          -930.895 181 -170.289,
+                          -915.273 181 -191.789,
+                          -930.895 159 -143.711,
+                          -930.895 181 -170.289,
+                          -930.895 159 -170.289,
+                          -890 181 -191,
+                          -890 181 -200,
+                          -915.273 181 -191.789,
+                          -915.273 159 -191.789,
+                          -915.273 181 -191.789,
+                          -890 181 -200,
+                          -914.04 181 -181.043,
+                          -890 181 -191,
+                          -915.273 181 -191.789,
+                          -924 181 -157,
+                          -914.04 181 -181.043,
+                          -915.273 181 -191.789,
+                          -930.895 159 -170.289,
+                          -915.273 181 -191.789,
+                          -915.273 159 -191.789,
+                          -890 181 -191,
+                          -865.96 181 -181.043,
+                          -890 181 -200,
+                          -915.273 159 -191.789,
+                          -890 181 -200,
+                          -890 159 -200,
+                          -890 159 -123,
+                          -890 181 -123,
+                          -865.96 181 -132.957,
+                          -914.04 159 -132.957,
+                          -914.04 181 -132.957,
+                          -890 181 -123,
+                          -914.04 159 -132.957,
+                          -890 181 -123,
+                          -890 159 -123,
+                          -865.96 159 -132.957,
+                          -865.96 181 -132.957,
+                          -856 181 -157,
+                          -865.96 159 -132.957,
+                          -890 159 -123,
+                          -865.96 181 -132.957,
+                          -856 159 -157,
+                          -856 181 -157,
+                          -865.96 181 -181.043,
+                          -865.96 159 -132.957,
+                          -856 181 -157,
+                          -856 159 -157,
+                          -865.96 159 -181.043,
+                          -865.96 181 -181.043,
+                          -890 181 -191,
+                          -856 159 -157,
+                          -865.96 181 -181.043,
+                          -865.96 159 -181.043,
+                          -890 159 -191,
+                          -890 181 -191,
+                          -914.04 181 -181.043,
+                          -865.96 159 -181.043,
+                          -890 181 -191,
+                          -890 159 -191,
+                          -914.04 159 -181.043,
+                          -914.04 181 -181.043,
+                          -924 181 -157,
+                          -890 159 -191,
+                          -914.04 181 -181.043,
+                          -914.04 159 -181.043,
+                          -924 159 -157,
+                          -924 181 -157,
+                          -914.04 181 -132.957,
+                          -914.04 159 -181.043,
+                          -924 181 -157,
+                          -924 159 -157,
+                          -924 159 -157,
+                          -914.04 181 -132.957,
+                          -914.04 159 -132.957,
+                          -890 159 -191,
+                          -890 159 -200,
+                          -823 159 -200,
+                          -865.96 159 -132.957,
+                          -823 159 -200,
+                          -823 159 -114,
+                          -865.96 159 -181.043,
+                          -890 159 -191,
+                          -823 159 -200,
+                          -856 159 -157,
+                          -865.96 159 -181.043,
+                          -823 159 -200,
+                          -865.96 159 -132.957,
+                          -856 159 -157,
+                          -823 159 -200,
+                          -914.04 159 -181.043,
+                          -915.273 159 -191.789,
+                          -890 159 -200,
+                          -890 159 -191,
+                          -914.04 159 -181.043,
+                          -890 159 -200,
+                          -930.895 159 -143.711,
+                          -930.895 159 -170.289,
+                          -915.273 159 -191.789,
+                          -924 159 -157,
+                          -930.895 159 -143.711,
+                          -915.273 159 -191.789,
+                          -914.04 159 -181.043,
+                          -924 159 -157,
+                          -915.273 159 -191.789,
+                          -924 159 -157,
+                          -915.273 159 -122.211,
+                          -930.895 159 -143.711,
+                          -890 159 -123,
+                          -890 159 -114,
+                          -915.273 159 -122.211,
+                          -914.04 159 -132.957,
+                          -890 159 -123,
+                          -915.273 159 -122.211,
+                          -924 159 -157,
+                          -914.04 159 -132.957,
+                          -915.273 159 -122.211,
+                          -865.96 159 -132.957,
+                          -823 159 -114,
+                          -890 159 -114,
+                          -865.96 159 -132.957,
+                          -890 159 -114,
+                          -890 159 -123 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          -0.824332 2.17701e-16 0.566107,
+                          -0.824332 2.17701e-16 0.566107,
+                          -0.824332 2.17701e-16 0.566107,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          -0.824332 2.17701e-16 0.566107,
+                          -0.824332 2.17701e-16 0.566107,
+                          -0.824332 2.17701e-16 0.566107,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          0.824332 -2.17701e-16 -0.566107,
+                          0.824332 -2.17701e-16 -0.566107,
+                          0.824332 -2.17701e-16 -0.566107,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          0.824332 -2.17701e-16 -0.566107,
+                          0.824332 -2.17701e-16 -0.566107,
+                          0.824332 -2.17701e-16 -0.566107,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -827 -181 -110,
+                          -886 -181 -114,
+                          -823 -181 -114,
+                          -823 -159 -114,
+                          -823 -181 -114,
+                          -886 -181 -114,
+                          -827 -181 -110,
+                          -823 -181 -114,
+                          -823 -181 -24,
+                          -823 -159 -24,
+                          -823 -181 -24,
+                          -823 -181 -114,
+                          -823 -159 -24,
+                          -823 -181 -114,
+                          -823 -159 -114,
+                          -880 -181 -107,
+                          -886 -181 -107,
+                          -886 -181 -114,
+                          -886 -159 -107,
+                          -886 -181 -114,
+                          -886 -181 -107,
+                          -877.208 -181 -110,
+                          -880 -181 -107,
+                          -886 -181 -114,
+                          -877.208 -181 -110,
+                          -886 -181 -114,
+                          -827 -181 -110,
+                          -886 -159 -114,
+                          -823 -159 -114,
+                          -886 -181 -114,
+                          -886 -159 -114,
+                          -886 -181 -114,
+                          -886 -159 -107,
+                          -880 -159 -107,
+                          -886 -181 -107,
+                          -880 -181 -107,
+                          -886 -159 -107,
+                          -886 -181 -107,
+                          -880 -159 -107,
+                          -827 -181 -36.8904,
+                          -823 -181 -24,
+                          -880 -181 -107,
+                          -880 -159 -107,
+                          -880 -181 -107,
+                          -823 -181 -24,
+                          -877.208 -181 -110,
+                          -827 -181 -36.8904,
+                          -880 -181 -107,
+                          -827 -181 -36.8904,
+                          -827 -181 -110,
+                          -823 -181 -24,
+                          -880 -159 -107,
+                          -823 -181 -24,
+                          -823 -159 -24,
+                          -827 -159 -110,
+                          -827 -181 -110,
+                          -827 -181 -36.8904,
+                          -877.208 -159 -110,
+                          -877.208 -181 -110,
+                          -827 -181 -110,
+                          -877.208 -159 -110,
+                          -827 -181 -110,
+                          -827 -159 -110,
+                          -827 -159 -36.8904,
+                          -827 -181 -36.8904,
+                          -877.208 -181 -110,
+                          -827 -159 -36.8904,
+                          -827 -159 -110,
+                          -827 -181 -36.8904,
+                          -827 -159 -36.8904,
+                          -877.208 -181 -110,
+                          -877.208 -159 -110,
+                          -827 -159 -36.8904,
+                          -823 -159 -24,
+                          -823 -159 -114,
+                          -877.208 -159 -110,
+                          -823 -159 -114,
+                          -886 -159 -114,
+                          -877.208 -159 -110,
+                          -827 -159 -110,
+                          -823 -159 -114,
+                          -827 -159 -36.8904,
+                          -823 -159 -114,
+                          -827 -159 -110,
+                          -827 -159 -36.8904,
+                          -880 -159 -107,
+                          -823 -159 -24,
+                          -877.208 -159 -110,
+                          -886 -159 -107,
+                          -880 -159 -107,
+                          -827 -159 -36.8904,
+                          -877.208 -159 -110,
+                          -880 -159 -107,
+                          -877.208 -159 -110,
+                          -886 -159 -114,
+                          -886 -159 -107 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          -0.824332 2.17701e-16 0.566107,
+                          -0.824332 2.17701e-16 0.566107,
+                          -0.824332 2.17701e-16 0.566107,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          -0.824332 2.17701e-16 0.566107,
+                          -0.824332 2.17701e-16 0.566107,
+                          -0.824332 2.17701e-16 0.566107,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          0.824332 -2.17701e-16 -0.566107,
+                          0.824332 -2.17701e-16 -0.566107,
+                          0.824332 -2.17701e-16 -0.566107,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          0.824332 -2.17701e-16 -0.566107,
+                          0.824332 -2.17701e-16 -0.566107,
+                          0.824332 -2.17701e-16 -0.566107,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -827 159 -110,
+                          -886 159 -114,
+                          -823 159 -114,
+                          -823 181 -114,
+                          -823 159 -114,
+                          -886 159 -114,
+                          -827 159 -110,
+                          -823 159 -114,
+                          -823 159 -24,
+                          -823 181 -24,
+                          -823 159 -24,
+                          -823 159 -114,
+                          -823 181 -24,
+                          -823 159 -114,
+                          -823 181 -114,
+                          -880 159 -107,
+                          -886 159 -107,
+                          -886 159 -114,
+                          -886 181 -107,
+                          -886 159 -114,
+                          -886 159 -107,
+                          -877.208 159 -110,
+                          -880 159 -107,
+                          -886 159 -114,
+                          -877.208 159 -110,
+                          -886 159 -114,
+                          -827 159 -110,
+                          -886 181 -114,
+                          -823 181 -114,
+                          -886 159 -114,
+                          -886 181 -114,
+                          -886 159 -114,
+                          -886 181 -107,
+                          -880 181 -107,
+                          -886 159 -107,
+                          -880 159 -107,
+                          -886 181 -107,
+                          -886 159 -107,
+                          -880 181 -107,
+                          -827 159 -36.8904,
+                          -823 159 -24,
+                          -880 159 -107,
+                          -880 181 -107,
+                          -880 159 -107,
+                          -823 159 -24,
+                          -877.208 159 -110,
+                          -827 159 -36.8904,
+                          -880 159 -107,
+                          -827 159 -36.8904,
+                          -827 159 -110,
+                          -823 159 -24,
+                          -880 181 -107,
+                          -823 159 -24,
+                          -823 181 -24,
+                          -827 181 -110,
+                          -827 159 -110,
+                          -827 159 -36.8904,
+                          -877.208 181 -110,
+                          -877.208 159 -110,
+                          -827 159 -110,
+                          -877.208 181 -110,
+                          -827 159 -110,
+                          -827 181 -110,
+                          -827 181 -36.8904,
+                          -827 159 -36.8904,
+                          -877.208 159 -110,
+                          -827 181 -36.8904,
+                          -827 181 -110,
+                          -827 159 -36.8904,
+                          -827 181 -36.8904,
+                          -877.208 159 -110,
+                          -877.208 181 -110,
+                          -827 181 -36.8904,
+                          -823 181 -24,
+                          -823 181 -114,
+                          -877.208 181 -110,
+                          -823 181 -114,
+                          -886 181 -114,
+                          -877.208 181 -110,
+                          -827 181 -110,
+                          -823 181 -114,
+                          -827 181 -36.8904,
+                          -823 181 -114,
+                          -827 181 -110,
+                          -827 181 -36.8904,
+                          -880 181 -107,
+                          -823 181 -24,
+                          -877.208 181 -110,
+                          -886 181 -107,
+                          -880 181 -107,
+                          -827 181 -36.8904,
+                          -877.208 181 -110,
+                          -880 181 -107,
+                          -877.208 181 -110,
+                          -886 181 -114,
+                          -886 181 -107 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          0 1 -6.12303e-17,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          -1 2.22045e-16 6.12303e-17,
+                          -1 2.22045e-16 6.12303e-17,
+                          -0.707107 2.00306e-16 0.707107,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          -1 2.22045e-16 1.22461e-16,
+                          -0.707107 2.00306e-16 0.707107,
+                          -0.707107 2.00306e-16 0.707107,
+                          0 6.12303e-17 1,
+                          -0.707107 2.00306e-16 0.707107,
+                          -1 2.22045e-16 6.12303e-17,
+                          -0.707107 2.00306e-16 0.707107,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          1.22461e-16 6.12303e-17 1,
+                          -0.707107 2.00306e-16 0.707107,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0 6.12303e-17 1,
+                          0.707107 -1.13713e-16 0.707107,
+                          0.707107 -1.13713e-16 0.707107,
+                          0.707107 -1.13713e-16 0.707107,
+                          1 -2.22045e-16 6.12303e-17,
+                          0 6.12303e-17 1,
+                          0.707107 -1.13713e-16 0.707107,
+                          0.707107 -1.13713e-16 0.707107,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          0.707107 -1.13713e-16 0.707107,
+                          1 -2.22045e-16 6.12303e-17,
+                          1 -2.22045e-16 6.12303e-17,
+                          1 -2.22045e-16 6.12303e-17,
+                          1 -2.22045e-16 6.12303e-17,
+                          0.707107 -2.00306e-16 -0.707107,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          1 -2.22045e-16 -1.22461e-16,
+                          0.707107 -2.00306e-16 -0.707107,
+                          0.707107 -2.00306e-16 -0.707107,
+                          1.22461e-16 -6.12303e-17 -1,
+                          1 -2.22045e-16 6.12303e-17,
+                          0.707107 -2.00306e-16 -0.707107,
+                          0.707107 -2.00306e-16 -0.707107,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          0.707107 -2.00306e-16 -0.707107,
+                          1.22461e-16 -6.12303e-17 -1,
+                          1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -0.707107 1.13713e-16 -0.707107,
+                          -0.707107 1.13713e-16 -0.707107,
+                          -0.707107 1.13713e-16 -0.707107,
+                          -1 2.22045e-16 6.12303e-17,
+                          -1.22461e-16 -6.12303e-17 -1,
+                          -0.707107 1.13713e-16 -0.707107,
+                          -0.707107 1.13713e-16 -0.707107,
+                          -0.707107 1.13713e-16 -0.707107,
+                          -1 2.22045e-16 6.12303e-17,
+                          -1 2.22045e-16 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17,
+                          0 -1 6.12303e-17 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -805.828 181 -186.828,
+                          -777 181 -200,
+                          -817 181 -200,
+                          -817 159 -200,
+                          -817 181 -200,
+                          -777 181 -200,
+                          -807 181 -184,
+                          -817 181 -200,
+                          -817 181 -24,
+                          -817 159 -24,
+                          -817 181 -24,
+                          -817 181 -200,
+                          -807 181 -184,
+                          -805.828 181 -186.828,
+                          -817 181 -200,
+                          -817 159 -24,
+                          -817 181 -200,
+                          -817 159 -200,
+                          -787 181 -40,
+                          -777 181 -24,
+                          -777 181 -200,
+                          -777 159 -200,
+                          -777 181 -200,
+                          -777 181 -24,
+                          -788.172 181 -186.828,
+                          -787 181 -184,
+                          -777 181 -200,
+                          -787 181 -40,
+                          -777 181 -200,
+                          -787 181 -184,
+                          -791 181 -188,
+                          -788.172 181 -186.828,
+                          -777 181 -200,
+                          -803 181 -188,
+                          -791 181 -188,
+                          -777 181 -200,
+                          -805.828 181 -186.828,
+                          -803 181 -188,
+                          -777 181 -200,
+                          -777 159 -200,
+                          -817 159 -200,
+                          -777 181 -200,
+                          -788.172 181 -37.1722,
+                          -817 181 -24,
+                          -777 181 -24,
+                          -777 159 -24,
+                          -777 181 -24,
+                          -817 181 -24,
+                          -787 181 -40,
+                          -788.172 181 -37.1722,
+                          -777 181 -24,
+                          -777 159 -24,
+                          -777 159 -200,
+                          -777 181 -24,
+                          -807 181 -40,
+                          -807 181 -184,
+                          -817 181 -24,
+                          -805.828 181 -37.1722,
+                          -807 181 -40,
+                          -817 181 -24,
+                          -803 181 -36,
+                          -805.828 181 -37.1722,
+                          -817 181 -24,
+                          -791 181 -36,
+                          -803 181 -36,
+                          -817 181 -24,
+                          -788.172 181 -37.1722,
+                          -791 181 -36,
+                          -817 181 -24,
+                          -817 159 -24,
+                          -777 159 -24,
+                          -817 181 -24,
+                          -787 159 -184,
+                          -787 181 -184,
+                          -788.172 181 -186.828,
+                          -787 159 -40,
+                          -787 181 -40,
+                          -787 181 -184,
+                          -787 159 -40,
+                          -787 181 -184,
+                          -787 159 -184,
+                          -788.172 159 -186.828,
+                          -788.172 181 -186.828,
+                          -791 181 -188,
+                          -788.172 159 -186.828,
+                          -787 159 -184,
+                          -788.172 181 -186.828,
+                          -803 159 -188,
+                          -791 181 -188,
+                          -803 181 -188,
+                          -791 159 -188,
+                          -791 181 -188,
+                          -803 159 -188,
+                          -788.172 159 -186.828,
+                          -791 181 -188,
+                          -791 159 -188,
+                          -803 159 -188,
+                          -803 181 -188,
+                          -805.828 181 -186.828,
+                          -805.828 159 -186.828,
+                          -805.828 181 -186.828,
+                          -807 181 -184,
+                          -803 159 -188,
+                          -805.828 181 -186.828,
+                          -805.828 159 -186.828,
+                          -807 159 -184,
+                          -807 181 -184,
+                          -807 181 -40,
+                          -805.828 159 -186.828,
+                          -807 181 -184,
+                          -807 159 -184,
+                          -807 159 -40,
+                          -807 181 -40,
+                          -805.828 181 -37.1722,
+                          -807 159 -184,
+                          -807 181 -40,
+                          -807 159 -40,
+                          -805.828 159 -37.1722,
+                          -805.828 181 -37.1722,
+                          -803 181 -36,
+                          -807 159 -40,
+                          -805.828 181 -37.1722,
+                          -805.828 159 -37.1722,
+                          -791 159 -36,
+                          -803 181 -36,
+                          -791 181 -36,
+                          -803 159 -36,
+                          -803 181 -36,
+                          -791 159 -36,
+                          -805.828 159 -37.1722,
+                          -803 181 -36,
+                          -803 159 -36,
+                          -791 159 -36,
+                          -791 181 -36,
+                          -788.172 181 -37.1722,
+                          -788.172 159 -37.1722,
+                          -788.172 181 -37.1722,
+                          -787 181 -40,
+                          -791 159 -36,
+                          -788.172 181 -37.1722,
+                          -788.172 159 -37.1722,
+                          -788.172 159 -37.1722,
+                          -787 181 -40,
+                          -787 159 -40,
+                          -788.172 159 -186.828,
+                          -817 159 -200,
+                          -777 159 -200,
+                          -807 159 -40,
+                          -817 159 -24,
+                          -817 159 -200,
+                          -807 159 -184,
+                          -807 159 -40,
+                          -817 159 -200,
+                          -805.828 159 -186.828,
+                          -807 159 -184,
+                          -817 159 -200,
+                          -803 159 -188,
+                          -805.828 159 -186.828,
+                          -817 159 -200,
+                          -791 159 -188,
+                          -803 159 -188,
+                          -817 159 -200,
+                          -788.172 159 -186.828,
+                          -791 159 -188,
+                          -817 159 -200,
+                          -787 159 -184,
+                          -777 159 -200,
+                          -777 159 -24,
+                          -788.172 159 -186.828,
+                          -777 159 -200,
+                          -787 159 -184,
+                          -805.828 159 -37.1722,
+                          -777 159 -24,
+                          -817 159 -24,
+                          -787 159 -40,
+                          -787 159 -184,
+                          -777 159 -24,
+                          -788.172 159 -37.1722,
+                          -787 159 -40,
+                          -777 159 -24,
+                          -791 159 -36,
+                          -788.172 159 -37.1722,
+                          -777 159 -24,
+                          -803 159 -36,
+                          -791 159 -36,
+                          -777 159 -24,
+                          -805.828 159 -37.1722,
+                          -803 159 -36,
+                          -777 159 -24,
+                          -807 159 -40,
+                          -805.828 159 -37.1722,
+                          -817 159 -24 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/right_arm/shoulder_link_r.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/right_arm/shoulder_link_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..cad080b2aa3bbf159172cf9f86a2cca503567cfc
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/right_arm/shoulder_link_r.iv
@@ -0,0 +1,1225 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.386933 0.500748 0.62
+    }
+    Separator {
+        Normal {
+            vector      [ 1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 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,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -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,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -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,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          0.576683 7.0621e-17 0.816968,
+                          0.576683 7.0621e-17 0.816968,
+                          0.576683 7.0621e-17 0.816968,
+                          0.576683 7.0621e-17 0.816968,
+                          0.576683 7.0621e-17 0.816968,
+                          0.576683 7.0621e-17 0.816968,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          1 3.67382e-16 0,
+                          1 3.67382e-16 0,
+                          0.5 0.866025 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          1 1.22461e-16 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.5 -0.866025 0,
+                          1 1.22461e-16 0,
+                          1 3.44505e-16 0,
+                          0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          1 3.67382e-16 0,
+                          0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          -1 -2.44921e-16 0,
+                          0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -1 -2.44921e-16 0,
+                          -1 -2.44921e-16 0,
+                          -0.5 -0.866025 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.5 0.866025 0,
+                          -1 -2.44921e-16 0,
+                          -1 -2.44921e-16 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          -1 -2.44921e-16 0,
+                          -0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          0.671507 0.740998 0,
+                          0.671507 0.740998 0,
+                          0.671507 0.740998 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          0.671507 0.740998 0,
+                          0.671507 0.740998 0,
+                          0.671507 0.740998 0,
+                          -1 -3.06152e-16 0,
+                          -1 -3.06152e-16 0,
+                          -0.718598 0.695426 0,
+                          -0.718598 0.695426 0,
+                          -0.718598 0.695426 0,
+                          -0.0327655 0.999463 0,
+                          -0.718598 0.695426 0,
+                          -1 -3.06152e-16 0,
+                          -0.718598 0.695426 0,
+                          -0.0327655 0.999463 0,
+                          -0.0327655 0.999463 0,
+                          0.671507 0.740998 0,
+                          -0.718598 0.695426 0,
+                          -0.0327655 0.999463 0,
+                          -0.0327655 0.999463 0,
+                          -0.0327655 0.999463 0,
+                          0.671507 0.740998 0,
+                          0.671507 0.740998 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,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          1 1.22461e-16 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          0.707107 0.707107 0,
+                          1 -1.22461e-16 0,
+                          1 -1.22461e-16 0,
+                          0.707107 0.707107 0,
+                          1 -1.22461e-16 0,
+                          0.707107 0.707107 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,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          -1 1.22461e-16 0,
+                          -1 1.22461e-16 0,
+                          -0.5 0.866025 0,
+                          -0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -1 -1.22461e-16 0,
+                          -0.5 -0.866025 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          -0.5 0.866025 0,
+                          -1 1.22461e-16 0,
+                          -0.5 0.866025 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          1 0 0,
+                          -0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          0.5 0.866025 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          1 0 0,
+                          1 0 0,
+                          0.5 -0.866025 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.5 0.866025 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          1 0 0,
+                          0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -0.5 -0.866025 0,
+                          -0.707107 0.707107 0,
+                          -0.707107 0.707107 0,
+                          -1 2.44921e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -0.707107 0.707107 0,
+                          -1 2.44921e-16 0,
+                          -1 2.44921e-16 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0.707107 0.707107 0,
+                          0.707107 0.707107 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          -0.707107 0.707107 0,
+                          0.707107 0.707107 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          -0.707107 0.707107 0,
+                          -0.707107 0.707107 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,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 1 0,
+                          -1.22461e-16 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,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 -1.22461e-16 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.866025 0 0.5,
+                          -0.866025 0 -0.5,
+                          -0.866025 0 -0.5,
+                          -1 0 0,
+                          -0.866025 0 -0.5,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.866025 0 0.5,
+                          -0.866025 0 0.5,
+                          -0.5 0 0.866025,
+                          -0.866025 0 0.5,
+                          -1 0 0,
+                          -0.866025 0 0.5,
+                          -0.5 0 0.866025,
+                          -0.5 0 0.866025,
+                          -6.12303e-17 0 1,
+                          -0.866025 0 0.5,
+                          -0.5 0 0.866025,
+                          -0.5 0 0.866025,
+                          1.60814e-16 0 1,
+                          -6.12303e-17 0 1,
+                          0.5 0 0.866025,
+                          -0.5 0 0.866025,
+                          -6.12303e-17 0 1,
+                          1.60814e-16 0 1,
+                          0.5 0 0.866025,
+                          0.5 0 0.866025,
+                          0.866025 0 0.5,
+                          1.60814e-16 0 1,
+                          0.5 0 0.866025,
+                          0.5 0 0.866025,
+                          0.866025 0 0.5,
+                          0.866025 0 0.5,
+                          1 0 1.22461e-16,
+                          0.5 0 0.866025,
+                          0.866025 0 0.5,
+                          0.866025 0 0.5,
+                          1 0 -1.22461e-16,
+                          1 0 -1.22461e-16,
+                          0.866025 0 -0.5,
+                          0.866025 0 0.5,
+                          1 0 1.22461e-16,
+                          1 0 1.22461e-16,
+                          0.866025 0 -0.5,
+                          0.866025 0 -0.5,
+                          0.5 0 -0.866025,
+                          1 0 -1.22461e-16,
+                          0.866025 0 -0.5,
+                          0.866025 0 -0.5,
+                          0.5 0 -0.866025,
+                          0.5 0 -0.866025,
+                          -6.12303e-17 0 -1,
+                          0.866025 0 -0.5,
+                          0.5 0 -0.866025,
+                          0.5 0 -0.866025,
+                          3.82859e-16 0 -1,
+                          -6.12303e-17 0 -1,
+                          -0.5 0 -0.866025,
+                          0.5 0 -0.866025,
+                          -6.12303e-17 0 -1,
+                          3.82859e-16 0 -1,
+                          -0.5 0 -0.866025,
+                          -0.5 0 -0.866025,
+                          -0.866025 0 -0.5,
+                          3.82859e-16 0 -1,
+                          -0.5 0 -0.866025,
+                          -0.5 0 -0.866025,
+                          -0.5 0 -0.866025,
+                          -0.866025 0 -0.5,
+                          -0.866025 0 -0.5,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0,
+                          1.22461e-16 -1 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -30 -38 -50,
+                          30 -38 -50,
+                          30 -38 -28,
+                          30 -32 -44,
+                          30 -38 -28,
+                          30 -38 -50,
+                          -30 -38 -28,
+                          -30 -38 -50,
+                          30 -38 -28,
+                          -40 -75 -28,
+                          -30 -38 -28,
+                          30 -38 -28,
+                          30 -75 16,
+                          30 -38 -28,
+                          30 -38 16,
+                          30 -32 -44,
+                          30 -38 16,
+                          30 -38 -28,
+                          30 -75 -28,
+                          30 -38 -28,
+                          30 -75 16,
+                          -40 -75 -28,
+                          30 -38 -28,
+                          30 -75 -28,
+                          -30 -7.10543e-15 -50,
+                          30 -38 -50,
+                          -30 -38 -50,
+                          30 7.10543e-15 -50,
+                          30 -32 -44,
+                          30 -38 -50,
+                          11 0 -50,
+                          30 7.10543e-15 -50,
+                          30 -38 -50,
+                          5.5 -9.52628 -50,
+                          11 0 -50,
+                          30 -38 -50,
+                          -5.5 -9.52628 -50,
+                          5.5 -9.52628 -50,
+                          30 -38 -50,
+                          -30 -7.10543e-15 -50,
+                          -5.5 -9.52628 -50,
+                          30 -38 -50,
+                          -30 -32 -44,
+                          -30 -38 -50,
+                          -30 -38 -28,
+                          -30 -32 -44,
+                          -30 -7.10543e-15 -50,
+                          -30 -38 -50,
+                          -30 -32 -28,
+                          -30 -32 -44,
+                          -30 -38 -28,
+                          -40 -75 -28,
+                          -30 -32 -28,
+                          -30 -38 -28,
+                          52.4 -38 51,
+                          -30 -38 51,
+                          -30 -38 28,
+                          -30 -32 28,
+                          -30 -38 28,
+                          -30 -38 51,
+                          13 -38 28,
+                          52.4 -38 51,
+                          -30 -38 28,
+                          13 -75 28,
+                          13 -38 28,
+                          -30 -38 28,
+                          -40 -32 28,
+                          -30 -38 28,
+                          -30 -32 28,
+                          13 -75 28,
+                          -30 -38 28,
+                          -40 -32 28,
+                          -7.99874 -13.8567 51,
+                          -30 -38 51,
+                          52.4 -38 51,
+                          -30 -7.10543e-15 51,
+                          -30 -38 51,
+                          -7.99874 -13.8567 51,
+                          -30 -7.10543e-15 45,
+                          -30 -38 51,
+                          -30 -7.10543e-15 51,
+                          -30 -32 45,
+                          -30 -38 51,
+                          -30 -7.10543e-15 45,
+                          -30 -32 45,
+                          -30 -32 28,
+                          -30 -38 51,
+                          30 -38 18,
+                          52.4 -38 18,
+                          52.4 -38 51,
+                          52.4 -32 45,
+                          52.4 -38 51,
+                          52.4 -38 18,
+                          13 -38 28,
+                          30 -38 18,
+                          52.4 -38 51,
+                          7.99874 -13.8567 51,
+                          -7.99874 -13.8567 51,
+                          52.4 -38 51,
+                          16 0 51,
+                          7.99874 -13.8567 51,
+                          52.4 -38 51,
+                          20.1452 22.2299 51,
+                          16 0 51,
+                          52.4 -38 51,
+                          20.1452 22.2299 51,
+                          52.4 -38 51,
+                          52.4 -7 51,
+                          52.4 -32 45,
+                          52.4 -7 51,
+                          52.4 -38 51,
+                          52.4 -32 18,
+                          52.4 -38 18,
+                          30 -38 18,
+                          52.4 -32 18,
+                          52.4 -32 45,
+                          52.4 -38 18,
+                          13 -38 28,
+                          30 -38 16,
+                          30 -38 18,
+                          30 -32 -44,
+                          30 -38 18,
+                          30 -38 16,
+                          30 -32 18,
+                          52.4 -32 18,
+                          30 -38 18,
+                          30 -32 -44,
+                          30 -32 18,
+                          30 -38 18,
+                          13 -75 28,
+                          30 -38 16,
+                          13 -38 28,
+                          13 -75 28,
+                          30 -75 16,
+                          30 -38 16,
+                          -30 -7.10543e-15 51,
+                          -7.99874 -13.8567 51,
+                          -16 0 51,
+                          -16 0 45,
+                          -16 0 51,
+                          -7.99874 -13.8567 51,
+                          -21.5565 20.8637 51,
+                          -16 0 51,
+                          -7.99874 13.8567 51,
+                          -7.99874 13.8567 45,
+                          -7.99874 13.8567 51,
+                          -16 0 51,
+                          -21.5565 20.8637 51,
+                          -30 -7.10543e-15 51,
+                          -16 0 51,
+                          -7.99874 13.8567 45,
+                          -16 0 51,
+                          -16 0 45,
+                          -7.99874 -13.8567 45,
+                          -7.99874 -13.8567 51,
+                          7.99874 -13.8567 51,
+                          -7.99874 -13.8567 45,
+                          -16 0 45,
+                          -7.99874 -13.8567 51,
+                          7.99874 -13.8567 45,
+                          7.99874 -13.8567 51,
+                          16 0 51,
+                          -7.99874 -13.8567 45,
+                          7.99874 -13.8567 51,
+                          7.99874 -13.8567 45,
+                          -0.984611 29.9834 51,
+                          7.99874 13.8567 51,
+                          16 0 51,
+                          16 0 45,
+                          16 0 51,
+                          7.99874 13.8567 51,
+                          20.1452 22.2299 51,
+                          -0.984611 29.9834 51,
+                          16 0 51,
+                          7.99874 -13.8567 45,
+                          16 0 51,
+                          16 0 45,
+                          -0.984611 29.9834 51,
+                          -7.99874 13.8567 51,
+                          7.99874 13.8567 51,
+                          7.99874 13.8567 45,
+                          7.99874 13.8567 51,
+                          -7.99874 13.8567 51,
+                          16 0 45,
+                          7.99874 13.8567 51,
+                          7.99874 13.8567 45,
+                          -0.984611 29.9834 51,
+                          -21.5565 20.8637 51,
+                          -7.99874 13.8567 51,
+                          7.99874 13.8567 45,
+                          -7.99874 13.8567 51,
+                          -7.99874 13.8567 45,
+                          20.1452 22.2299 45,
+                          20.1452 22.2299 51,
+                          52.4 -7 51,
+                          52.4 -32 45,
+                          52.4 -7 45,
+                          52.4 -7 51,
+                          20.1452 22.2299 45,
+                          52.4 -7 51,
+                          52.4 -7 45,
+                          -30 -7.10543e-15 45,
+                          -30 -7.10543e-15 51,
+                          -21.5565 20.8637 51,
+                          -21.5565 20.8637 45,
+                          -21.5565 20.8637 51,
+                          -0.984611 29.9834 51,
+                          -21.5565 20.8637 45,
+                          -30 -7.10543e-15 45,
+                          -21.5565 20.8637 51,
+                          -0.984611 29.9834 45,
+                          -0.984611 29.9834 51,
+                          20.1452 22.2299 51,
+                          -21.5565 20.8637 45,
+                          -0.984611 29.9834 51,
+                          -0.984611 29.9834 45,
+                          -0.984611 29.9834 45,
+                          20.1452 22.2299 51,
+                          20.1452 22.2299 45,
+                          -30 -32 45,
+                          52.4 -7 45,
+                          52.4 -32 45,
+                          7.99874 -13.8567 45,
+                          52.4 -7 45,
+                          -30 -32 45,
+                          7.99874 -13.8567 45,
+                          16 0 45,
+                          52.4 -7 45,
+                          20.1452 22.2299 45,
+                          52.4 -7 45,
+                          16 0 45,
+                          30 -32 18,
+                          52.4 -32 45,
+                          52.4 -32 18,
+                          20.3516 -32 11.75,
+                          52.4 -32 45,
+                          30 -32 18,
+                          -30 -32 45,
+                          52.4 -32 45,
+                          -30 -32 28,
+                          -11.75 -32 20.3516,
+                          -30 -32 28,
+                          52.4 -32 45,
+                          1.05734e-14 -32 23.5,
+                          -11.75 -32 20.3516,
+                          52.4 -32 45,
+                          11.75 -32 20.3516,
+                          1.05734e-14 -32 23.5,
+                          52.4 -32 45,
+                          20.3516 -32 11.75,
+                          11.75 -32 20.3516,
+                          52.4 -32 45,
+                          20.3516 -32 -11.75,
+                          30 -32 18,
+                          30 -32 -44,
+                          20.3516 -32 -11.75,
+                          23.5 -32 0,
+                          30 -32 18,
+                          20.3516 -32 11.75,
+                          30 -32 18,
+                          23.5 -32 0,
+                          23.5 -75 0,
+                          30 -75 -28,
+                          30 -75 16,
+                          20.3516 -75 11.75,
+                          23.5 -75 0,
+                          30 -75 16,
+                          13 -75 28,
+                          20.3516 -75 11.75,
+                          30 -75 16,
+                          30 7.10543e-15 -50,
+                          30 7.10543e-15 -44,
+                          30 -32 -44,
+                          -30 -32 -44,
+                          30 -32 -44,
+                          30 7.10543e-15 -44,
+                          11.75 -32 -20.3516,
+                          30 -32 -44,
+                          -30 -32 -44,
+                          11.75 -32 -20.3516,
+                          20.3516 -32 -11.75,
+                          30 -32 -44,
+                          21.2115 21.2145 -50,
+                          30 7.10543e-15 -44,
+                          30 7.10543e-15 -50,
+                          21.2115 21.2145 -44,
+                          30 7.10543e-15 -44,
+                          21.2115 21.2145 -50,
+                          5.5 -9.52628 -44,
+                          -30 -32 -44,
+                          30 7.10543e-15 -44,
+                          5.5 -9.52628 -44,
+                          30 7.10543e-15 -44,
+                          11 0 -44,
+                          21.2115 21.2145 -44,
+                          11 0 -44,
+                          30 7.10543e-15 -44,
+                          5.5 9.52628 -50,
+                          30 7.10543e-15 -50,
+                          11 0 -50,
+                          -21.2115 21.2145 -50,
+                          30 7.10543e-15 -50,
+                          5.5 9.52628 -50,
+                          -21.2115 21.2145 -50,
+                          21.2115 21.2145 -50,
+                          30 7.10543e-15 -50,
+                          20.3516 -75 -11.75,
+                          30 -75 -28,
+                          23.5 -75 0,
+                          11.75 -75 -20.3516,
+                          1.37303e-16 -75 -23.5,
+                          30 -75 -28,
+                          -40 -75 -28,
+                          30 -75 -28,
+                          1.37303e-16 -75 -23.5,
+                          20.3516 -75 -11.75,
+                          11.75 -75 -20.3516,
+                          30 -75 -28,
+                          11 0 -44,
+                          11 0 -50,
+                          5.5 -9.52628 -50,
+                          5.5 9.52628 -44,
+                          5.5 9.52628 -50,
+                          11 0 -50,
+                          5.5 9.52628 -44,
+                          11 0 -50,
+                          11 0 -44,
+                          5.5 -9.52628 -44,
+                          5.5 -9.52628 -50,
+                          -5.5 -9.52628 -50,
+                          5.5 -9.52628 -44,
+                          11 0 -44,
+                          5.5 -9.52628 -50,
+                          -30 -7.10543e-15 -50,
+                          -11 0 -50,
+                          -5.5 -9.52628 -50,
+                          -5.5 -9.52628 -44,
+                          -5.5 -9.52628 -50,
+                          -11 0 -50,
+                          5.5 -9.52628 -44,
+                          -5.5 -9.52628 -50,
+                          -5.5 -9.52628 -44,
+                          -21.2115 21.2145 -50,
+                          -5.5 9.52628 -50,
+                          -11 0 -50,
+                          -11 0 -44,
+                          -11 0 -50,
+                          -5.5 9.52628 -50,
+                          -21.2115 21.2145 -50,
+                          -11 0 -50,
+                          -30 -7.10543e-15 -50,
+                          -5.5 -9.52628 -44,
+                          -11 0 -50,
+                          -11 0 -44,
+                          -21.2115 21.2145 -50,
+                          5.5 9.52628 -50,
+                          -5.5 9.52628 -50,
+                          -5.5 9.52628 -44,
+                          -5.5 9.52628 -50,
+                          5.5 9.52628 -50,
+                          -11 0 -44,
+                          -5.5 9.52628 -50,
+                          -5.5 9.52628 -44,
+                          -5.5 9.52628 -44,
+                          5.5 9.52628 -50,
+                          5.5 9.52628 -44,
+                          -21.2115 21.2145 -44,
+                          -21.2115 21.2145 -50,
+                          -30 -7.10543e-15 -50,
+                          -30 -32 -44,
+                          -30 -7.10543e-15 -44,
+                          -30 -7.10543e-15 -50,
+                          -21.2115 21.2145 -44,
+                          -30 -7.10543e-15 -50,
+                          -30 -7.10543e-15 -44,
+                          -21.2115 21.2145 -50,
+                          3.43167e-15 29.9995 -50,
+                          21.2115 21.2145 -50,
+                          21.2115 21.2145 -44,
+                          21.2115 21.2145 -50,
+                          3.43167e-15 29.9995 -50,
+                          3.43167e-15 29.9995 -44,
+                          3.43167e-15 29.9995 -50,
+                          -21.2115 21.2145 -50,
+                          21.2115 21.2145 -44,
+                          3.43167e-15 29.9995 -50,
+                          3.43167e-15 29.9995 -44,
+                          3.43167e-15 29.9995 -44,
+                          -21.2115 21.2145 -50,
+                          -21.2115 21.2145 -44,
+                          -11 0 -44,
+                          -30 -7.10543e-15 -44,
+                          -30 -32 -44,
+                          -11 0 -44,
+                          -5.5 9.52628 -44,
+                          -30 -7.10543e-15 -44,
+                          21.2115 21.2145 -44,
+                          -30 -7.10543e-15 -44,
+                          -5.5 9.52628 -44,
+                          21.2115 21.2145 -44,
+                          -21.2115 21.2145 -44,
+                          -30 -7.10543e-15 -44,
+                          -23.5 -32 0,
+                          -30 -32 -44,
+                          -30 -32 -28,
+                          -5.5 -9.52628 -44,
+                          -11 0 -44,
+                          -30 -32 -44,
+                          5.5 -9.52628 -44,
+                          -5.5 -9.52628 -44,
+                          -30 -32 -44,
+                          1.37303e-16 -32 -23.5,
+                          11.75 -32 -20.3516,
+                          -30 -32 -44,
+                          -11.75 -32 -20.3516,
+                          1.37303e-16 -32 -23.5,
+                          -30 -32 -44,
+                          -20.3516 -32 -11.75,
+                          -11.75 -32 -20.3516,
+                          -30 -32 -44,
+                          -23.5 -32 0,
+                          -20.3516 -32 -11.75,
+                          -30 -32 -44,
+                          -40 -32 -28,
+                          -30 -32 28,
+                          -30 -32 -28,
+                          -23.5 -32 0,
+                          -30 -32 -28,
+                          -30 -32 28,
+                          -40 -75 -28,
+                          -40 -32 -28,
+                          -30 -32 -28,
+                          -21.5565 20.8637 45,
+                          -30 -32 45,
+                          -30 -7.10543e-15 45,
+                          -40 -32 -28,
+                          -40 -32 28,
+                          -30 -32 28,
+                          -20.3516 -32 11.75,
+                          -23.5 -32 0,
+                          -30 -32 28,
+                          -11.75 -32 20.3516,
+                          -20.3516 -32 11.75,
+                          -30 -32 28,
+                          -7.99874 -13.8567 45,
+                          -30 -32 45,
+                          -16 0 45,
+                          -21.5565 20.8637 45,
+                          -16 0 45,
+                          -30 -32 45,
+                          -7.99874 -13.8567 45,
+                          7.99874 -13.8567 45,
+                          -30 -32 45,
+                          -0.984611 29.9834 45,
+                          -7.99874 13.8567 45,
+                          -16 0 45,
+                          -21.5565 20.8637 45,
+                          -0.984611 29.9834 45,
+                          -16 0 45,
+                          -0.984611 29.9834 45,
+                          7.99874 13.8567 45,
+                          -7.99874 13.8567 45,
+                          20.1452 22.2299 45,
+                          16 0 45,
+                          7.99874 13.8567 45,
+                          -0.984611 29.9834 45,
+                          20.1452 22.2299 45,
+                          7.99874 13.8567 45,
+                          21.2115 21.2145 -44,
+                          5.5 9.52628 -44,
+                          11 0 -44,
+                          21.2115 21.2145 -44,
+                          -5.5 9.52628 -44,
+                          5.5 9.52628 -44,
+                          21.2115 21.2145 -44,
+                          3.43167e-15 29.9995 -44,
+                          -21.2115 21.2145 -44,
+                          -40 -75 28,
+                          -40 -32 28,
+                          -40 -32 -28,
+                          13 -75 28,
+                          -40 -32 28,
+                          -40 -75 28,
+                          -40 -75 28,
+                          -40 -32 -28,
+                          -40 -75 -28,
+                          23.5 -75 0,
+                          23.5 -32 0,
+                          20.3516 -32 -11.75,
+                          20.3516 -75 11.75,
+                          20.3516 -32 11.75,
+                          23.5 -32 0,
+                          20.3516 -75 11.75,
+                          23.5 -32 0,
+                          23.5 -75 0,
+                          20.3516 -75 -11.75,
+                          20.3516 -32 -11.75,
+                          11.75 -32 -20.3516,
+                          20.3516 -75 -11.75,
+                          23.5 -75 0,
+                          20.3516 -32 -11.75,
+                          11.75 -75 -20.3516,
+                          11.75 -32 -20.3516,
+                          1.37303e-16 -32 -23.5,
+                          20.3516 -75 -11.75,
+                          11.75 -32 -20.3516,
+                          11.75 -75 -20.3516,
+                          1.37303e-16 -75 -23.5,
+                          1.37303e-16 -32 -23.5,
+                          -11.75 -32 -20.3516,
+                          11.75 -75 -20.3516,
+                          1.37303e-16 -32 -23.5,
+                          1.37303e-16 -75 -23.5,
+                          -11.75 -75 -20.3516,
+                          -11.75 -32 -20.3516,
+                          -20.3516 -32 -11.75,
+                          1.37303e-16 -75 -23.5,
+                          -11.75 -32 -20.3516,
+                          -11.75 -75 -20.3516,
+                          -20.3516 -75 -11.75,
+                          -20.3516 -32 -11.75,
+                          -23.5 -32 0,
+                          -11.75 -75 -20.3516,
+                          -20.3516 -32 -11.75,
+                          -20.3516 -75 -11.75,
+                          -23.5 -75 -6.70532e-30,
+                          -23.5 -32 0,
+                          -20.3516 -32 11.75,
+                          -20.3516 -75 -11.75,
+                          -23.5 -32 0,
+                          -23.5 -75 -6.70532e-30,
+                          -20.3516 -75 11.75,
+                          -20.3516 -32 11.75,
+                          -11.75 -32 20.3516,
+                          -23.5 -75 -6.70532e-30,
+                          -20.3516 -32 11.75,
+                          -20.3516 -75 11.75,
+                          -11.75 -75 20.3516,
+                          -11.75 -32 20.3516,
+                          1.05734e-14 -32 23.5,
+                          -20.3516 -75 11.75,
+                          -11.75 -32 20.3516,
+                          -11.75 -75 20.3516,
+                          -5.08075e-15 -75 23.5,
+                          1.05734e-14 -32 23.5,
+                          11.75 -32 20.3516,
+                          -11.75 -75 20.3516,
+                          1.05734e-14 -32 23.5,
+                          -5.08075e-15 -75 23.5,
+                          11.75 -75 20.3516,
+                          11.75 -32 20.3516,
+                          20.3516 -32 11.75,
+                          -5.08075e-15 -75 23.5,
+                          11.75 -32 20.3516,
+                          11.75 -75 20.3516,
+                          11.75 -75 20.3516,
+                          20.3516 -32 11.75,
+                          20.3516 -75 11.75,
+                          13 -75 28,
+                          11.75 -75 20.3516,
+                          20.3516 -75 11.75,
+                          13 -75 28,
+                          -5.08075e-15 -75 23.5,
+                          11.75 -75 20.3516,
+                          -40 -75 28,
+                          -11.75 -75 20.3516,
+                          -5.08075e-15 -75 23.5,
+                          13 -75 28,
+                          -40 -75 28,
+                          -5.08075e-15 -75 23.5,
+                          -40 -75 28,
+                          -20.3516 -75 11.75,
+                          -11.75 -75 20.3516,
+                          -40 -75 28,
+                          -23.5 -75 -6.70532e-30,
+                          -20.3516 -75 11.75,
+                          -40 -75 28,
+                          -20.3516 -75 -11.75,
+                          -23.5 -75 -6.70532e-30,
+                          -40 -75 -28,
+                          -11.75 -75 -20.3516,
+                          -20.3516 -75 -11.75,
+                          -40 -75 28,
+                          -40 -75 -28,
+                          -20.3516 -75 -11.75,
+                          -40 -75 -28,
+                          1.37303e-16 -75 -23.5,
+                          -11.75 -75 -20.3516 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/right_arm/shoulder_r.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/right_arm/shoulder_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..fe4128e415492128534416dc5450e17314399375
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/right_arm/shoulder_r.iv
@@ -0,0 +1,2746 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+    Material {
+        diffuseColor    0.392 0.437 0.49
+    }
+    Separator {
+        Normal {
+            vector      [ 5.22546e-16 -0.707107 -0.707107,
+                          -1.24914e-16 -0.707107 0.707107,
+                          -1.24914e-16 -0.707107 0.707107,
+                          -5.22546e-16 0.707107 0.707107,
+                          -1.24914e-16 -0.707107 0.707107,
+                          -1.24914e-16 -0.707107 0.707107,
+                          5.22546e-16 -0.707107 -0.707107,
+                          5.22546e-16 -0.707107 -0.707107,
+                          -1.24914e-16 -0.707107 0.707107,
+                          5.22546e-16 -0.707107 -0.707107,
+                          -1.24914e-16 -0.707107 0.707107,
+                          -1.24914e-16 -0.707107 0.707107,
+                          -5.22546e-16 0.707107 0.707107,
+                          -1.24914e-16 -0.707107 0.707107,
+                          -1.24914e-16 -0.707107 0.707107,
+                          -5.22546e-16 0.707107 0.707107,
+                          -5.22546e-16 0.707107 0.707107,
+                          -1.24914e-16 -0.707107 0.707107,
+                          5.22546e-16 -0.707107 -0.707107,
+                          5.22546e-16 -0.707107 -0.707107,
+                          -1.24914e-16 -0.707107 0.707107,
+                          -1.24914e-16 -0.707107 0.707107,
+                          -1.24914e-16 -0.707107 0.707107,
+                          5.22546e-16 -0.707107 -0.707107,
+                          -5.22546e-16 0.707107 0.707107,
+                          -1.24914e-16 -0.707107 0.707107,
+                          -1.24914e-16 -0.707107 0.707107,
+                          -5.22546e-16 0.707107 0.707107,
+                          -1.24914e-16 -0.707107 0.707107,
+                          -5.22546e-16 0.707107 0.707107,
+                          1.24914e-16 0.707107 -0.707107,
+                          1.24914e-16 0.707107 -0.707107,
+                          5.22546e-16 -0.707107 -0.707107,
+                          5.22546e-16 -0.707107 -0.707107,
+                          5.22546e-16 -0.707107 -0.707107,
+                          1.24914e-16 0.707107 -0.707107,
+                          5.22546e-16 -0.707107 -0.707107,
+                          1.24914e-16 0.707107 -0.707107,
+                          5.22546e-16 -0.707107 -0.707107,
+                          5.22546e-16 -0.707107 -0.707107,
+                          -1.24914e-16 -0.707107 0.707107,
+                          5.22546e-16 -0.707107 -0.707107,
+                          -5.22546e-16 0.707107 0.707107,
+                          1.24914e-16 0.707107 -0.707107,
+                          1.24914e-16 0.707107 -0.707107,
+                          1.24914e-16 0.707107 -0.707107,
+                          5.22546e-16 -0.707107 -0.707107,
+                          1.24914e-16 0.707107 -0.707107,
+                          -5.22546e-16 0.707107 0.707107,
+                          1.24914e-16 0.707107 -0.707107,
+                          1.24914e-16 0.707107 -0.707107,
+                          -5.22546e-16 0.707107 0.707107,
+                          1.24914e-16 0.707107 -0.707107,
+                          -5.22546e-16 0.707107 0.707107,
+                          1.24914e-16 0.707107 -0.707107,
+                          1.24914e-16 0.707107 -0.707107,
+                          5.22546e-16 -0.707107 -0.707107,
+                          -5.22546e-16 0.707107 0.707107,
+                          1.24914e-16 0.707107 -0.707107,
+                          1.24914e-16 0.707107 -0.707107,
+                          -5.22546e-16 0.707107 0.707107,
+                          1.24914e-16 0.707107 -0.707107,
+                          -5.22546e-16 0.707107 0.707107,
+                          1.24914e-16 0.707107 -0.707107,
+                          5.22546e-16 -0.707107 -0.707107,
+                          5.22546e-16 -0.707107 -0.707107,
+                          1 2.81169e-16 4.57824e-16,
+                          1 2.81169e-16 4.57824e-16,
+                          1 2.81169e-16 4.57824e-16,
+                          1 2.81169e-16 4.57824e-16,
+                          1 2.81169e-16 4.57824e-16,
+                          1 2.81169e-16 4.57824e-16,
+                          -5.22546e-16 0.707107 0.707107,
+                          -5.22546e-16 0.707107 0.707107,
+                          1.24914e-16 0.707107 -0.707107,
+                          -1 -2.81169e-16 -4.57824e-16,
+                          -1 -2.81169e-16 -4.57824e-16,
+                          -1 -2.81169e-16 -4.57824e-16,
+                          -1 -2.81169e-16 -4.57824e-16,
+                          -1 -2.81169e-16 -4.57824e-16,
+                          -1 -2.81169e-16 -4.57824e-16,
+                          -5.22546e-16 0.707107 0.707107,
+                          -5.22546e-16 0.707107 0.707107,
+                          -1.24914e-16 -0.707107 0.707107 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -45 -2.12132 107.879,
+                          29 -2.12132 112.121,
+                          -45 -2.12132 112.121,
+                          29 2.12132 112.121,
+                          -45 -2.12132 112.121,
+                          29 -2.12132 112.121,
+                          -66.8 -2.12099 107.879,
+                          -45 -2.12132 107.879,
+                          -45 -2.12132 112.121,
+                          -66.8 -2.12099 107.879,
+                          -45 -2.12132 112.121,
+                          -66.8 -2.12132 112.121,
+                          -45 2.12132 112.121,
+                          -66.8 -2.12132 112.121,
+                          -45 -2.12132 112.121,
+                          29 2.12132 112.121,
+                          -45 2.12132 112.121,
+                          -45 -2.12132 112.121,
+                          -45 -2.12132 107.879,
+                          29 -2.12132 107.879,
+                          29 -2.12132 112.121,
+                          66.8 -2.12132 112.121,
+                          29 -2.12132 112.121,
+                          29 -2.12132 107.879,
+                          66.8 2.12099 112.121,
+                          29 -2.12132 112.121,
+                          66.8 -2.12132 112.121,
+                          29 2.12132 112.121,
+                          29 -2.12132 112.121,
+                          66.8 2.12099 112.121,
+                          -45 2.12132 107.879,
+                          29 2.12132 107.879,
+                          29 -2.12132 107.879,
+                          66.8 -2.12099 107.879,
+                          29 -2.12132 107.879,
+                          29 2.12132 107.879,
+                          -45 -2.12132 107.879,
+                          -45 2.12132 107.879,
+                          29 -2.12132 107.879,
+                          66.8 -2.12099 107.879,
+                          66.8 -2.12132 112.121,
+                          29 -2.12132 107.879,
+                          -45 2.12132 112.121,
+                          29 2.12132 107.879,
+                          -45 2.12132 107.879,
+                          66.8 2.12132 107.879,
+                          66.8 -2.12099 107.879,
+                          29 2.12132 107.879,
+                          29 2.12132 112.121,
+                          66.8 2.12132 107.879,
+                          29 2.12132 107.879,
+                          29 2.12132 112.121,
+                          29 2.12132 107.879,
+                          -45 2.12132 112.121,
+                          -66.8 2.12132 107.879,
+                          -45 2.12132 107.879,
+                          -45 -2.12132 107.879,
+                          -66.8 2.12099 112.121,
+                          -45 2.12132 107.879,
+                          -66.8 2.12132 107.879,
+                          -45 2.12132 112.121,
+                          -45 2.12132 107.879,
+                          -66.8 2.12099 112.121,
+                          -66.8 2.12132 107.879,
+                          -45 -2.12132 107.879,
+                          -66.8 -2.12099 107.879,
+                          66.8 2.12132 107.879,
+                          66.8 -2.12132 112.121,
+                          66.8 -2.12099 107.879,
+                          66.8 2.12099 112.121,
+                          66.8 -2.12132 112.121,
+                          66.8 2.12132 107.879,
+                          29 2.12132 112.121,
+                          66.8 2.12099 112.121,
+                          66.8 2.12132 107.879,
+                          -66.8 2.12132 107.879,
+                          -66.8 -2.12099 107.879,
+                          -66.8 -2.12132 112.121,
+                          -66.8 2.12099 112.121,
+                          -66.8 2.12132 107.879,
+                          -66.8 -2.12132 112.121,
+                          -45 2.12132 112.121,
+                          -66.8 2.12099 112.121,
+                          -66.8 -2.12132 112.121 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    1 0 0
+    }
+    Separator {
+        Normal {
+            vector      [ 1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          1.32875e-16 -0.866025 0.5,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          -5.04106e-16 0.866025 0.5,
+                          -5.04106e-16 0.866025 0.5,
+                          -3.71231e-16 2.44921e-16 1,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          -5.04106e-16 0.866025 0.5,
+                          -3.71231e-16 2.44921e-16 1,
+                          -3.71231e-16 2.44921e-16 1,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1.32875e-16 -0.866025 0.5,
+                          1.32875e-16 -0.866025 0.5,
+                          5.04106e-16 -0.866025 -0.5,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1.32875e-16 -0.866025 0.5,
+                          -3.71231e-16 0 1,
+                          1.32875e-16 -0.866025 0.5,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          5.04106e-16 -0.866025 -0.5,
+                          5.04106e-16 -0.866025 -0.5,
+                          3.71231e-16 -1.22461e-16 -1,
+                          1.32875e-16 -0.866025 0.5,
+                          5.04106e-16 -0.866025 -0.5,
+                          5.04106e-16 -0.866025 -0.5,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          3.71231e-16 -1.22461e-16 -1,
+                          3.71231e-16 -1.22461e-16 -1,
+                          -1.32875e-16 0.866025 -0.5,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          5.04106e-16 -0.866025 -0.5,
+                          3.71231e-16 -1.22461e-16 -1,
+                          3.71231e-16 -1.22461e-16 -1,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          -1.32875e-16 0.866025 -0.5,
+                          -1.32875e-16 0.866025 -0.5,
+                          -5.04106e-16 0.866025 0.5,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          3.71231e-16 -1.22461e-16 -1,
+                          -1.32875e-16 0.866025 -0.5,
+                          -1.32875e-16 0.866025 -0.5,
+                          -1.32875e-16 0.866025 -0.5,
+                          -5.04106e-16 0.866025 0.5,
+                          -5.04106e-16 0.866025 0.5,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          -4.9227e-16 0.901322 0.43315,
+                          -4.9227e-16 0.901322 0.43315,
+                          -4.9227e-16 0.901322 0.43315,
+                          -4.9227e-16 0.901322 0.43315,
+                          -4.9227e-16 0.901322 0.43315,
+                          -4.9227e-16 0.901322 0.43315,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          1.87225e-16 -0.915411 0.40252,
+                          1.87225e-16 -0.915411 0.40252,
+                          1.87225e-16 -0.915411 0.40252,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          1.87225e-16 -0.915411 0.40252,
+                          1.87225e-16 -0.915411 0.40252,
+                          -2.00284e-16 -0.386421 0.922322,
+                          1.87225e-16 -0.915411 0.40252,
+                          1.87225e-16 -0.915411 0.40252,
+                          1.87225e-16 -0.915411 0.40252,
+                          -2.00284e-16 -0.386421 0.922322,
+                          -2.00284e-16 -0.386421 0.922322,
+                          -4.77631e-16 0.35511 0.934825,
+                          1.87225e-16 -0.915411 0.40252,
+                          -2.00284e-16 -0.386421 0.922322,
+                          -2.00284e-16 -0.386421 0.922322,
+                          -4.77631e-16 0.35511 0.934825,
+                          -4.77631e-16 0.35511 0.934825,
+                          -4.9227e-16 0.901322 0.43315,
+                          -2.00284e-16 -0.386421 0.922322,
+                          -4.77631e-16 0.35511 0.934825,
+                          -4.77631e-16 0.35511 0.934825,
+                          -4.77631e-16 0.35511 0.934825,
+                          -4.9227e-16 0.901322 0.43315,
+                          -4.9227e-16 0.901322 0.43315,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 59 57.5 70,
+                          59 18.1851 99.4986,
+                          59 2.64676e-14 89,
+                          53 2.4261e-14 89,
+                          59 2.64676e-14 89,
+                          59 18.1851 99.4986,
+                          59 -50 82,
+                          59 2.64676e-14 89,
+                          59 -18.1851 99.4986,
+                          53 -18.1851 99.4986,
+                          59 -18.1851 99.4986,
+                          59 2.64676e-14 89,
+                          59 -50 82,
+                          59 57.5 70,
+                          59 2.64676e-14 89,
+                          53 -18.1851 99.4986,
+                          59 2.64676e-14 89,
+                          53 2.4261e-14 89,
+                          59 31.0956 124.944,
+                          59 18.1851 120.501,
+                          59 18.1851 99.4986,
+                          53 18.1851 99.4986,
+                          59 18.1851 99.4986,
+                          59 18.1851 120.501,
+                          59 31.0956 124.944,
+                          59 18.1851 99.4986,
+                          59 57.5 70,
+                          53 18.1851 99.4986,
+                          53 2.4261e-14 89,
+                          59 18.1851 99.4986,
+                          59 31.0956 124.944,
+                          59 3.16109e-14 131,
+                          59 18.1851 120.501,
+                          53 18.1851 120.501,
+                          59 18.1851 120.501,
+                          59 3.16109e-14 131,
+                          53 18.1851 99.4986,
+                          59 18.1851 120.501,
+                          53 18.1851 120.501,
+                          59 -31.5817 123.887,
+                          59 -18.1851 120.501,
+                          59 3.16109e-14 131,
+                          53 2.94044e-14 131,
+                          59 3.16109e-14 131,
+                          59 -18.1851 120.501,
+                          59 -13.3297 141.82,
+                          59 -31.5817 123.887,
+                          59 3.16109e-14 131,
+                          59 12.2494 142.252,
+                          59 -13.3297 141.82,
+                          59 3.16109e-14 131,
+                          59 31.0956 124.944,
+                          59 12.2494 142.252,
+                          59 3.16109e-14 131,
+                          53 18.1851 120.501,
+                          59 3.16109e-14 131,
+                          53 2.94044e-14 131,
+                          59 -50 82,
+                          59 -18.1851 99.4986,
+                          59 -18.1851 120.501,
+                          53 -18.1851 120.501,
+                          59 -18.1851 120.501,
+                          59 -18.1851 99.4986,
+                          59 -31.5817 123.887,
+                          59 -50 82,
+                          59 -18.1851 120.501,
+                          53 2.94044e-14 131,
+                          59 -18.1851 120.501,
+                          53 -18.1851 120.501,
+                          53 -18.1851 120.501,
+                          59 -18.1851 99.4986,
+                          53 -18.1851 99.4986,
+                          59 -50 4.26326e-14,
+                          59 57.5 4.26326e-14,
+                          59 57.5 70,
+                          53 57.5 70,
+                          59 57.5 70,
+                          59 57.5 4.26326e-14,
+                          59 -50 82,
+                          59 -50 4.26326e-14,
+                          59 57.5 70,
+                          53 31.0956 124.944,
+                          59 31.0956 124.944,
+                          59 57.5 70,
+                          53 31.0956 124.944,
+                          59 57.5 70,
+                          53 57.5 70,
+                          53 57.5 4.26326e-14,
+                          59 57.5 4.26326e-14,
+                          59 -50 4.26326e-14,
+                          53 57.5 4.26326e-14,
+                          53 57.5 70,
+                          59 57.5 4.26326e-14,
+                          53 -50 4.26326e-14,
+                          59 -50 4.26326e-14,
+                          59 -50 82,
+                          53 57.5 4.26326e-14,
+                          59 -50 4.26326e-14,
+                          53 -50 4.26326e-14,
+                          53 -50 82,
+                          59 -50 82,
+                          59 -31.5817 123.887,
+                          53 -50 4.26326e-14,
+                          59 -50 82,
+                          53 -50 82,
+                          53 -31.5817 123.887,
+                          59 -31.5817 123.887,
+                          59 -13.3297 141.82,
+                          53 -50 82,
+                          59 -31.5817 123.887,
+                          53 -31.5817 123.887,
+                          53 -13.3297 141.82,
+                          59 -13.3297 141.82,
+                          59 12.2494 142.252,
+                          53 -31.5817 123.887,
+                          59 -13.3297 141.82,
+                          53 -13.3297 141.82,
+                          53 12.2494 142.252,
+                          59 12.2494 142.252,
+                          59 31.0956 124.944,
+                          53 -13.3297 141.82,
+                          59 12.2494 142.252,
+                          53 12.2494 142.252,
+                          53 12.2494 142.252,
+                          59 31.0956 124.944,
+                          53 31.0956 124.944,
+                          53 -50 82,
+                          53 -18.1851 99.4986,
+                          53 2.4261e-14 89,
+                          53 57.5 70,
+                          53 2.4261e-14 89,
+                          53 18.1851 99.4986,
+                          53 -50 82,
+                          53 2.4261e-14 89,
+                          53 57.5 70,
+                          53 -31.5817 123.887,
+                          53 -18.1851 120.501,
+                          53 -18.1851 99.4986,
+                          53 -50 82,
+                          53 -31.5817 123.887,
+                          53 -18.1851 99.4986,
+                          53 -31.5817 123.887,
+                          53 2.94044e-14 131,
+                          53 -18.1851 120.501,
+                          53 31.0956 124.944,
+                          53 18.1851 120.501,
+                          53 2.94044e-14 131,
+                          53 -13.3297 141.82,
+                          53 31.0956 124.944,
+                          53 2.94044e-14 131,
+                          53 -31.5817 123.887,
+                          53 -13.3297 141.82,
+                          53 2.94044e-14 131,
+                          53 57.5 70,
+                          53 18.1851 99.4986,
+                          53 18.1851 120.501,
+                          53 31.0956 124.944,
+                          53 57.5 70,
+                          53 18.1851 120.501,
+                          53 57.5 4.26326e-14,
+                          53 -50 82,
+                          53 57.5 70,
+                          53 -13.3297 141.82,
+                          53 12.2494 142.252,
+                          53 31.0956 124.944,
+                          53 57.5 4.26326e-14,
+                          53 -50 4.26326e-14,
+                          53 -50 82 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.386933 0.500748 0.62
+    }
+    Separator {
+        Normal {
+            vector      [ -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0 1,
+                          0 0 1,
+                          -3.18491e-16 0.866025 0.5,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          3.18491e-16 -0.866025 0.5,
+                          3.18491e-16 -0.866025 0.5,
+                          0 -2.44921e-16 1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          3.18491e-16 -0.866025 0.5,
+                          0 -2.44921e-16 1,
+                          0 -2.44921e-16 1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -3.18491e-16 0.866025 0.5,
+                          -3.18491e-16 0.866025 0.5,
+                          -3.18491e-16 0.866025 -0.5,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -3.18491e-16 0.866025 0.5,
+                          0 0 1,
+                          -3.18491e-16 0.866025 0.5,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -3.18491e-16 0.866025 -0.5,
+                          -3.18491e-16 0.866025 -0.5,
+                          0 1.22461e-16 -1,
+                          -3.18491e-16 0.866025 0.5,
+                          -3.18491e-16 0.866025 -0.5,
+                          -3.18491e-16 0.866025 -0.5,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 1.22461e-16 -1,
+                          0 1.22461e-16 -1,
+                          3.18491e-16 -0.866025 -0.5,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -3.18491e-16 0.866025 -0.5,
+                          0 1.22461e-16 -1,
+                          0 1.22461e-16 -1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          3.18491e-16 -0.866025 -0.5,
+                          3.18491e-16 -0.866025 -0.5,
+                          3.18491e-16 -0.866025 0.5,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 1.22461e-16 -1,
+                          3.18491e-16 -0.866025 -0.5,
+                          3.18491e-16 -0.866025 -0.5,
+                          3.18491e-16 -0.866025 -0.5,
+                          3.18491e-16 -0.866025 0.5,
+                          3.18491e-16 -0.866025 0.5,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -3.31471e-16 0.901322 0.43315,
+                          -3.31471e-16 0.901322 0.43315,
+                          -1.30596e-16 0.35511 0.934825,
+                          -3.31471e-16 0.901322 0.43315,
+                          -3.31471e-16 0.901322 0.43315,
+                          -3.31471e-16 0.901322 0.43315,
+                          -3.31471e-16 0.901322 0.43315,
+                          -3.31471e-16 0.901322 0.43315,
+                          -3.31471e-16 0.901322 0.43315,
+                          -1.30596e-16 0.35511 0.934825,
+                          -1.30596e-16 0.35511 0.934825,
+                          1.42111e-16 -0.386421 0.922322,
+                          -1.30596e-16 0.35511 0.934825,
+                          -3.31471e-16 0.901322 0.43315,
+                          -1.30596e-16 0.35511 0.934825,
+                          1.42111e-16 -0.386421 0.922322,
+                          1.42111e-16 -0.386421 0.922322,
+                          3.36653e-16 -0.915411 0.40252,
+                          -1.30596e-16 0.35511 0.934825,
+                          1.42111e-16 -0.386421 0.922322,
+                          1.42111e-16 -0.386421 0.922322,
+                          3.36653e-16 -0.915411 0.40252,
+                          3.36653e-16 -0.915411 0.40252,
+                          3.36653e-16 -0.915411 0.40252,
+                          1.42111e-16 -0.386421 0.922322,
+                          3.36653e-16 -0.915411 0.40252,
+                          3.36653e-16 -0.915411 0.40252,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          3.36653e-16 -0.915411 0.40252,
+                          3.36653e-16 -0.915411 0.40252,
+                          3.36653e-16 -0.915411 0.40252,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 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 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -58 -50 82,
+                          -58 -15.5872 100.999,
+                          -58 -1.06812e-14 92,
+                          -52 -1.06812e-14 92,
+                          -58 -1.06812e-14 92,
+                          -58 -15.5872 100.999,
+                          -58 57.5 70,
+                          -58 -1.06812e-14 92,
+                          -58 15.5872 100.999,
+                          -52 15.5872 100.999,
+                          -58 15.5872 100.999,
+                          -58 -1.06812e-14 92,
+                          -58 57.5 70,
+                          -58 -50 82,
+                          -58 -1.06812e-14 92,
+                          -52 15.5872 100.999,
+                          -58 -1.06812e-14 92,
+                          -52 -1.06812e-14 92,
+                          -58 -31.5817 123.887,
+                          -58 -15.5872 119.001,
+                          -58 -15.5872 100.999,
+                          -52 -15.5872 100.999,
+                          -58 -15.5872 100.999,
+                          -58 -15.5872 119.001,
+                          -58 -50 82,
+                          -58 -31.5817 123.887,
+                          -58 -15.5872 100.999,
+                          -52 -15.5872 100.999,
+                          -52 -1.06812e-14 92,
+                          -58 -15.5872 100.999,
+                          -58 -31.5817 123.887,
+                          -58 -1.50898e-14 128,
+                          -58 -15.5872 119.001,
+                          -52 -15.5872 119.001,
+                          -58 -15.5872 119.001,
+                          -58 -1.50898e-14 128,
+                          -52 -15.5872 100.999,
+                          -58 -15.5872 119.001,
+                          -52 -15.5872 119.001,
+                          -58 31.0956 124.944,
+                          -58 15.5872 119.001,
+                          -58 -1.50898e-14 128,
+                          -52 -1.50898e-14 128,
+                          -58 -1.50898e-14 128,
+                          -58 15.5872 119.001,
+                          -58 -13.3297 141.82,
+                          -58 31.0956 124.944,
+                          -58 -1.50898e-14 128,
+                          -58 -31.5817 123.887,
+                          -58 -13.3297 141.82,
+                          -58 -1.50898e-14 128,
+                          -52 -15.5872 119.001,
+                          -58 -1.50898e-14 128,
+                          -52 -1.50898e-14 128,
+                          -58 57.5 70,
+                          -58 15.5872 100.999,
+                          -58 15.5872 119.001,
+                          -52 15.5872 119.001,
+                          -58 15.5872 119.001,
+                          -58 15.5872 100.999,
+                          -58 57.5 70,
+                          -58 15.5872 119.001,
+                          -58 31.0956 124.944,
+                          -52 -1.50898e-14 128,
+                          -58 15.5872 119.001,
+                          -52 15.5872 119.001,
+                          -52 15.5872 119.001,
+                          -58 15.5872 100.999,
+                          -52 15.5872 100.999,
+                          -58 -13.3297 141.82,
+                          -58 12.2494 142.252,
+                          -58 31.0956 124.944,
+                          -52 31.0956 124.944,
+                          -58 31.0956 124.944,
+                          -58 12.2494 142.252,
+                          -52 57.5 70,
+                          -58 57.5 70,
+                          -58 31.0956 124.944,
+                          -52 57.5 70,
+                          -58 31.0956 124.944,
+                          -52 31.0956 124.944,
+                          -52 12.2494 142.252,
+                          -58 12.2494 142.252,
+                          -58 -13.3297 141.82,
+                          -52 12.2494 142.252,
+                          -52 31.0956 124.944,
+                          -58 12.2494 142.252,
+                          -52 -13.3297 141.82,
+                          -58 -13.3297 141.82,
+                          -58 -31.5817 123.887,
+                          -52 12.2494 142.252,
+                          -58 -13.3297 141.82,
+                          -52 -13.3297 141.82,
+                          -52 -31.5817 123.887,
+                          -58 -31.5817 123.887,
+                          -58 -50 82,
+                          -52 -13.3297 141.82,
+                          -58 -31.5817 123.887,
+                          -52 -31.5817 123.887,
+                          -58 57.5 1.42109e-14,
+                          -58 -50 1.42109e-14,
+                          -58 -50 82,
+                          -52 -50 82,
+                          -58 -50 82,
+                          -58 -50 1.42109e-14,
+                          -58 57.5 70,
+                          -58 57.5 1.42109e-14,
+                          -58 -50 82,
+                          -52 -31.5817 123.887,
+                          -58 -50 82,
+                          -52 -50 82,
+                          -52 -50 1.42109e-14,
+                          -58 -50 1.42109e-14,
+                          -58 57.5 1.42109e-14,
+                          -52 -50 82,
+                          -58 -50 1.42109e-14,
+                          -52 -50 1.42109e-14,
+                          -52 57.5 1.42109e-14,
+                          -58 57.5 1.42109e-14,
+                          -58 57.5 70,
+                          -52 -50 1.42109e-14,
+                          -58 57.5 1.42109e-14,
+                          -52 57.5 1.42109e-14,
+                          -52 57.5 1.42109e-14,
+                          -58 57.5 70,
+                          -52 57.5 70,
+                          -52 57.5 70,
+                          -52 15.5872 100.999,
+                          -52 -1.06812e-14 92,
+                          -52 -50 82,
+                          -52 -1.06812e-14 92,
+                          -52 -15.5872 100.999,
+                          -52 -50 82,
+                          -52 57.5 70,
+                          -52 -1.06812e-14 92,
+                          -52 31.0956 124.944,
+                          -52 15.5872 119.001,
+                          -52 15.5872 100.999,
+                          -52 57.5 70,
+                          -52 31.0956 124.944,
+                          -52 15.5872 100.999,
+                          -52 31.0956 124.944,
+                          -52 -1.50898e-14 128,
+                          -52 15.5872 119.001,
+                          -52 -31.5817 123.887,
+                          -52 -15.5872 119.001,
+                          -52 -1.50898e-14 128,
+                          -52 12.2494 142.252,
+                          -52 -1.50898e-14 128,
+                          -52 31.0956 124.944,
+                          -52 -13.3297 141.82,
+                          -52 -31.5817 123.887,
+                          -52 -1.50898e-14 128,
+                          -52 12.2494 142.252,
+                          -52 -13.3297 141.82,
+                          -52 -1.50898e-14 128,
+                          -52 -50 82,
+                          -52 -15.5872 100.999,
+                          -52 -15.5872 119.001,
+                          -52 -31.5817 123.887,
+                          -52 -50 82,
+                          -52 -15.5872 119.001,
+                          -52 -50 1.42109e-14,
+                          -52 57.5 1.42109e-14,
+                          -52 57.5 70,
+                          -52 -50 82,
+                          -52 -50 1.42109e-14,
+                          -52 57.5 70 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    1 0 0
+    }
+    Separator {
+        Normal {
+            vector      [ 0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -1 0 0,
+                          -1 0 0,
+                          -0.707107 -0.707107 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.707107 0.707107 0,
+                          -0.707107 0.707107 0,
+                          -1 2.44921e-16 0,
+                          -0.707107 0.707107 0,
+                          -1 2.44921e-16 0,
+                          -1 2.44921e-16 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -0.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          -6.12303e-17 -1 0,
+                          -0.707107 -0.707107 0,
+                          -1 0 0,
+                          -0.707107 -0.707107 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          0.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          -6.12303e-17 -1 0,
+                          -6.12303e-17 -1 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.707107 -0.707107 0,
+                          0.707107 -0.707107 0,
+                          1 -1.22461e-16 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          -6.12303e-17 -1 0,
+                          0.707107 -0.707107 0,
+                          0.707107 -0.707107 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          1 -1.22461e-16 0,
+                          1 -1.22461e-16 0,
+                          0.707107 0.707107 0,
+                          0.707107 -0.707107 0,
+                          1 -1.22461e-16 0,
+                          1 -1.22461e-16 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0.707107 0.707107 0,
+                          0.707107 0.707107 0,
+                          1.83691e-16 1 0,
+                          1 -1.22461e-16 0,
+                          0.707107 0.707107 0,
+                          0.707107 0.707107 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          -0.707107 0.707107 0,
+                          0.707107 0.707107 0,
+                          1.83691e-16 1 0,
+                          1.83691e-16 1 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          1.83691e-16 1 0,
+                          -0.707107 0.707107 0,
+                          -0.707107 0.707107 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,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          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,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          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,
+                          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,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 53 57.5 6,
+                          6.01005 6.01005 6,
+                          8.5 -1.04092e-15 6,
+                          8.5 -1.04092e-15 1.42109e-14,
+                          8.5 -1.04092e-15 6,
+                          6.01005 6.01005 6,
+                          53 57.5 6,
+                          8.5 -1.04092e-15 6,
+                          6.01005 -6.01005 6,
+                          6.01005 -6.01005 1.42109e-14,
+                          6.01005 -6.01005 6,
+                          8.5 -1.04092e-15 6,
+                          6.01005 -6.01005 1.42109e-14,
+                          8.5 -1.04092e-15 6,
+                          8.5 -1.04092e-15 1.42109e-14,
+                          53 57.5 6,
+                          0 8.5 6,
+                          6.01005 6.01005 6,
+                          6.01005 6.01005 1.42109e-14,
+                          6.01005 6.01005 6,
+                          0 8.5 6,
+                          6.01005 6.01005 1.42109e-14,
+                          8.5 -1.04092e-15 1.42109e-14,
+                          6.01005 6.01005 6,
+                          53 57.5 6,
+                          -6.01005 6.01005 6,
+                          0 8.5 6,
+                          0 8.5 1.42109e-14,
+                          0 8.5 6,
+                          -6.01005 6.01005 6,
+                          6.01005 6.01005 1.42109e-14,
+                          0 8.5 6,
+                          0 8.5 1.42109e-14,
+                          -52 -50 6,
+                          -8.5 1.04092e-15 6,
+                          -6.01005 6.01005 6,
+                          -6.01005 6.01005 1.42109e-14,
+                          -6.01005 6.01005 6,
+                          -8.5 1.04092e-15 6,
+                          53 57.5 6,
+                          -52 57.5 6,
+                          -6.01005 6.01005 6,
+                          -52 -50 6,
+                          -6.01005 6.01005 6,
+                          -52 57.5 6,
+                          0 8.5 1.42109e-14,
+                          -6.01005 6.01005 6,
+                          -6.01005 6.01005 1.42109e-14,
+                          -52 -50 6,
+                          -6.01005 -6.01005 6,
+                          -8.5 1.04092e-15 6,
+                          -8.5 1.04092e-15 1.42109e-14,
+                          -8.5 1.04092e-15 6,
+                          -6.01005 -6.01005 6,
+                          -6.01005 6.01005 1.42109e-14,
+                          -8.5 1.04092e-15 6,
+                          -8.5 1.04092e-15 1.42109e-14,
+                          -52 -50 6,
+                          -1.56137e-15 -8.5 6,
+                          -6.01005 -6.01005 6,
+                          -6.01005 -6.01005 1.42109e-14,
+                          -6.01005 -6.01005 6,
+                          -1.56137e-15 -8.5 6,
+                          -8.5 1.04092e-15 1.42109e-14,
+                          -6.01005 -6.01005 6,
+                          -6.01005 -6.01005 1.42109e-14,
+                          -52 -50 6,
+                          6.01005 -6.01005 6,
+                          -1.56137e-15 -8.5 6,
+                          -1.56137e-15 -8.5 1.42109e-14,
+                          -1.56137e-15 -8.5 6,
+                          6.01005 -6.01005 6,
+                          -6.01005 -6.01005 1.42109e-14,
+                          -1.56137e-15 -8.5 6,
+                          -1.56137e-15 -8.5 1.42109e-14,
+                          -8 -50 6,
+                          53 57.5 6,
+                          6.01005 -6.01005 6,
+                          -52 -50 6,
+                          -8 -50 6,
+                          6.01005 -6.01005 6,
+                          -1.56137e-15 -8.5 1.42109e-14,
+                          6.01005 -6.01005 6,
+                          6.01005 -6.01005 1.42109e-14,
+                          -52 57.5 1.42109e-14,
+                          -52 57.5 6,
+                          53 57.5 6,
+                          -52 -50 1.42109e-14,
+                          -52 -50 6,
+                          -52 57.5 6,
+                          -52 -50 1.42109e-14,
+                          -52 57.5 6,
+                          -52 57.5 1.42109e-14,
+                          -8 -50 6,
+                          53 -50 6,
+                          53 57.5 6,
+                          53 57.5 1.42109e-14,
+                          53 57.5 6,
+                          53 -50 6,
+                          53 57.5 1.42109e-14,
+                          -52 57.5 1.42109e-14,
+                          53 57.5 6,
+                          53 -50 1.42109e-14,
+                          53 -50 6,
+                          -8 -50 6,
+                          53 57.5 1.42109e-14,
+                          53 -50 6,
+                          53 -50 1.42109e-14,
+                          -52 -64.75 6,
+                          -8 -64.75 6,
+                          -8 -50 6,
+                          -8 -50 1.42109e-14,
+                          -8 -50 6,
+                          -8 -64.75 6,
+                          -52 -50 6,
+                          -52 -64.75 6,
+                          -8 -50 6,
+                          53 -50 1.42109e-14,
+                          -8 -50 6,
+                          -8 -50 1.42109e-14,
+                          -8 -64.75 1.42109e-14,
+                          -8 -64.75 6,
+                          -52 -64.75 6,
+                          -8 -50 1.42109e-14,
+                          -8 -64.75 6,
+                          -8 -64.75 1.42109e-14,
+                          -52 -64.75 1.42109e-14,
+                          -52 -64.75 6,
+                          -52 -50 6,
+                          -8 -64.75 1.42109e-14,
+                          -52 -64.75 6,
+                          -52 -64.75 1.42109e-14,
+                          -52 -64.75 1.42109e-14,
+                          -52 -50 6,
+                          -52 -50 1.42109e-14,
+                          53 -50 1.42109e-14,
+                          6.01005 -6.01005 1.42109e-14,
+                          8.5 -1.04092e-15 1.42109e-14,
+                          53 -50 1.42109e-14,
+                          8.5 -1.04092e-15 1.42109e-14,
+                          6.01005 6.01005 1.42109e-14,
+                          53 -50 1.42109e-14,
+                          -1.56137e-15 -8.5 1.42109e-14,
+                          6.01005 -6.01005 1.42109e-14,
+                          53 -50 1.42109e-14,
+                          -6.01005 -6.01005 1.42109e-14,
+                          -1.56137e-15 -8.5 1.42109e-14,
+                          -52 57.5 1.42109e-14,
+                          -8.5 1.04092e-15 1.42109e-14,
+                          -6.01005 -6.01005 1.42109e-14,
+                          -8 -50 1.42109e-14,
+                          -52 57.5 1.42109e-14,
+                          -6.01005 -6.01005 1.42109e-14,
+                          53 -50 1.42109e-14,
+                          -8 -50 1.42109e-14,
+                          -6.01005 -6.01005 1.42109e-14,
+                          -52 57.5 1.42109e-14,
+                          -6.01005 6.01005 1.42109e-14,
+                          -8.5 1.04092e-15 1.42109e-14,
+                          -52 57.5 1.42109e-14,
+                          0 8.5 1.42109e-14,
+                          -6.01005 6.01005 1.42109e-14,
+                          -52 57.5 1.42109e-14,
+                          6.01005 6.01005 1.42109e-14,
+                          0 8.5 1.42109e-14,
+                          53 57.5 1.42109e-14,
+                          6.01005 6.01005 1.42109e-14,
+                          -52 57.5 1.42109e-14,
+                          53 57.5 1.42109e-14,
+                          53 -50 1.42109e-14,
+                          6.01005 6.01005 1.42109e-14,
+                          -8 -50 1.42109e-14,
+                          -52 -50 1.42109e-14,
+                          -52 57.5 1.42109e-14,
+                          -8 -64.75 1.42109e-14,
+                          -52 -64.75 1.42109e-14,
+                          -52 -50 1.42109e-14,
+                          -8 -50 1.42109e-14,
+                          -8 -64.75 1.42109e-14,
+                          -52 -50 1.42109e-14 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.666667 0.208556 0.221419
+    }
+    Separator {
+        Normal {
+            vector      [ 0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -0.866025 0 0.5,
+                          -0.866025 0 0.5,
+                          -0.866025 0 0.5,
+                          -0.866025 0 0.5,
+                          -0.866025 0 0.5,
+                          -0.866025 0 0.5,
+                          1 0 3.71231e-16,
+                          1 0 3.71231e-16,
+                          1 0 3.71231e-16,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          1 0 3.71231e-16,
+                          1 0 3.71231e-16,
+                          1 0 3.71231e-16,
+                          -1 0 -3.71231e-16,
+                          -1 0 -3.71231e-16,
+                          -1 0 -3.71231e-16,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -1 0 -3.71231e-16,
+                          -1 0 -3.71231e-16,
+                          -1 0 -3.71231e-16,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 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 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 59 57.5 5.68434e-14,
+                          59 57.5 70,
+                          24 57.5 70,
+                          24 60.5 70,
+                          24 57.5 70,
+                          59 57.5 70,
+                          12.453 57.5 50,
+                          59 57.5 5.68434e-14,
+                          24 57.5 70,
+                          12.453 60.5 50,
+                          12.453 57.5 50,
+                          24 57.5 70,
+                          12.453 60.5 50,
+                          24 57.5 70,
+                          24 60.5 70,
+                          59 60.5 70,
+                          59 57.5 70,
+                          59 57.5 5.68434e-14,
+                          59 60.5 70,
+                          24 60.5 70,
+                          59 57.5 70,
+                          -58 57.5 50,
+                          -58 57.5 1.42109e-14,
+                          59 57.5 5.68434e-14,
+                          59 60.5 5.68434e-14,
+                          59 57.5 5.68434e-14,
+                          -58 57.5 1.42109e-14,
+                          12.453 57.5 50,
+                          -58 57.5 50,
+                          59 57.5 5.68434e-14,
+                          59 60.5 70,
+                          59 57.5 5.68434e-14,
+                          59 60.5 5.68434e-14,
+                          -58 60.5 1.42109e-14,
+                          -58 57.5 1.42109e-14,
+                          -58 57.5 50,
+                          59 60.5 5.68434e-14,
+                          -58 57.5 1.42109e-14,
+                          -58 60.5 1.42109e-14,
+                          -58 60.5 50,
+                          -58 57.5 50,
+                          12.453 57.5 50,
+                          -58 60.5 1.42109e-14,
+                          -58 57.5 50,
+                          -58 60.5 50,
+                          -58 60.5 50,
+                          12.453 57.5 50,
+                          12.453 60.5 50,
+                          59 60.5 70,
+                          12.453 60.5 50,
+                          24 60.5 70,
+                          -58 60.5 1.42109e-14,
+                          -58 60.5 50,
+                          12.453 60.5 50,
+                          59 60.5 70,
+                          -58 60.5 1.42109e-14,
+                          12.453 60.5 50,
+                          59 60.5 70,
+                          59 60.5 5.68434e-14,
+                          -58 60.5 1.42109e-14 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.6 0.6 0.6
+    }
+    Separator {
+        Normal {
+            vector      [ 1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          0.95563 -0.294568 3.54759e-16,
+                          1 2.45301e-16 3.71231e-16,
+                          1 2.45301e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          0.83961 -0.54319 3.11689e-16,
+                          1 2.45301e-16 3.71231e-16,
+                          0.95563 -0.294568 3.54759e-16,
+                          0.707107 -0.707107 2.625e-16,
+                          1 2.45301e-16 3.71231e-16,
+                          0.83961 -0.54319 3.11689e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          -2.82764e-16 -0.216594 0.976262,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          -2.82764e-16 -0.216594 0.976262,
+                          -2.82764e-16 -0.216594 0.976262,
+                          -4.95773e-16 0.443205 0.89642,
+                          5.51445e-17 -0.780721 0.62488,
+                          -2.82764e-16 -0.216594 0.976262,
+                          -2.82764e-16 -0.216594 0.976262,
+                          -4.95773e-16 0.443205 0.89642,
+                          -4.95773e-16 0.443205 0.89642,
+                          -4.89794e-16 0.907236 0.420621,
+                          -2.82764e-16 -0.216594 0.976262,
+                          -4.95773e-16 0.443205 0.89642,
+                          -4.95773e-16 0.443205 0.89642,
+                          -4.89794e-16 0.907236 0.420621,
+                          -4.89794e-16 0.907236 0.420621,
+                          -4.89794e-16 0.907236 0.420621,
+                          -4.95773e-16 0.443205 0.89642,
+                          -4.89794e-16 0.907236 0.420621,
+                          -4.89794e-16 0.907236 0.420621,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          -4.89794e-16 0.907236 0.420621,
+                          -4.89794e-16 0.907236 0.420621,
+                          -4.89794e-16 0.907236 0.420621,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -0.707107 0.707107 -2.625e-16,
+                          -1 -2.45301e-16 -3.71231e-16,
+                          -1 -2.45301e-16 -3.71231e-16,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -0.707107 0.707107 -2.625e-16,
+                          -0.934704 0.355427 -3.46991e-16,
+                          -1 -2.45301e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          0.707107 -0.707107 2.625e-16,
+                          0.83961 -0.54319 3.11689e-16,
+                          0.477925 -0.878401 1.7742e-16,
+                          -0.707107 0.707107 -2.625e-16,
+                          -0.773562 0.633721 -2.8717e-16,
+                          -0.934704 0.355427 -3.46991e-16,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -0.427992 0.903782 -1.58884e-16,
+                          -0.773562 0.633721 -2.8717e-16,
+                          -0.707107 0.707107 -2.625e-16,
+                          0.707107 -0.707107 2.625e-16,
+                          3.06531e-16 -1 0,
+                          3.06531e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          0.707107 -0.707107 2.625e-16,
+                          0.477925 -0.878401 1.7742e-16,
+                          3.06531e-16 -1 0,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          -0.427992 0.903782 -1.58884e-16,
+                          -0.707107 0.707107 -2.625e-16,
+                          -3.06531e-16 1 0,
+                          -3.06531e-16 1 0,
+                          -0.427992 0.903782 -1.58884e-16,
+                          -3.06531e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 88 62 59.294,
+                          88 -67 82.5012,
+                          88 -67 32,
+                          87.379 -71.1232 77.3497,
+                          88 -67 32,
+                          88 -67 82.5012,
+                          88 -56 32,
+                          88 62 59.294,
+                          88 -67 32,
+                          86 -56 32,
+                          88 -56 32,
+                          88 -67 32,
+                          86 -56 32,
+                          88 -67 32,
+                          86 -67 32,
+                          83.8995 -76.8995 32,
+                          86 -67 32,
+                          88 -67 32,
+                          85.7545 -74.6047 73,
+                          88 -67 32,
+                          87.379 -71.1232 77.3497,
+                          83.8995 -76.8995 32,
+                          88 -67 32,
+                          85.7545 -74.6047 73,
+                          88 31.2997 125.511,
+                          88 -26.9349 132.558,
+                          88 -67 82.5012,
+                          86 -67 82.5012,
+                          88 -67 82.5012,
+                          88 -26.9349 132.558,
+                          88 62 59.294,
+                          88 31.2997 125.511,
+                          88 -67 82.5012,
+                          85.2164 -71.2651 77.1724,
+                          88 -67 82.5012,
+                          86 -67 82.5012,
+                          85.2164 -71.2651 77.1724,
+                          87.379 -71.1232 77.3497,
+                          88 -67 82.5012,
+                          88 15.2919 141.925,
+                          88 -7.47399 144.68,
+                          88 -26.9349 132.558,
+                          86 -26.9349 132.558,
+                          88 -26.9349 132.558,
+                          88 -7.47399 144.68,
+                          88 31.2997 125.511,
+                          88 15.2919 141.925,
+                          88 -26.9349 132.558,
+                          86 -67 82.5012,
+                          88 -26.9349 132.558,
+                          86 -26.9349 132.558,
+                          86 -7.47399 144.68,
+                          88 -7.47399 144.68,
+                          88 15.2919 141.925,
+                          86 -26.9349 132.558,
+                          88 -7.47399 144.68,
+                          86 -7.47399 144.68,
+                          86 15.2919 141.925,
+                          88 15.2919 141.925,
+                          88 31.2997 125.511,
+                          86 -7.47399 144.68,
+                          88 15.2919 141.925,
+                          86 15.2919 141.925,
+                          86 31.2997 125.511,
+                          88 31.2997 125.511,
+                          88 62 59.294,
+                          86 15.2919 141.925,
+                          88 31.2997 125.511,
+                          86 31.2997 125.511,
+                          88 -62.5 3,
+                          88 62 3,
+                          88 62 59.294,
+                          86 62 59.294,
+                          88 62 59.294,
+                          88 62 3,
+                          88 -56 7,
+                          88 -62.5 3,
+                          88 62 59.294,
+                          88 -56 32,
+                          88 -56 7,
+                          88 62 59.294,
+                          86 31.2997 125.511,
+                          88 62 59.294,
+                          86 62 59.294,
+                          78 62 3,
+                          88 62 3,
+                          88 -62.5 3,
+                          86 62 59.294,
+                          88 62 3,
+                          86 62 5,
+                          78 62 5,
+                          86 62 5,
+                          88 62 3,
+                          78 62 5,
+                          88 62 3,
+                          78 62 3,
+                          88 -56 7,
+                          88 -62.5 7,
+                          88 -62.5 3,
+                          86 -62.5 7,
+                          88 -62.5 3,
+                          88 -62.5 7,
+                          86 -62.5 5,
+                          88 -62.5 3,
+                          86 -62.5 7,
+                          78 -62.5 5,
+                          88 -62.5 3,
+                          86 -62.5 5,
+                          78 62 3,
+                          88 -62.5 3,
+                          78 -62.5 3,
+                          78 -62.5 5,
+                          78 -62.5 3,
+                          88 -62.5 3,
+                          86 -62.5 7,
+                          88 -62.5 7,
+                          88 -56 7,
+                          86 -56 7,
+                          88 -56 7,
+                          88 -56 32,
+                          86 -62.5 7,
+                          88 -56 7,
+                          86 -56 7,
+                          86 -56 7,
+                          88 -56 32,
+                          86 -56 32,
+                          86 -67 82.5012,
+                          86 -56 32,
+                          86 -67 32,
+                          82.4853 -75.4853 32,
+                          86 -67 82.5012,
+                          86 -67 32,
+                          82.4853 -75.4853 32,
+                          86 -67 32,
+                          83.8995 -76.8995 32,
+                          86 62 5,
+                          86 -56 7,
+                          86 -56 32,
+                          86 62 59.294,
+                          86 62 5,
+                          86 -56 32,
+                          86 -67 82.5012,
+                          86 62 59.294,
+                          86 -56 32,
+                          86 62 5,
+                          86 -62.5 7,
+                          86 -56 7,
+                          86 62 5,
+                          86 -62.5 5,
+                          86 -62.5 7,
+                          78 -62.5 5,
+                          86 -62.5 5,
+                          86 62 5,
+                          78 -62.5 5,
+                          86 62 5,
+                          78 62 5,
+                          86 -67 82.5012,
+                          86 31.2997 125.511,
+                          86 62 59.294,
+                          86 -26.9349 132.558,
+                          86 15.2919 141.925,
+                          86 31.2997 125.511,
+                          86 -67 82.5012,
+                          86 -26.9349 132.558,
+                          86 31.2997 125.511,
+                          86 -26.9349 132.558,
+                          86 -7.47399 144.68,
+                          86 15.2919 141.925,
+                          82.4853 -75.4853 32,
+                          85.2164 -71.2651 77.1724,
+                          86 -67 82.5012,
+                          78 62 5,
+                          78 62 3,
+                          78 -62.5 3,
+                          78 -62.5 5,
+                          78 62 5,
+                          78 -62.5 3,
+                          83.2827 -74.6047 73,
+                          85.7545 -74.6047 73,
+                          87.379 -71.1232 77.3497,
+                          85.2164 -71.2651 77.1724,
+                          83.2827 -74.6047 73,
+                          87.379 -71.1232 77.3497,
+                          80.6909 -79.2976 73,
+                          85.7545 -74.6047 73,
+                          83.2827 -74.6047 73,
+                          83.8995 -76.8995 32,
+                          85.7545 -74.6047 73,
+                          80.6909 -79.2976 73,
+                          82.4853 -75.4853 32,
+                          83.2827 -74.6047 73,
+                          85.2164 -71.2651 77.1724,
+                          79.1358 -77.8451 73,
+                          80.6909 -79.2976 73,
+                          83.2827 -74.6047 73,
+                          79.1358 -77.8451 73,
+                          83.2827 -74.6047 73,
+                          82.4853 -75.4853 32,
+                          83.8995 -76.8995 32,
+                          74 -81 73,
+                          74 -81 32,
+                          68 -81 32,
+                          74 -81 32,
+                          74 -81 73,
+                          74 -79 32,
+                          83.8995 -76.8995 32,
+                          74 -81 32,
+                          68 -79 32,
+                          74 -79 32,
+                          74 -81 32,
+                          68 -81 32,
+                          68 -79 32,
+                          74 -81 32,
+                          83.8995 -76.8995 32,
+                          80.6909 -79.2976 73,
+                          74 -81 73,
+                          74 -79 73,
+                          74 -81 73,
+                          80.6909 -79.2976 73,
+                          68 -79 73,
+                          74 -81 73,
+                          74 -79 73,
+                          68 -81 73,
+                          74 -81 73,
+                          68 -79 73,
+                          68 -81 32,
+                          74 -81 73,
+                          68 -81 73,
+                          74 -79 73,
+                          80.6909 -79.2976 73,
+                          79.1358 -77.8451 73,
+                          82.4853 -75.4853 32,
+                          83.8995 -76.8995 32,
+                          74 -79 32,
+                          79.1358 -77.8451 73,
+                          82.4853 -75.4853 32,
+                          74 -79 32,
+                          74 -79 73,
+                          79.1358 -77.8451 73,
+                          74 -79 32,
+                          68 -79 73,
+                          74 -79 73,
+                          74 -79 32,
+                          68 -79 32,
+                          68 -79 73,
+                          74 -79 32,
+                          68 -81 73,
+                          68 -79 73,
+                          68 -79 32,
+                          68 -81 32,
+                          68 -81 73,
+                          68 -79 32 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.463437 0.535976 0.575758
+    }
+    Separator {
+        Normal {
+            vector      [ -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          -0.193181 -0.981163 -7.17148e-17,
+                          3.06531e-16 -1 0,
+                          3.06531e-16 -1 0,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          0.707123 -0.707091 2.62506e-16,
+                          4.28992e-16 -1 0,
+                          4.28992e-16 -1 0,
+                          0.193181 -0.981163 7.17148e-17,
+                          4.28992e-16 -1 0,
+                          0.707123 -0.707091 2.62506e-16,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          -0.707123 -0.707091 -2.62506e-16,
+                          3.06531e-16 -1 0,
+                          -0.379967 -0.925 -1.41055e-16,
+                          -0.193181 -0.981163 -7.17148e-17,
+                          -0.379967 -0.925 -1.41055e-16,
+                          3.06531e-16 -1 0,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -0.707123 -0.707091 -2.62506e-16,
+                          -0.379967 -0.925 -1.41055e-16,
+                          -0.830843 -0.556507 -3.08435e-16,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          0.707123 -0.707091 2.62506e-16,
+                          0.830843 -0.556507 3.08435e-16,
+                          0.379967 -0.925 1.41055e-16,
+                          0.193181 -0.981163 7.17148e-17,
+                          0.707123 -0.707091 2.62506e-16,
+                          0.379967 -0.925 1.41055e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -0.707123 -0.707091 -2.62506e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -0.707123 -0.707091 -2.62506e-16,
+                          -0.830843 -0.556507 -3.08435e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          0.830843 -0.556507 3.08435e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          0.707123 -0.707091 2.62506e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          0.830843 -0.556507 3.08435e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -75 -81 73,
+                          76 -82.5 73,
+                          76 -81 73,
+                          76 -82.5 3,
+                          76 -81 73,
+                          76 -82.5 73,
+                          -75 -81 3,
+                          -75 -81 73,
+                          76 -81 73,
+                          76 -82.5 3,
+                          76 -81 3,
+                          76 -81 73,
+                          75.5993 -81 3,
+                          76 -81 73,
+                          76 -81 3,
+                          -74.5993 -81 3,
+                          -75 -81 3,
+                          76 -81 73,
+                          75.5993 -81 3,
+                          -74.5993 -81 3,
+                          76 -81 73,
+                          -75 -81 73,
+                          -75 -82.5 73,
+                          76 -82.5 73,
+                          76 -82.5 3,
+                          76 -82.5 73,
+                          -75 -82.5 73,
+                          -75 -81 3,
+                          -75 -82.5 73,
+                          -75 -81 73,
+                          68 -82.5 3,
+                          76 -82.5 3,
+                          -75 -82.5 73,
+                          -75 -82.5 3,
+                          -67 -82.5 3,
+                          -75 -82.5 73,
+                          68 -82.5 1.5,
+                          -75 -82.5 73,
+                          -67 -82.5 3,
+                          -75 -81 3,
+                          -75 -82.5 3,
+                          -75 -82.5 73,
+                          68 -82.5 1.5,
+                          68 -82.5 3,
+                          -75 -82.5 73,
+                          71.8636 -82.123 3,
+                          76 -81 3,
+                          76 -82.5 3,
+                          71.8636 -82.123 3,
+                          75.5993 -81 3,
+                          76 -81 3,
+                          71.8636 -82.123 3,
+                          76 -82.5 3,
+                          68 -82.5 3,
+                          -70.8636 -82.123 3,
+                          -67 -82.5 3,
+                          -75 -82.5 3,
+                          -67 -82.5 1.5,
+                          68 -82.5 1.5,
+                          -67 -82.5 3,
+                          -70.8636 -82.123 3,
+                          -67 -82.5 1.5,
+                          -67 -82.5 3,
+                          -74.5993 -81 3,
+                          -75 -82.5 3,
+                          -75 -81 3,
+                          -70.8636 -82.123 3,
+                          -75 -82.5 3,
+                          -74.5993 -81 3,
+                          82.1415 -76.6408 1.5,
+                          68 -82.5 3,
+                          68 -82.5 1.5,
+                          71.8636 -82.123 3,
+                          68 -82.5 3,
+                          82.1415 -76.6408 1.5,
+                          88 -52.5 1.5,
+                          68 -82.5 1.5,
+                          -67 -82.5 1.5,
+                          82.1415 -76.6408 1.5,
+                          68 -82.5 1.5,
+                          88 -52.5 1.5,
+                          -81.1415 -76.6408 1.5,
+                          -67 -82.5 1.5,
+                          -74.5993 -81 3,
+                          -70.8636 -82.123 3,
+                          -74.5993 -81 3,
+                          -67 -82.5 1.5,
+                          -81.1415 -76.6408 1.5,
+                          88 -52.5 1.5,
+                          -67 -82.5 1.5,
+                          -87 -52.5 3,
+                          -74.5993 -81 3,
+                          75.5993 -81 3,
+                          -83.6169 -73.6302 3,
+                          -74.5993 -81 3,
+                          -87 -52.5 3,
+                          -81.1415 -76.6408 1.5,
+                          -74.5993 -81 3,
+                          -83.6169 -73.6302 3,
+                          84.6169 -73.6302 3,
+                          -87 -52.5 3,
+                          75.5993 -81 3,
+                          82.1415 -76.6408 1.5,
+                          84.6169 -73.6302 3,
+                          75.5993 -81 3,
+                          71.8636 -82.123 3,
+                          82.1415 -76.6408 1.5,
+                          75.5993 -81 3,
+                          -87 -52.5 3,
+                          -87 -62.5 1.5,
+                          -87 -62.5 3,
+                          -81.1415 -76.6408 1.5,
+                          -87 -62.5 3,
+                          -87 -62.5 1.5,
+                          -83.6169 -73.6302 3,
+                          -87 -52.5 3,
+                          -87 -62.5 3,
+                          -81.1415 -76.6408 1.5,
+                          -83.6169 -73.6302 3,
+                          -87 -62.5 3,
+                          -87 -52.5 3,
+                          -87 -52.5 1.5,
+                          -87 -62.5 1.5,
+                          88 -52.5 1.5,
+                          -87 -62.5 1.5,
+                          -87 -52.5 1.5,
+                          -81.1415 -76.6408 1.5,
+                          -87 -62.5 1.5,
+                          88 -52.5 1.5,
+                          88 -52.5 3,
+                          -87 -52.5 1.5,
+                          -87 -52.5 3,
+                          88 -52.5 1.5,
+                          -87 -52.5 1.5,
+                          88 -52.5 3,
+                          88 -52.5 3,
+                          -87 -52.5 3,
+                          88 -62.5 3,
+                          84.6169 -73.6302 3,
+                          88 -62.5 3,
+                          -87 -52.5 3,
+                          88 -52.5 1.5,
+                          88 -62.5 3,
+                          88 -62.5 1.5,
+                          84.6169 -73.6302 3,
+                          88 -62.5 1.5,
+                          88 -62.5 3,
+                          82.1415 -76.6408 1.5,
+                          88 -52.5 1.5,
+                          88 -62.5 1.5,
+                          82.1415 -76.6408 1.5,
+                          88 -62.5 1.5,
+                          84.6169 -73.6302 3,
+                          88 -52.5 1.5,
+                          88 -52.5 3,
+                          88 -62.5 3 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.6 0.6 0.6
+    }
+    Separator {
+        Normal {
+            vector      [ 1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          0.934703 0.35543 3.46991e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          0.773562 0.633721 2.8717e-16,
+                          0.707107 0.707107 2.625e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          0.773562 0.633721 2.8717e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          0.934703 0.35543 3.46991e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          -2.82764e-16 -0.216594 0.976262,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          -2.82764e-16 -0.216594 0.976262,
+                          -2.82764e-16 -0.216594 0.976262,
+                          -4.95773e-16 0.443205 0.89642,
+                          5.51445e-17 -0.780721 0.62488,
+                          -2.82764e-16 -0.216594 0.976262,
+                          -2.82764e-16 -0.216594 0.976262,
+                          -4.95773e-16 0.443205 0.89642,
+                          -4.95773e-16 0.443205 0.89642,
+                          -4.89794e-16 0.907236 0.420621,
+                          -2.82764e-16 -0.216594 0.976262,
+                          -4.95773e-16 0.443205 0.89642,
+                          -4.95773e-16 0.443205 0.89642,
+                          -4.89794e-16 0.907236 0.420621,
+                          -4.89794e-16 0.907236 0.420621,
+                          -4.89794e-16 0.907236 0.420621,
+                          -4.95773e-16 0.443205 0.89642,
+                          -4.89794e-16 0.907236 0.420621,
+                          -4.89794e-16 0.907236 0.420621,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -4.89794e-16 0.907236 0.420621,
+                          -4.89794e-16 0.907236 0.420621,
+                          -4.89794e-16 0.907236 0.420621,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -0.707107 -0.707107 -2.625e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -0.955628 -0.294576 -3.54759e-16,
+                          -1 -3.67761e-16 -3.71231e-16,
+                          -0.707107 -0.707107 -2.625e-16,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          -0.477925 -0.878401 -1.7742e-16,
+                          -0.707107 -0.707107 -2.625e-16,
+                          3.06531e-16 -1 0,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          -0.955628 -0.294576 -3.54759e-16,
+                          -0.707107 -0.707107 -2.625e-16,
+                          -0.83961 -0.54319 -3.11689e-16,
+                          -0.477925 -0.878401 -1.7742e-16,
+                          -0.83961 -0.54319 -3.11689e-16,
+                          -0.707107 -0.707107 -2.625e-16,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.06531e-16 -1 0,
+                          -0.477925 -0.878401 -1.7742e-16,
+                          3.06531e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.67761e-16 -1 0,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          3.71231e-16 0 -1,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.67761e-16 1 0,
+                          -3.06531e-16 1 0,
+                          -3.06531e-16 1 0,
+                          0.707107 0.707107 2.625e-16,
+                          0.427992 0.903782 1.58884e-16,
+                          0.707107 0.707107 2.625e-16,
+                          0.773562 0.633721 2.8717e-16,
+                          0.427992 0.903782 1.58884e-16,
+                          -3.06531e-16 1 0,
+                          0.707107 0.707107 2.625e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          1 3.67761e-16 3.71231e-16,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          5.51445e-17 -0.780721 0.62488,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1,
+                          -3.71231e-16 0 1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -85 -67 3,
+                          -85 -62.5 3,
+                          -85 -62.5 5,
+                          -77 -62.5 3,
+                          -85 -62.5 5,
+                          -85 -62.5 3,
+                          -85 -67 82.5012,
+                          -85 -67 3,
+                          -85 -62.5 5,
+                          -85 62 59.294,
+                          -85 -67 82.5012,
+                          -85 -62.5 5,
+                          -85 62 5,
+                          -85 62 59.294,
+                          -85 -62.5 5,
+                          -77 62 5,
+                          -85 62 5,
+                          -85 -62.5 5,
+                          -77 -62.5 5,
+                          -85 -62.5 5,
+                          -77 -62.5 3,
+                          -77 -62.5 5,
+                          -77 62 5,
+                          -85 -62.5 5,
+                          -87 62 3,
+                          -85 -62.5 3,
+                          -85 -67 3,
+                          -77 -62.5 3,
+                          -85 -62.5 3,
+                          -87 62 3,
+                          -84.2164 -71.2652 77.1723,
+                          -85 -67 3,
+                          -85 -67 82.5012,
+                          -87 62 3,
+                          -85 -67 3,
+                          -87 -67 3,
+                          -81.4848 -75.4848 3,
+                          -87 -67 3,
+                          -85 -67 3,
+                          -82.2827 -74.6047 73,
+                          -81.4848 -75.4848 3,
+                          -85 -67 3,
+                          -82.2827 -74.6047 73,
+                          -85 -67 3,
+                          -84.2164 -71.2652 77.1723,
+                          -85 31.2997 125.511,
+                          -85 -26.9349 132.558,
+                          -85 -67 82.5012,
+                          -87 -67 82.5012,
+                          -85 -67 82.5012,
+                          -85 -26.9349 132.558,
+                          -85 62 59.294,
+                          -85 31.2997 125.511,
+                          -85 -67 82.5012,
+                          -86.3789 -71.1233 77.3496,
+                          -85 -67 82.5012,
+                          -87 -67 82.5012,
+                          -86.3789 -71.1233 77.3496,
+                          -84.2164 -71.2652 77.1723,
+                          -85 -67 82.5012,
+                          -85 15.2919 141.925,
+                          -85 -7.47399 144.68,
+                          -85 -26.9349 132.558,
+                          -87 -26.9349 132.558,
+                          -85 -26.9349 132.558,
+                          -85 -7.47399 144.68,
+                          -85 31.2997 125.511,
+                          -85 15.2919 141.925,
+                          -85 -26.9349 132.558,
+                          -87 -67 82.5012,
+                          -85 -26.9349 132.558,
+                          -87 -26.9349 132.558,
+                          -87 -7.47399 144.68,
+                          -85 -7.47399 144.68,
+                          -85 15.2919 141.925,
+                          -87 -26.9349 132.558,
+                          -85 -7.47399 144.68,
+                          -87 -7.47399 144.68,
+                          -87 15.2919 141.925,
+                          -85 15.2919 141.925,
+                          -85 31.2997 125.511,
+                          -87 -7.47399 144.68,
+                          -85 15.2919 141.925,
+                          -87 15.2919 141.925,
+                          -87 31.2997 125.511,
+                          -85 31.2997 125.511,
+                          -85 62 59.294,
+                          -87 15.2919 141.925,
+                          -85 31.2997 125.511,
+                          -87 31.2997 125.511,
+                          -87 62 59.294,
+                          -85 62 59.294,
+                          -85 62 5,
+                          -87 31.2997 125.511,
+                          -85 62 59.294,
+                          -87 62 59.294,
+                          -87 62 3,
+                          -87 62 59.294,
+                          -85 62 5,
+                          -77 62 3,
+                          -87 62 3,
+                          -85 62 5,
+                          -77 62 5,
+                          -77 62 3,
+                          -85 62 5,
+                          -87 -67 82.5012,
+                          -87 31.2997 125.511,
+                          -87 62 59.294,
+                          -87 62 3,
+                          -87 -67 82.5012,
+                          -87 62 59.294,
+                          -87 -26.9349 132.558,
+                          -87 15.2919 141.925,
+                          -87 31.2997 125.511,
+                          -87 -67 82.5012,
+                          -87 -26.9349 132.558,
+                          -87 31.2997 125.511,
+                          -87 -26.9349 132.558,
+                          -87 -7.47399 144.68,
+                          -87 15.2919 141.925,
+                          -87 62 3,
+                          -87 -67 3,
+                          -87 -67 82.5012,
+                          -82.8989 -76.8989 3,
+                          -87 -67 82.5012,
+                          -87 -67 3,
+                          -86.3789 -71.1233 77.3496,
+                          -87 -67 82.5012,
+                          -82.8989 -76.8989 3,
+                          -81.4848 -75.4848 3,
+                          -82.8989 -76.8989 3,
+                          -87 -67 3,
+                          -77 62 3,
+                          -77 -62.5 3,
+                          -87 62 3,
+                          -67 -81 3,
+                          -73 -81 3,
+                          -82.8989 -76.8989 3,
+                          -79.6909 -79.2976 73,
+                          -82.8989 -76.8989 3,
+                          -73 -81 3,
+                          -73 -79 3,
+                          -67 -81 3,
+                          -82.8989 -76.8989 3,
+                          -81.4848 -75.4848 3,
+                          -73 -79 3,
+                          -82.8989 -76.8989 3,
+                          -86.3789 -71.1233 77.3496,
+                          -82.8989 -76.8989 3,
+                          -84.7545 -74.6047 73,
+                          -79.6909 -79.2976 73,
+                          -84.7545 -74.6047 73,
+                          -82.8989 -76.8989 3,
+                          -67 -81 73,
+                          -73 -81 3,
+                          -67 -81 3,
+                          -73 -81 73,
+                          -79.6909 -79.2976 73,
+                          -73 -81 3,
+                          -67 -81 73,
+                          -73 -81 73,
+                          -73 -81 3,
+                          -73 -79 3,
+                          -67 -79 3,
+                          -67 -81 3,
+                          -67 -79 73,
+                          -67 -81 3,
+                          -67 -79 3,
+                          -67 -79 73,
+                          -67 -81 73,
+                          -67 -81 3,
+                          -73 -79 73,
+                          -67 -79 3,
+                          -73 -79 3,
+                          -73 -79 73,
+                          -67 -79 73,
+                          -67 -79 3,
+                          -73 -79 73,
+                          -73 -79 3,
+                          -81.4848 -75.4848 3,
+                          -78.1358 -77.8451 73,
+                          -81.4848 -75.4848 3,
+                          -82.2827 -74.6047 73,
+                          -78.1358 -77.8451 73,
+                          -73 -79 73,
+                          -81.4848 -75.4848 3,
+                          -77 -62.5 5,
+                          -77 -62.5 3,
+                          -77 62 3,
+                          -77 -62.5 5,
+                          -77 62 3,
+                          -77 62 5,
+                          -84.7545 -74.6047 73,
+                          -82.2827 -74.6047 73,
+                          -84.2164 -71.2652 77.1723,
+                          -86.3789 -71.1233 77.3496,
+                          -84.7545 -74.6047 73,
+                          -84.2164 -71.2652 77.1723,
+                          -79.6909 -79.2976 73,
+                          -82.2827 -74.6047 73,
+                          -84.7545 -74.6047 73,
+                          -78.1358 -77.8451 73,
+                          -82.2827 -74.6047 73,
+                          -79.6909 -79.2976 73,
+                          -78.1358 -77.8451 73,
+                          -79.6909 -79.2976 73,
+                          -73 -81 73,
+                          -73 -79 73,
+                          -73 -81 73,
+                          -67 -81 73,
+                          -78.1358 -77.8451 73,
+                          -73 -81 73,
+                          -73 -79 73,
+                          -73 -79 73,
+                          -67 -81 73,
+                          -67 -79 73 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/right_arm/underarm_r.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/right_arm/underarm_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..8e3144cbec1a7e5fe9dde8fc7035fe46ca74a01a
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/right_arm/underarm_r.iv
@@ -0,0 +1,554 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+        Units {
+            units MILLIMETERS
+    }
+
+    Material {
+        diffuseColor    0.867564 0.849066 0.868687
+    }
+    Separator {
+        Normal {
+            vector      [ 0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0.999793 0.0203361,
+                          0 0.638971 -0.769231,
+                          0 0.638971 -0.769231,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          0 0 -1,
+                          0 0 -1,
+                          0 0 -1,
+                          0 -0.999793 0.0203361,
+                          0 -0.638971 -0.769231,
+                          0 -0.638971 -0.769231,
+                          0 -0.999793 0.0203361,
+                          0 -0.638971 -0.769231,
+                          0 -0.999793 0.0203361,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.999793 0.0203361,
+                          0 0.999793 0.0203361,
+                          0 0.638971 -0.769231,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0 1,
+                          0 0 1,
+                          0 0 1,
+                          0 1 0,
+                          0 1 0,
+                          0 1 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,
+                          -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,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -2.44921e-16 1,
+                          0 -2.44921e-16 1,
+                          0 -1 -1.83691e-16,
+                          0 1 6.12303e-17,
+                          0 1 6.12303e-17,
+                          0 -1.22461e-16 1,
+                          0 1 6.12303e-17,
+                          0 -1.22461e-16 1,
+                          0 -1.22461e-16 1,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -1 -1.83691e-16,
+                          0 -1 -1.83691e-16,
+                          0 1.22461e-16 -1,
+                          0 -1 -1.83691e-16,
+                          0 -2.44921e-16 1,
+                          0 -1 -1.83691e-16,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 1.22461e-16 -1,
+                          0 1.22461e-16 -1,
+                          0 1 6.12303e-17,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 -1 -1.83691e-16,
+                          0 1.22461e-16 -1,
+                          0 1.22461e-16 -1,
+                          0 1.22461e-16 -1,
+                          0 1 6.12303e-17,
+                          0 1 6.12303e-17,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 0.5 -0.866025,
+                          0 0.6071 0.794625,
+                          0 0.6071 0.794625,
+                          0 0.999793 0.0203361,
+                          1 0 0,
+                          1 0 0,
+                          1 0 0,
+                          0 0.999793 0.0203361,
+                          0 0.6071 0.794625,
+                          0 0.999793 0.0203361,
+                          0 -0.999793 0.0203361,
+                          0 -0.999793 0.0203361,
+                          0 -0.6071 0.794625,
+                          0 -0.5 -0.866025,
+                          0 -0.5 -0.866025,
+                          0 -0.5 -0.866025,
+                          0 -0.5 -0.866025,
+                          0 -0.5 -0.866025,
+                          0 -0.5 -0.866025,
+                          0 -0.999793 0.0203361,
+                          0 -0.6071 0.794625,
+                          0 -0.6071 0.794625,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0,
+                          -1 0 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 22.5 8.30662 -203.5,
+                          -22.5 -8.30662 -203.5,
+                          -22.5 8.30662 -203.5,
+                          -22.5 -12.9968 -193.236,
+                          -22.5 8.30662 -203.5,
+                          -22.5 -8.30662 -203.5,
+                          -22.5 12.9968 -193.236,
+                          22.5 8.30662 -203.5,
+                          -22.5 8.30662 -203.5,
+                          -22.5 2.5 -193.5,
+                          -22.5 8.30662 -203.5,
+                          -22.5 -3.55271e-15 -196,
+                          -22.5 -12.9968 -193.236,
+                          -22.5 -3.55271e-15 -196,
+                          -22.5 8.30662 -203.5,
+                          -22.5 12.9968 -193.236,
+                          -22.5 8.30662 -203.5,
+                          -22.5 2.5 -193.5,
+                          22.5 8.30662 -203.5,
+                          22.5 -8.30662 -203.5,
+                          -22.5 -8.30662 -203.5,
+                          22.5 -12.9968 -193.236,
+                          -22.5 -8.30662 -203.5,
+                          22.5 -8.30662 -203.5,
+                          -22.5 -12.9968 -193.236,
+                          -22.5 -8.30662 -203.5,
+                          22.5 -12.9968 -193.236,
+                          22.5 12.9968 -193.236,
+                          22.5 -8.30662 -203.5,
+                          22.5 8.30662 -203.5,
+                          22.5 -2.5 -193.5,
+                          22.5 -8.30662 -203.5,
+                          22.5 -3.55271e-15 -196,
+                          22.5 12.9968 -193.236,
+                          22.5 -3.55271e-15 -196,
+                          22.5 -8.30662 -203.5,
+                          22.5 -12.9968 -193.236,
+                          22.5 -8.30662 -203.5,
+                          22.5 -2.5 -193.5,
+                          -22.5 12.9968 -193.236,
+                          22.5 12.9968 -193.236,
+                          22.5 8.30662 -203.5,
+                          -22.5 -22.5 0,
+                          22.5 -22.5 0,
+                          22.5 22.5 0,
+                          22.5 -22.5 -174.736,
+                          22.5 22.5 0,
+                          22.5 -22.5 0,
+                          -22.5 22.5 0,
+                          -22.5 -22.5 0,
+                          22.5 22.5 0,
+                          22.5 22.5 -174.736,
+                          -22.5 22.5 0,
+                          22.5 22.5 0,
+                          22.5 -22.5 -174.736,
+                          22.5 22.5 -174.736,
+                          22.5 22.5 0,
+                          -22.5 -22.5 -174.736,
+                          22.5 -22.5 0,
+                          -22.5 -22.5 0,
+                          -22.5 -22.5 -174.736,
+                          22.5 -22.5 -174.736,
+                          22.5 -22.5 0,
+                          -22.5 22.5 -174.736,
+                          -22.5 -22.5 0,
+                          -22.5 22.5 0,
+                          -22.5 22.5 -174.736,
+                          -22.5 -22.5 -174.736,
+                          -22.5 -22.5 0,
+                          -22.5 22.5 -174.736,
+                          -22.5 22.5 0,
+                          22.5 22.5 -174.736,
+                          22.5 12.9968 -193.236,
+                          22.5 2.5 -193.5,
+                          22.5 -3.55271e-15 -196,
+                          -22.5 -3.55271e-15 -196,
+                          22.5 -3.55271e-15 -196,
+                          22.5 2.5 -193.5,
+                          -22.5 -2.5 -193.5,
+                          22.5 -2.5 -193.5,
+                          22.5 -3.55271e-15 -196,
+                          -22.5 -2.5 -193.5,
+                          22.5 -3.55271e-15 -196,
+                          -22.5 -3.55271e-15 -196,
+                          22.5 12.9968 -193.236,
+                          22.5 -3.55271e-15 -191,
+                          22.5 2.5 -193.5,
+                          -22.5 2.5 -193.5,
+                          22.5 2.5 -193.5,
+                          22.5 -3.55271e-15 -191,
+                          -22.5 2.5 -193.5,
+                          -22.5 -3.55271e-15 -196,
+                          22.5 2.5 -193.5,
+                          22.5 -12.9968 -193.236,
+                          22.5 -2.5 -193.5,
+                          22.5 -3.55271e-15 -191,
+                          -22.5 -3.55271e-15 -191,
+                          22.5 -3.55271e-15 -191,
+                          22.5 -2.5 -193.5,
+                          22.5 12.9968 -193.236,
+                          22.5 7.8923 -183.17,
+                          22.5 -3.55271e-15 -191,
+                          22.5 -12.9968 -193.236,
+                          22.5 -3.55271e-15 -191,
+                          22.5 7.8923 -183.17,
+                          -22.5 2.5 -193.5,
+                          22.5 -3.55271e-15 -191,
+                          -22.5 -3.55271e-15 -191,
+                          -22.5 -3.55271e-15 -191,
+                          22.5 -2.5 -193.5,
+                          -22.5 -2.5 -193.5,
+                          22.5 -7.8923 -183.17,
+                          22.5 7.8923 -183.17,
+                          22.5 22.5 -174.736,
+                          -22.5 7.8923 -183.17,
+                          22.5 22.5 -174.736,
+                          22.5 7.8923 -183.17,
+                          22.5 -22.5 -174.736,
+                          22.5 -7.8923 -183.17,
+                          22.5 22.5 -174.736,
+                          -22.5 22.5 -174.736,
+                          22.5 22.5 -174.736,
+                          -22.5 7.8923 -183.17,
+                          -22.5 7.8923 -183.17,
+                          22.5 7.8923 -183.17,
+                          22.5 12.9968 -193.236,
+                          22.5 -7.8923 -183.17,
+                          22.5 -12.9968 -193.236,
+                          22.5 7.8923 -183.17,
+                          -22.5 12.9968 -193.236,
+                          -22.5 7.8923 -183.17,
+                          22.5 12.9968 -193.236,
+                          -22.5 -12.9968 -193.236,
+                          22.5 -12.9968 -193.236,
+                          22.5 -7.8923 -183.17,
+                          -22.5 -22.5 -174.736,
+                          22.5 -7.8923 -183.17,
+                          22.5 -22.5 -174.736,
+                          -22.5 -7.8923 -183.17,
+                          22.5 -7.8923 -183.17,
+                          -22.5 -22.5 -174.736,
+                          -22.5 -12.9968 -193.236,
+                          22.5 -7.8923 -183.17,
+                          -22.5 -7.8923 -183.17,
+                          -22.5 22.5 -174.736,
+                          -22.5 7.8923 -183.17,
+                          -22.5 -22.5 -174.736,
+                          -22.5 -7.8923 -183.17,
+                          -22.5 -22.5 -174.736,
+                          -22.5 7.8923 -183.17,
+                          -22.5 -12.9968 -193.236,
+                          -22.5 -2.5 -193.5,
+                          -22.5 -3.55271e-15 -196,
+                          -22.5 -12.9968 -193.236,
+                          -22.5 -3.55271e-15 -191,
+                          -22.5 -2.5 -193.5,
+                          -22.5 12.9968 -193.236,
+                          -22.5 2.5 -193.5,
+                          -22.5 -3.55271e-15 -191,
+                          -22.5 -12.9968 -193.236,
+                          -22.5 -7.8923 -183.17,
+                          -22.5 -3.55271e-15 -191,
+                          -22.5 12.9968 -193.236,
+                          -22.5 -3.55271e-15 -191,
+                          -22.5 -7.8923 -183.17,
+                          -22.5 12.9968 -193.236,
+                          -22.5 -7.8923 -183.17,
+                          -22.5 7.8923 -183.17 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    1 1 1
+    }
+    Separator {
+        Normal {
+            vector      [ -8.61283e-17 -2.22045e-16 -1,
+                          -8.61283e-17 -2.22045e-16 -1,
+                          -8.61283e-17 -2.22045e-16 -1,
+                          1 -1.43925e-17 -8.61283e-17,
+                          1 -1.43925e-17 -8.61283e-17,
+                          0.707107 0.707107 -3.7492e-16,
+                          -8.61283e-17 -2.22045e-16 -1,
+                          -8.61283e-17 -2.22045e-16 -1,
+                          -8.61283e-17 -2.22045e-16 -1,
+                          -8.61283e-17 -2.22045e-16 -1,
+                          -8.61283e-17 -2.22045e-16 -1,
+                          -8.61283e-17 -2.22045e-16 -1,
+                          0.707107 -0.707107 2.53117e-16,
+                          0.707107 -0.707107 2.53117e-16,
+                          1 -2.59314e-16 -8.61283e-17,
+                          0.707107 -0.707107 2.53117e-16,
+                          1 -2.59314e-16 -8.61283e-17,
+                          1 -2.59314e-16 -8.61283e-17,
+                          -8.61283e-17 -2.22045e-16 -1,
+                          -8.61283e-17 -2.22045e-16 -1,
+                          -8.61283e-17 -2.22045e-16 -1,
+                          0.707107 0.707107 -3.7492e-16,
+                          0.707107 0.707107 -3.7492e-16,
+                          7.56228e-17 1 -4.44089e-16,
+                          0.707107 0.707107 -3.7492e-16,
+                          1 -1.43925e-17 -8.61283e-17,
+                          0.707107 0.707107 -3.7492e-16,
+                          7.56228e-17 1 -4.44089e-16,
+                          7.56228e-17 1 -4.44089e-16,
+                          -0.707107 0.707107 -2.53117e-16,
+                          0.707107 0.707107 -3.7492e-16,
+                          7.56228e-17 1 -4.44089e-16,
+                          7.56228e-17 1 -4.44089e-16,
+                          -0.707107 0.707107 -2.53117e-16,
+                          -0.707107 0.707107 -2.53117e-16,
+                          -1 1.36853e-16 8.61283e-17,
+                          7.56228e-17 1 -4.44089e-16,
+                          -0.707107 0.707107 -2.53117e-16,
+                          -0.707107 0.707107 -2.53117e-16,
+                          -8.61283e-17 -2.22045e-16 -1,
+                          -8.61283e-17 -2.22045e-16 -1,
+                          -8.61283e-17 -2.22045e-16 -1,
+                          -1 1.36853e-16 8.61283e-17,
+                          -1 1.36853e-16 8.61283e-17,
+                          -0.707107 -0.707107 3.7492e-16,
+                          -0.707107 0.707107 -2.53117e-16,
+                          -1 1.36853e-16 8.61283e-17,
+                          -1 1.36853e-16 8.61283e-17,
+                          -8.61283e-17 -2.22045e-16 -1,
+                          -8.61283e-17 -2.22045e-16 -1,
+                          -8.61283e-17 -2.22045e-16 -1,
+                          -0.707107 -0.707107 3.7492e-16,
+                          -0.707107 -0.707107 3.7492e-16,
+                          -1.98083e-16 -1 4.44089e-16,
+                          -1 1.36853e-16 8.61283e-17,
+                          -0.707107 -0.707107 3.7492e-16,
+                          -0.707107 -0.707107 3.7492e-16,
+                          -1.98083e-16 -1 4.44089e-16,
+                          -1.98083e-16 -1 4.44089e-16,
+                          0.707107 -0.707107 2.53117e-16,
+                          -0.707107 -0.707107 3.7492e-16,
+                          -1.98083e-16 -1 4.44089e-16,
+                          -1.98083e-16 -1 4.44089e-16,
+                          -1.98083e-16 -1 4.44089e-16,
+                          0.707107 -0.707107 2.53117e-16,
+                          0.707107 -0.707107 2.53117e-16,
+                          8.61283e-17 2.22045e-16 1,
+                          8.61283e-17 2.22045e-16 1,
+                          8.61283e-17 2.22045e-16 1,
+                          8.61283e-17 2.22045e-16 1,
+                          8.61283e-17 2.22045e-16 1,
+                          8.61283e-17 2.22045e-16 1,
+                          8.61283e-17 2.22045e-16 1,
+                          8.61283e-17 2.22045e-16 1,
+                          8.61283e-17 2.22045e-16 1,
+                          8.61283e-17 2.22045e-16 1,
+                          8.61283e-17 2.22045e-16 1,
+                          8.61283e-17 2.22045e-16 1,
+                          8.61283e-17 2.22045e-16 1,
+                          8.61283e-17 2.22045e-16 1,
+                          8.61283e-17 2.22045e-16 1,
+                          8.61283e-17 2.22045e-16 1,
+                          8.61283e-17 2.22045e-16 1,
+                          8.61283e-17 2.22045e-16 1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -31.7337 34.7337 -166,
+                          34.7337 34.7337 -166,
+                          48.5 1.5 -166,
+                          48.5 1.5 -20,
+                          48.5 1.5 -166,
+                          34.7337 34.7337 -166,
+                          -45.5 1.5 -166,
+                          -31.7337 34.7337 -166,
+                          48.5 1.5 -166,
+                          34.7337 -31.7337 -166,
+                          -45.5 1.5 -166,
+                          48.5 1.5 -166,
+                          34.7337 -31.7337 -20,
+                          34.7337 -31.7337 -166,
+                          48.5 1.5 -166,
+                          34.7337 -31.7337 -20,
+                          48.5 1.5 -166,
+                          48.5 1.5 -20,
+                          -31.7337 34.7337 -166,
+                          1.5 48.5 -166,
+                          34.7337 34.7337 -166,
+                          34.7337 34.7337 -20,
+                          34.7337 34.7337 -166,
+                          1.5 48.5 -166,
+                          34.7337 34.7337 -20,
+                          48.5 1.5 -20,
+                          34.7337 34.7337 -166,
+                          1.5 48.5 -20,
+                          1.5 48.5 -166,
+                          -31.7337 34.7337 -166,
+                          34.7337 34.7337 -20,
+                          1.5 48.5 -166,
+                          1.5 48.5 -20,
+                          -31.7337 34.7337 -20,
+                          -31.7337 34.7337 -166,
+                          -45.5 1.5 -166,
+                          1.5 48.5 -20,
+                          -31.7337 34.7337 -166,
+                          -31.7337 34.7337 -20,
+                          34.7337 -31.7337 -166,
+                          -31.7337 -31.7337 -166,
+                          -45.5 1.5 -166,
+                          -45.5 1.5 -20,
+                          -45.5 1.5 -166,
+                          -31.7337 -31.7337 -166,
+                          -31.7337 34.7337 -20,
+                          -45.5 1.5 -166,
+                          -45.5 1.5 -20,
+                          34.7337 -31.7337 -166,
+                          1.5 -45.5 -166,
+                          -31.7337 -31.7337 -166,
+                          -31.7337 -31.7337 -20,
+                          -31.7337 -31.7337 -166,
+                          1.5 -45.5 -166,
+                          -45.5 1.5 -20,
+                          -31.7337 -31.7337 -166,
+                          -31.7337 -31.7337 -20,
+                          1.5 -45.5 -20,
+                          1.5 -45.5 -166,
+                          34.7337 -31.7337 -166,
+                          -31.7337 -31.7337 -20,
+                          1.5 -45.5 -166,
+                          1.5 -45.5 -20,
+                          1.5 -45.5 -20,
+                          34.7337 -31.7337 -166,
+                          34.7337 -31.7337 -20,
+                          -31.7337 -31.7337 -20,
+                          34.7337 -31.7337 -20,
+                          48.5 1.5 -20,
+                          -45.5 1.5 -20,
+                          -31.7337 -31.7337 -20,
+                          48.5 1.5 -20,
+                          34.7337 34.7337 -20,
+                          -45.5 1.5 -20,
+                          48.5 1.5 -20,
+                          -31.7337 -31.7337 -20,
+                          1.5 -45.5 -20,
+                          34.7337 -31.7337 -20,
+                          34.7337 34.7337 -20,
+                          -31.7337 34.7337 -20,
+                          -45.5 1.5 -20,
+                          34.7337 34.7337 -20,
+                          1.5 48.5 -20,
+                          -31.7337 34.7337 -20 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/right_arm/upperarm_r.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/right_arm/upperarm_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..0cb1611ab809954f443d6f03ba43145c565ea730
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/right_arm/upperarm_r.iv
@@ -0,0 +1,3464 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+
+    Material {
+        diffuseColor    0.62 0.62 0.62
+    }
+    Separator {
+        Normal {
+            vector      [ 2.284e-16 -0.809017 0.587785,
+                          0 -1 1.22461e-16,
+                          0 -1 1.22461e-16,
+                          -2.284e-16 -0.809017 -0.587785,
+                          0 -1 1.22461e-16,
+                          0 -1 1.22461e-16,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -2.284e-16 -0.809017 -0.587785,
+                          -2.284e-16 -0.809017 -0.587785,
+                          0 -1 1.22461e-16,
+                          2.284e-16 -0.809017 0.587785,
+                          2.284e-16 -0.809017 0.587785,
+                          0 -1 1.22461e-16,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          3.6956e-16 -0.309017 0.951057,
+                          3.6956e-16 -0.309017 0.951057,
+                          2.284e-16 -0.809017 0.587785,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          2.284e-16 -0.809017 0.587785,
+                          3.6956e-16 -0.309017 0.951057,
+                          2.284e-16 -0.809017 0.587785,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          3.6956e-16 0.309017 0.951057,
+                          3.6956e-16 0.309017 0.951057,
+                          3.6956e-16 -0.309017 0.951057,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          3.6956e-16 -0.309017 0.951057,
+                          3.6956e-16 0.309017 0.951057,
+                          3.6956e-16 -0.309017 0.951057,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          2.284e-16 0.809017 0.587785,
+                          2.284e-16 0.809017 0.587785,
+                          3.6956e-16 0.309017 0.951057,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          3.6956e-16 0.309017 0.951057,
+                          2.284e-16 0.809017 0.587785,
+                          3.6956e-16 0.309017 0.951057,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          0 1 0,
+                          0 1 0,
+                          2.284e-16 0.809017 0.587785,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          2.284e-16 0.809017 0.587785,
+                          0 1 0,
+                          2.284e-16 0.809017 0.587785,
+                          -2.284e-16 0.809017 -0.587785,
+                          0 1 -2.44921e-16,
+                          0 1 -2.44921e-16,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          -2.284e-16 0.809017 -0.587785,
+                          0 1 -2.44921e-16,
+                          -2.284e-16 0.809017 -0.587785,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          0 1 -1.22461e-16,
+                          0 1 -1.22461e-16,
+                          -1.68598e-16 0.900969 -0.433884,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1.68598e-16 0.900969 0.433884,
+                          1.68598e-16 0.900969 0.433884,
+                          0 1 -1.22461e-16,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1.68598e-16 0.900969 0.433884,
+                          0 1 -1.22461e-16,
+                          0 1 -1.22461e-16,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          -1.68598e-16 0.900969 -0.433884,
+                          -1.68598e-16 0.900969 -0.433884,
+                          -3.03803e-16 0.62349 -0.781832,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          -1.68598e-16 0.900969 -0.433884,
+                          0 1 -1.22461e-16,
+                          -1.68598e-16 0.900969 -0.433884,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          -3.03803e-16 0.62349 -0.781832,
+                          -3.03803e-16 0.62349 -0.781832,
+                          -3.78836e-16 0.222521 -0.974928,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          -3.03803e-16 0.62349 -0.781832,
+                          -1.68598e-16 0.900969 -0.433884,
+                          -3.03803e-16 0.62349 -0.781832,
+                          -3.78836e-16 0.222521 -0.974928,
+                          -3.78836e-16 0.222521 -0.974928,
+                          -3.78836e-16 -0.222521 -0.974928,
+                          -3.78836e-16 0.222521 -0.974928,
+                          -3.03803e-16 0.62349 -0.781832,
+                          -3.78836e-16 0.222521 -0.974928,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          -3.78836e-16 -0.222521 -0.974928,
+                          -3.78836e-16 -0.222521 -0.974928,
+                          -3.03803e-16 -0.62349 -0.781832,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          -3.78836e-16 -0.222521 -0.974928,
+                          -3.78836e-16 0.222521 -0.974928,
+                          -3.78836e-16 -0.222521 -0.974928,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          -3.03803e-16 -0.62349 -0.781832,
+                          -3.03803e-16 -0.62349 -0.781832,
+                          -1.68598e-16 -0.900969 -0.433884,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          -3.03803e-16 -0.62349 -0.781832,
+                          -3.78836e-16 -0.222521 -0.974928,
+                          -3.03803e-16 -0.62349 -0.781832,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          -1.68598e-16 -0.900969 -0.433884,
+                          -1.68598e-16 -0.900969 -0.433884,
+                          0 -1 0,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          -1.68598e-16 -0.900969 -0.433884,
+                          -3.03803e-16 -0.62349 -0.781832,
+                          -1.68598e-16 -0.900969 -0.433884,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          0 -1 2.44921e-16,
+                          0 -1 2.44921e-16,
+                          1.68598e-16 -0.900969 0.433884,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          0 -1 0,
+                          -1.68598e-16 -0.900969 -0.433884,
+                          0 -1 0,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1.68598e-16 -0.900969 0.433884,
+                          1.68598e-16 -0.900969 0.433884,
+                          3.03803e-16 -0.62349 0.781832,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1.68598e-16 -0.900969 0.433884,
+                          0 -1 2.44921e-16,
+                          1.68598e-16 -0.900969 0.433884,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          3.03803e-16 -0.62349 0.781832,
+                          3.03803e-16 -0.62349 0.781832,
+                          3.78836e-16 -0.222521 0.974928,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1.68598e-16 -0.900969 0.433884,
+                          3.03803e-16 -0.62349 0.781832,
+                          3.03803e-16 -0.62349 0.781832,
+                          3.78836e-16 -0.222521 0.974928,
+                          3.78836e-16 -0.222521 0.974928,
+                          3.78836e-16 0.222521 0.974928,
+                          3.03803e-16 -0.62349 0.781832,
+                          3.78836e-16 -0.222521 0.974928,
+                          3.78836e-16 -0.222521 0.974928,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          3.78836e-16 0.222521 0.974928,
+                          3.78836e-16 0.222521 0.974928,
+                          3.03803e-16 0.62349 0.781832,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          3.78836e-16 -0.222521 0.974928,
+                          3.78836e-16 0.222521 0.974928,
+                          3.78836e-16 0.222521 0.974928,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          3.03803e-16 0.62349 0.781832,
+                          3.03803e-16 0.62349 0.781832,
+                          1.68598e-16 0.900969 0.433884,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          3.78836e-16 0.222521 0.974928,
+                          3.03803e-16 0.62349 0.781832,
+                          3.03803e-16 0.62349 0.781832,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          3.03803e-16 0.62349 0.781832,
+                          1.68598e-16 0.900969 0.433884,
+                          1.68598e-16 0.900969 0.433884,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -2.284e-16 0.809017 -0.587785,
+                          -2.284e-16 0.809017 -0.587785,
+                          -3.6956e-16 0.309017 -0.951057,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -3.6956e-16 0.309017 -0.951057,
+                          -3.6956e-16 0.309017 -0.951057,
+                          -3.6956e-16 -0.309017 -0.951057,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -3.6956e-16 0.309017 -0.951057,
+                          -2.284e-16 0.809017 -0.587785,
+                          -3.6956e-16 0.309017 -0.951057,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -3.6956e-16 -0.309017 -0.951057,
+                          -3.6956e-16 -0.309017 -0.951057,
+                          -2.284e-16 -0.809017 -0.587785,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -3.6956e-16 -0.309017 -0.951057,
+                          -3.6956e-16 0.309017 -0.951057,
+                          -3.6956e-16 -0.309017 -0.951057,
+                          -2.284e-16 -0.809017 -0.587785,
+                          -3.6956e-16 -0.309017 -0.951057,
+                          -2.284e-16 -0.809017 -0.587785,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -72.5 14.9668 -10.874,
+                          -69.5 18.5 7.43738e-14,
+                          -72.5 18.5 7.45404e-14,
+                          -69.5 14.9668 10.874,
+                          -72.5 18.5 7.45404e-14,
+                          -69.5 18.5 7.43738e-14,
+                          -72.5 34.237 -16.4872,
+                          -72.5 14.9668 -10.874,
+                          -72.5 18.5 7.45404e-14,
+                          -72.5 34.237 -16.4872,
+                          -72.5 18.5 7.45404e-14,
+                          -72.5 38 7.45404e-14,
+                          -72.5 14.9668 10.874,
+                          -72.5 38 7.45404e-14,
+                          -72.5 18.5 7.45404e-14,
+                          -69.5 14.9668 10.874,
+                          -72.5 14.9668 10.874,
+                          -72.5 18.5 7.45404e-14,
+                          -72.5 14.9668 -10.874,
+                          -69.5 14.9668 -10.874,
+                          -69.5 18.5 7.43738e-14,
+                          -69.5 33.5 7.43738e-14,
+                          -69.5 18.5 7.43738e-14,
+                          -69.5 14.9668 -10.874,
+                          -69.5 30.1822 14.5355,
+                          -69.5 18.5 7.43738e-14,
+                          -69.5 33.5 7.43738e-14,
+                          -69.5 14.9668 10.874,
+                          -69.5 18.5 7.43738e-14,
+                          -69.5 30.1822 14.5355,
+                          -72.5 5.71681 -17.5945,
+                          -69.5 5.71681 -17.5945,
+                          -69.5 14.9668 -10.874,
+                          -69.5 30.1822 -14.5355,
+                          -69.5 14.9668 -10.874,
+                          -69.5 5.71681 -17.5945,
+                          -72.5 14.9668 -10.874,
+                          -72.5 5.71681 -17.5945,
+                          -69.5 14.9668 -10.874,
+                          -69.5 30.1822 -14.5355,
+                          -69.5 33.5 7.43738e-14,
+                          -69.5 14.9668 -10.874,
+                          -72.5 -5.71681 -17.5945,
+                          -69.5 -5.71681 -17.5945,
+                          -69.5 5.71681 -17.5945,
+                          -69.5 -20.887 -26.1912,
+                          -69.5 5.71681 -17.5945,
+                          -69.5 -5.71681 -17.5945,
+                          -72.5 5.71681 -17.5945,
+                          -72.5 -5.71681 -17.5945,
+                          -69.5 5.71681 -17.5945,
+                          -69.5 30.1822 -14.5355,
+                          -69.5 5.71681 -17.5945,
+                          -69.5 -20.887 -26.1912,
+                          -72.5 -14.9668 -10.874,
+                          -69.5 -14.9668 -10.874,
+                          -69.5 -5.71681 -17.5945,
+                          -69.5 -30.1822 -14.5355,
+                          -69.5 -5.71681 -17.5945,
+                          -69.5 -14.9668 -10.874,
+                          -72.5 -5.71681 -17.5945,
+                          -72.5 -14.9668 -10.874,
+                          -69.5 -5.71681 -17.5945,
+                          -69.5 -20.887 -26.1912,
+                          -69.5 -5.71681 -17.5945,
+                          -69.5 -30.1822 -14.5355,
+                          -72.5 -18.5 7.45404e-14,
+                          -69.5 -18.5 7.43738e-14,
+                          -69.5 -14.9668 -10.874,
+                          -69.5 -30.1822 -14.5355,
+                          -69.5 -14.9668 -10.874,
+                          -69.5 -18.5 7.43738e-14,
+                          -72.5 -14.9668 -10.874,
+                          -72.5 -18.5 7.45404e-14,
+                          -69.5 -14.9668 -10.874,
+                          -72.5 -14.9668 10.874,
+                          -69.5 -18.5 7.43738e-14,
+                          -72.5 -18.5 7.45404e-14,
+                          -69.5 -30.1822 -14.5355,
+                          -69.5 -18.5 7.43738e-14,
+                          -69.5 -33.5 7.43738e-14,
+                          -69.5 -14.9668 10.874,
+                          -69.5 -33.5 7.43738e-14,
+                          -69.5 -18.5 7.43738e-14,
+                          -69.5 -14.9668 10.874,
+                          -69.5 -18.5 7.43738e-14,
+                          -72.5 -14.9668 10.874,
+                          -72.5 -38 7.45404e-14,
+                          -72.5 -18.5 7.45404e-14,
+                          -72.5 -14.9668 -10.874,
+                          -72.5 -34.237 16.4872,
+                          -72.5 -18.5 7.45404e-14,
+                          -72.5 -38 7.45404e-14,
+                          -72.5 -34.237 16.4872,
+                          -72.5 -14.9668 10.874,
+                          -72.5 -18.5 7.45404e-14,
+                          -72.5 -34.237 -16.4872,
+                          -72.5 -14.9668 -10.874,
+                          -72.5 -5.71681 -17.5945,
+                          -72.5 -38 7.45404e-14,
+                          -72.5 -14.9668 -10.874,
+                          -72.5 -34.237 -16.4872,
+                          -72.5 23.6929 -29.7093,
+                          -72.5 -5.71681 -17.5945,
+                          -72.5 5.71681 -17.5945,
+                          -72.5 -34.237 -16.4872,
+                          -72.5 -5.71681 -17.5945,
+                          -72.5 23.6929 -29.7093,
+                          -72.5 34.237 -16.4872,
+                          -72.5 5.71681 -17.5945,
+                          -72.5 14.9668 -10.874,
+                          -72.5 23.6929 -29.7093,
+                          -72.5 5.71681 -17.5945,
+                          -72.5 34.237 -16.4872,
+                          -69.5 30.1822 -14.5355,
+                          -69.5 34.237 -16.4872,
+                          -69.5 38 7.43738e-14,
+                          -72.5 38 7.45404e-14,
+                          -69.5 38 7.43738e-14,
+                          -69.5 34.237 -16.4872,
+                          -69.5 33.5 7.43738e-14,
+                          -69.5 38 7.43738e-14,
+                          -69.5 34.237 16.4872,
+                          -72.5 34.237 16.4872,
+                          -69.5 34.237 16.4872,
+                          -69.5 38 7.43738e-14,
+                          -69.5 30.1822 -14.5355,
+                          -69.5 38 7.43738e-14,
+                          -69.5 33.5 7.43738e-14,
+                          -72.5 34.237 16.4872,
+                          -69.5 38 7.43738e-14,
+                          -72.5 38 7.45404e-14,
+                          -69.5 20.887 -26.1912,
+                          -69.5 23.6929 -29.7093,
+                          -69.5 34.237 -16.4872,
+                          -72.5 34.237 -16.4872,
+                          -69.5 34.237 -16.4872,
+                          -69.5 23.6929 -29.7093,
+                          -69.5 30.1822 -14.5355,
+                          -69.5 20.887 -26.1912,
+                          -69.5 34.237 -16.4872,
+                          -72.5 34.237 -16.4872,
+                          -72.5 38 7.45404e-14,
+                          -69.5 34.237 -16.4872,
+                          -69.5 -8.45593 -37.0472,
+                          -69.5 8.45593 -37.0472,
+                          -69.5 23.6929 -29.7093,
+                          -72.5 23.6929 -29.7093,
+                          -69.5 23.6929 -29.7093,
+                          -69.5 8.45593 -37.0472,
+                          -69.5 7.45486 -32.66,
+                          -69.5 -8.45593 -37.0472,
+                          -69.5 23.6929 -29.7093,
+                          -69.5 20.887 -26.1912,
+                          -69.5 7.45486 -32.66,
+                          -69.5 23.6929 -29.7093,
+                          -72.5 23.6929 -29.7093,
+                          -72.5 34.237 -16.4872,
+                          -69.5 23.6929 -29.7093,
+                          -72.5 8.45593 -37.0472,
+                          -69.5 8.45593 -37.0472,
+                          -69.5 -8.45593 -37.0472,
+                          -72.5 8.45593 -37.0472,
+                          -72.5 23.6929 -29.7093,
+                          -69.5 8.45593 -37.0472,
+                          -69.5 -7.45486 -32.66,
+                          -69.5 -23.6929 -29.7093,
+                          -69.5 -8.45593 -37.0472,
+                          -72.5 -8.45593 -37.0472,
+                          -69.5 -8.45593 -37.0472,
+                          -69.5 -23.6929 -29.7093,
+                          -69.5 7.45486 -32.66,
+                          -69.5 -7.45486 -32.66,
+                          -69.5 -8.45593 -37.0472,
+                          -72.5 -8.45593 -37.0472,
+                          -72.5 8.45593 -37.0472,
+                          -69.5 -8.45593 -37.0472,
+                          -69.5 -20.887 -26.1912,
+                          -69.5 -34.237 -16.4872,
+                          -69.5 -23.6929 -29.7093,
+                          -72.5 -23.6929 -29.7093,
+                          -69.5 -23.6929 -29.7093,
+                          -69.5 -34.237 -16.4872,
+                          -69.5 -7.45486 -32.66,
+                          -69.5 -20.887 -26.1912,
+                          -69.5 -23.6929 -29.7093,
+                          -72.5 -23.6929 -29.7093,
+                          -72.5 -8.45593 -37.0472,
+                          -69.5 -23.6929 -29.7093,
+                          -69.5 -33.5 7.43738e-14,
+                          -69.5 -38 7.43738e-14,
+                          -69.5 -34.237 -16.4872,
+                          -72.5 -34.237 -16.4872,
+                          -69.5 -34.237 -16.4872,
+                          -69.5 -38 7.43738e-14,
+                          -69.5 -30.1822 -14.5355,
+                          -69.5 -33.5 7.43738e-14,
+                          -69.5 -34.237 -16.4872,
+                          -69.5 -20.887 -26.1912,
+                          -69.5 -30.1822 -14.5355,
+                          -69.5 -34.237 -16.4872,
+                          -72.5 -34.237 -16.4872,
+                          -72.5 -23.6929 -29.7093,
+                          -69.5 -34.237 -16.4872,
+                          -69.5 -30.1822 14.5355,
+                          -69.5 -34.237 16.4872,
+                          -69.5 -38 7.43738e-14,
+                          -72.5 -38 7.45404e-14,
+                          -69.5 -38 7.43738e-14,
+                          -69.5 -34.237 16.4872,
+                          -69.5 -33.5 7.43738e-14,
+                          -69.5 -30.1822 14.5355,
+                          -69.5 -38 7.43738e-14,
+                          -72.5 -38 7.45404e-14,
+                          -72.5 -34.237 -16.4872,
+                          -69.5 -38 7.43738e-14,
+                          -69.5 -20.887 26.1912,
+                          -69.5 -23.6929 29.7093,
+                          -69.5 -34.237 16.4872,
+                          -72.5 -34.237 16.4872,
+                          -69.5 -34.237 16.4872,
+                          -69.5 -23.6929 29.7093,
+                          -69.5 -30.1822 14.5355,
+                          -69.5 -20.887 26.1912,
+                          -69.5 -34.237 16.4872,
+                          -72.5 -34.237 16.4872,
+                          -72.5 -38 7.45404e-14,
+                          -69.5 -34.237 16.4872,
+                          -69.5 8.45593 37.0472,
+                          -69.5 -8.45593 37.0472,
+                          -69.5 -23.6929 29.7093,
+                          -72.5 -23.6929 29.7093,
+                          -69.5 -23.6929 29.7093,
+                          -69.5 -8.45593 37.0472,
+                          -69.5 -7.45486 32.66,
+                          -69.5 8.45593 37.0472,
+                          -69.5 -23.6929 29.7093,
+                          -69.5 -20.887 26.1912,
+                          -69.5 -7.45486 32.66,
+                          -69.5 -23.6929 29.7093,
+                          -72.5 -34.237 16.4872,
+                          -69.5 -23.6929 29.7093,
+                          -72.5 -23.6929 29.7093,
+                          -72.5 -8.45593 37.0472,
+                          -69.5 -8.45593 37.0472,
+                          -69.5 8.45593 37.0472,
+                          -72.5 -23.6929 29.7093,
+                          -69.5 -8.45593 37.0472,
+                          -72.5 -8.45593 37.0472,
+                          -69.5 7.45486 32.66,
+                          -69.5 23.6929 29.7093,
+                          -69.5 8.45593 37.0472,
+                          -72.5 8.45593 37.0472,
+                          -69.5 8.45593 37.0472,
+                          -69.5 23.6929 29.7093,
+                          -69.5 -7.45486 32.66,
+                          -69.5 7.45486 32.66,
+                          -69.5 8.45593 37.0472,
+                          -72.5 -8.45593 37.0472,
+                          -69.5 8.45593 37.0472,
+                          -72.5 8.45593 37.0472,
+                          -69.5 20.887 26.1912,
+                          -69.5 34.237 16.4872,
+                          -69.5 23.6929 29.7093,
+                          -72.5 23.6929 29.7093,
+                          -69.5 23.6929 29.7093,
+                          -69.5 34.237 16.4872,
+                          -69.5 7.45486 32.66,
+                          -69.5 20.887 26.1912,
+                          -69.5 23.6929 29.7093,
+                          -72.5 8.45593 37.0472,
+                          -69.5 23.6929 29.7093,
+                          -72.5 23.6929 29.7093,
+                          -69.5 30.1822 14.5355,
+                          -69.5 33.5 7.43738e-14,
+                          -69.5 34.237 16.4872,
+                          -69.5 20.887 26.1912,
+                          -69.5 30.1822 14.5355,
+                          -69.5 34.237 16.4872,
+                          -72.5 23.6929 29.7093,
+                          -69.5 34.237 16.4872,
+                          -72.5 34.237 16.4872,
+                          -69.5 5.71681 17.5945,
+                          -69.5 30.1822 14.5355,
+                          -69.5 20.887 26.1912,
+                          -69.5 14.9668 10.874,
+                          -69.5 30.1822 14.5355,
+                          -69.5 5.71681 17.5945,
+                          -69.5 -20.887 26.1912,
+                          -69.5 20.887 26.1912,
+                          -69.5 7.45486 32.66,
+                          -69.5 -30.1822 14.5355,
+                          -69.5 20.887 26.1912,
+                          -69.5 -20.887 26.1912,
+                          -69.5 -5.71681 17.5945,
+                          -69.5 20.887 26.1912,
+                          -69.5 -30.1822 14.5355,
+                          -69.5 5.71681 17.5945,
+                          -69.5 20.887 26.1912,
+                          -69.5 -5.71681 17.5945,
+                          -69.5 -20.887 26.1912,
+                          -69.5 7.45486 32.66,
+                          -69.5 -7.45486 32.66,
+                          -69.5 -14.9668 10.874,
+                          -69.5 -30.1822 14.5355,
+                          -69.5 -33.5 7.43738e-14,
+                          -69.5 -5.71681 17.5945,
+                          -69.5 -30.1822 14.5355,
+                          -69.5 -14.9668 10.874,
+                          -69.5 20.887 -26.1912,
+                          -69.5 -20.887 -26.1912,
+                          -69.5 -7.45486 -32.66,
+                          -69.5 30.1822 -14.5355,
+                          -69.5 -20.887 -26.1912,
+                          -69.5 20.887 -26.1912,
+                          -69.5 20.887 -26.1912,
+                          -69.5 -7.45486 -32.66,
+                          -69.5 7.45486 -32.66,
+                          -72.5 34.237 16.4872,
+                          -72.5 38 7.45404e-14,
+                          -72.5 14.9668 10.874,
+                          -72.5 -23.6929 -29.7093,
+                          -72.5 23.6929 -29.7093,
+                          -72.5 8.45593 -37.0472,
+                          -72.5 -34.237 -16.4872,
+                          -72.5 23.6929 -29.7093,
+                          -72.5 -23.6929 -29.7093,
+                          -72.5 -23.6929 -29.7093,
+                          -72.5 8.45593 -37.0472,
+                          -72.5 -8.45593 -37.0472,
+                          -72.5 -34.237 16.4872,
+                          -72.5 -5.71681 17.5945,
+                          -72.5 -14.9668 10.874,
+                          -69.5 -14.9668 10.874,
+                          -72.5 -14.9668 10.874,
+                          -72.5 -5.71681 17.5945,
+                          -72.5 -23.6929 29.7093,
+                          -72.5 5.71681 17.5945,
+                          -72.5 -5.71681 17.5945,
+                          -69.5 -5.71681 17.5945,
+                          -72.5 -5.71681 17.5945,
+                          -72.5 5.71681 17.5945,
+                          -72.5 -34.237 16.4872,
+                          -72.5 -23.6929 29.7093,
+                          -72.5 -5.71681 17.5945,
+                          -69.5 -5.71681 17.5945,
+                          -69.5 -14.9668 10.874,
+                          -72.5 -5.71681 17.5945,
+                          -72.5 34.237 16.4872,
+                          -72.5 14.9668 10.874,
+                          -72.5 5.71681 17.5945,
+                          -69.5 5.71681 17.5945,
+                          -72.5 5.71681 17.5945,
+                          -72.5 14.9668 10.874,
+                          -72.5 -23.6929 29.7093,
+                          -72.5 34.237 16.4872,
+                          -72.5 5.71681 17.5945,
+                          -69.5 5.71681 17.5945,
+                          -69.5 -5.71681 17.5945,
+                          -72.5 5.71681 17.5945,
+                          -69.5 14.9668 10.874,
+                          -69.5 5.71681 17.5945,
+                          -72.5 14.9668 10.874,
+                          -72.5 -23.6929 29.7093,
+                          -72.5 23.6929 29.7093,
+                          -72.5 34.237 16.4872,
+                          -72.5 -8.45593 37.0472,
+                          -72.5 8.45593 37.0472,
+                          -72.5 23.6929 29.7093,
+                          -72.5 -23.6929 29.7093,
+                          -72.5 -8.45593 37.0472,
+                          -72.5 23.6929 29.7093 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+    Separator {
+        Normal {
+            vector      [ 1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          -3.88578e-16 1.42779e-16 -1,
+                          -3.88578e-16 1.42779e-16 -1,
+                          -3.14366e-16 -0.587785 -0.809017,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          -3.14366e-16 0.587785 -0.809017,
+                          -3.14366e-16 0.587785 -0.809017,
+                          -3.88578e-16 1.42779e-16 -1,
+                          -3.14366e-16 0.587785 -0.809017,
+                          -3.88578e-16 1.42779e-16 -1,
+                          -3.88578e-16 1.42779e-16 -1,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          -3.14366e-16 -0.587785 -0.809017,
+                          -3.14366e-16 -0.587785 -0.809017,
+                          -1.20077e-16 -0.951057 -0.309017,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          -3.14366e-16 -0.587785 -0.809017,
+                          -3.88578e-16 1.42779e-16 -1,
+                          -3.14366e-16 -0.587785 -0.809017,
+                          -1.20077e-16 -0.951057 -0.309017,
+                          -1.20077e-16 -0.951057 -0.309017,
+                          1.20077e-16 -0.951057 0.309017,
+                          -3.14366e-16 -0.587785 -0.809017,
+                          -1.20077e-16 -0.951057 -0.309017,
+                          -1.20077e-16 -0.951057 -0.309017,
+                          1.20077e-16 -0.951057 0.309017,
+                          1.20077e-16 -0.951057 0.309017,
+                          3.14366e-16 -0.587785 0.809017,
+                          -1.20077e-16 -0.951057 -0.309017,
+                          1.20077e-16 -0.951057 0.309017,
+                          1.20077e-16 -0.951057 0.309017,
+                          3.14366e-16 -0.587785 0.809017,
+                          3.14366e-16 -0.587785 0.809017,
+                          3.88578e-16 -2.6524e-16 1,
+                          1.20077e-16 -0.951057 0.309017,
+                          3.14366e-16 -0.587785 0.809017,
+                          3.14366e-16 -0.587785 0.809017,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          3.88578e-16 -2.03185e-17 1,
+                          3.88578e-16 -2.03185e-17 1,
+                          3.14366e-16 0.587785 0.809017,
+                          3.14366e-16 -0.587785 0.809017,
+                          3.88578e-16 -2.6524e-16 1,
+                          3.88578e-16 -2.6524e-16 1,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          3.14366e-16 0.587785 0.809017,
+                          3.14366e-16 0.587785 0.809017,
+                          1.20077e-16 0.951057 0.309017,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          3.88578e-16 -2.03185e-17 1,
+                          3.14366e-16 0.587785 0.809017,
+                          3.14366e-16 0.587785 0.809017,
+                          1.20077e-16 0.951057 0.309017,
+                          1.20077e-16 0.951057 0.309017,
+                          -1.20077e-16 0.951057 -0.309017,
+                          3.14366e-16 0.587785 0.809017,
+                          1.20077e-16 0.951057 0.309017,
+                          1.20077e-16 0.951057 0.309017,
+                          -1.20077e-16 0.951057 -0.309017,
+                          -1.20077e-16 0.951057 -0.309017,
+                          -3.14366e-16 0.587785 -0.809017,
+                          1.20077e-16 0.951057 0.309017,
+                          -1.20077e-16 0.951057 -0.309017,
+                          -1.20077e-16 0.951057 -0.309017,
+                          -1.20077e-16 0.951057 -0.309017,
+                          -3.14366e-16 0.587785 -0.809017,
+                          -3.14366e-16 0.587785 -0.809017,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -3.88578e-16 1.42779e-16 -1,
+                          -3.88578e-16 1.42779e-16 -1,
+                          -3.14366e-16 0.587785 -0.809017,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -3.14366e-16 -0.587785 -0.809017,
+                          -3.14366e-16 -0.587785 -0.809017,
+                          -3.88578e-16 1.42779e-16 -1,
+                          -3.14366e-16 -0.587785 -0.809017,
+                          -3.88578e-16 1.42779e-16 -1,
+                          -3.88578e-16 1.42779e-16 -1,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -3.14366e-16 0.587785 -0.809017,
+                          -3.14366e-16 0.587785 -0.809017,
+                          -1.20077e-16 0.951057 -0.309017,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -3.14366e-16 0.587785 -0.809017,
+                          -3.88578e-16 1.42779e-16 -1,
+                          -3.14366e-16 0.587785 -0.809017,
+                          -1.20077e-16 0.951057 -0.309017,
+                          -1.20077e-16 0.951057 -0.309017,
+                          1.20077e-16 0.951057 0.309017,
+                          -1.20077e-16 0.951057 -0.309017,
+                          -3.14366e-16 0.587785 -0.809017,
+                          -1.20077e-16 0.951057 -0.309017,
+                          1.20077e-16 0.951057 0.309017,
+                          1.20077e-16 0.951057 0.309017,
+                          3.14366e-16 0.587785 0.809017,
+                          1.20077e-16 0.951057 0.309017,
+                          -1.20077e-16 0.951057 -0.309017,
+                          1.20077e-16 0.951057 0.309017,
+                          3.14366e-16 0.587785 0.809017,
+                          3.14366e-16 0.587785 0.809017,
+                          3.88578e-16 -2.03185e-17 1,
+                          3.14366e-16 0.587785 0.809017,
+                          1.20077e-16 0.951057 0.309017,
+                          3.14366e-16 0.587785 0.809017,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          3.88578e-16 -2.6524e-16 1,
+                          3.88578e-16 -2.6524e-16 1,
+                          3.14366e-16 -0.587785 0.809017,
+                          3.88578e-16 -2.03185e-17 1,
+                          3.14366e-16 0.587785 0.809017,
+                          3.88578e-16 -2.03185e-17 1,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          3.14366e-16 -0.587785 0.809017,
+                          3.14366e-16 -0.587785 0.809017,
+                          1.20077e-16 -0.951057 0.309017,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          3.14366e-16 -0.587785 0.809017,
+                          3.88578e-16 -2.6524e-16 1,
+                          3.14366e-16 -0.587785 0.809017,
+                          1.20077e-16 -0.951057 0.309017,
+                          1.20077e-16 -0.951057 0.309017,
+                          -1.20077e-16 -0.951057 -0.309017,
+                          1.20077e-16 -0.951057 0.309017,
+                          3.14366e-16 -0.587785 0.809017,
+                          1.20077e-16 -0.951057 0.309017,
+                          -1.20077e-16 -0.951057 -0.309017,
+                          -1.20077e-16 -0.951057 -0.309017,
+                          -3.14366e-16 -0.587785 -0.809017,
+                          -1.20077e-16 -0.951057 -0.309017,
+                          1.20077e-16 -0.951057 0.309017,
+                          -1.20077e-16 -0.951057 -0.309017,
+                          -3.14366e-16 -0.587785 -0.809017,
+                          -1.20077e-16 -0.951057 -0.309017,
+                          -3.14366e-16 -0.587785 -0.809017 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 0 -9.11272 12.5378,
+                          0 -9.11272 -12.5378,
+                          0 -9.00211e-14 -15.5,
+                          -159.7 -7.60129e-14 -15.5,
+                          0 -9.00211e-14 -15.5,
+                          0 -9.11272 -12.5378,
+                          0 -9.06509e-14 15.5,
+                          0 -9.11272 12.5378,
+                          0 -9.00211e-14 -15.5,
+                          0 9.11272 -12.5378,
+                          0 -9.06509e-14 15.5,
+                          0 -9.00211e-14 -15.5,
+                          -159.7 9.11067 -12.5398,
+                          0 9.11272 -12.5378,
+                          0 -9.00211e-14 -15.5,
+                          -159.7 9.11067 -12.5398,
+                          0 -9.00211e-14 -15.5,
+                          -159.7 -7.60129e-14 -15.5,
+                          0 -14.741 4.78816,
+                          0 -14.741 -4.78816,
+                          0 -9.11272 -12.5378,
+                          -159.7 -9.11067 -12.5398,
+                          0 -9.11272 -12.5378,
+                          0 -14.741 -4.78816,
+                          0 -9.11272 12.5378,
+                          0 -14.741 4.78816,
+                          0 -9.11272 -12.5378,
+                          -159.7 -9.11067 -12.5398,
+                          -159.7 -7.60129e-14 -15.5,
+                          0 -9.11272 -12.5378,
+                          -159.7 -14.7414 -4.78976,
+                          0 -14.741 -4.78816,
+                          0 -14.741 4.78816,
+                          -159.7 -9.11067 -12.5398,
+                          0 -14.741 -4.78816,
+                          -159.7 -14.7414 -4.78976,
+                          -159.7 -14.7414 4.78976,
+                          0 -14.741 4.78816,
+                          0 -9.11272 12.5378,
+                          -159.7 -14.7414 -4.78976,
+                          0 -14.741 4.78816,
+                          -159.7 -14.7414 4.78976,
+                          -159.7 -9.11067 12.5398,
+                          0 -9.11272 12.5378,
+                          0 -9.06509e-14 15.5,
+                          -159.7 -14.7414 4.78976,
+                          0 -9.11272 12.5378,
+                          -159.7 -9.11067 12.5398,
+                          0 9.11272 -12.5378,
+                          0 9.11272 12.5378,
+                          0 -9.06509e-14 15.5,
+                          -159.7 -7.85409e-14 15.5,
+                          0 -9.06509e-14 15.5,
+                          0 9.11272 12.5378,
+                          -159.7 -9.11067 12.5398,
+                          0 -9.06509e-14 15.5,
+                          -159.7 -7.85409e-14 15.5,
+                          0 14.741 -4.78816,
+                          0 14.741 4.78816,
+                          0 9.11272 12.5378,
+                          -159.7 9.11067 12.5398,
+                          0 9.11272 12.5378,
+                          0 14.741 4.78816,
+                          0 9.11272 -12.5378,
+                          0 14.741 -4.78816,
+                          0 9.11272 12.5378,
+                          -159.7 -7.85409e-14 15.5,
+                          0 9.11272 12.5378,
+                          -159.7 9.11067 12.5398,
+                          -159.7 14.7414 4.78976,
+                          0 14.741 4.78816,
+                          0 14.741 -4.78816,
+                          -159.7 9.11067 12.5398,
+                          0 14.741 4.78816,
+                          -159.7 14.7414 4.78976,
+                          -159.7 14.7414 -4.78976,
+                          0 14.741 -4.78816,
+                          0 9.11272 -12.5378,
+                          -159.7 14.7414 4.78976,
+                          0 14.741 -4.78816,
+                          -159.7 14.7414 -4.78976,
+                          -159.7 14.7414 -4.78976,
+                          0 9.11272 -12.5378,
+                          -159.7 9.11067 -12.5398,
+                          -234.7 9.11272 12.5378,
+                          -234.7 9.11272 -12.5378,
+                          -234.7 -7.22238e-14 -15.5,
+                          -159.7 -7.60129e-14 -15.5,
+                          -234.7 -7.22238e-14 -15.5,
+                          -234.7 9.11272 -12.5378,
+                          -234.7 -7.28537e-14 15.5,
+                          -234.7 9.11272 12.5378,
+                          -234.7 -7.22238e-14 -15.5,
+                          -234.7 -9.11272 -12.5378,
+                          -234.7 -7.28537e-14 15.5,
+                          -234.7 -7.22238e-14 -15.5,
+                          -159.7 -9.11067 -12.5398,
+                          -234.7 -9.11272 -12.5378,
+                          -234.7 -7.22238e-14 -15.5,
+                          -159.7 -9.11067 -12.5398,
+                          -234.7 -7.22238e-14 -15.5,
+                          -159.7 -7.60129e-14 -15.5,
+                          -234.7 14.741 4.78816,
+                          -234.7 14.741 -4.78816,
+                          -234.7 9.11272 -12.5378,
+                          -159.7 9.11067 -12.5398,
+                          -234.7 9.11272 -12.5378,
+                          -234.7 14.741 -4.78816,
+                          -234.7 9.11272 12.5378,
+                          -234.7 14.741 4.78816,
+                          -234.7 9.11272 -12.5378,
+                          -159.7 9.11067 -12.5398,
+                          -159.7 -7.60129e-14 -15.5,
+                          -234.7 9.11272 -12.5378,
+                          -159.7 14.7414 -4.78976,
+                          -234.7 14.741 -4.78816,
+                          -234.7 14.741 4.78816,
+                          -159.7 14.7414 -4.78976,
+                          -159.7 9.11067 -12.5398,
+                          -234.7 14.741 -4.78816,
+                          -159.7 14.7414 4.78976,
+                          -234.7 14.741 4.78816,
+                          -234.7 9.11272 12.5378,
+                          -159.7 14.7414 4.78976,
+                          -159.7 14.7414 -4.78976,
+                          -234.7 14.741 4.78816,
+                          -159.7 9.11067 12.5398,
+                          -234.7 9.11272 12.5378,
+                          -234.7 -7.28537e-14 15.5,
+                          -159.7 9.11067 12.5398,
+                          -159.7 14.7414 4.78976,
+                          -234.7 9.11272 12.5378,
+                          -234.7 -9.11272 -12.5378,
+                          -234.7 -9.11272 12.5378,
+                          -234.7 -7.28537e-14 15.5,
+                          -159.7 -7.85409e-14 15.5,
+                          -234.7 -7.28537e-14 15.5,
+                          -234.7 -9.11272 12.5378,
+                          -159.7 -7.85409e-14 15.5,
+                          -159.7 9.11067 12.5398,
+                          -234.7 -7.28537e-14 15.5,
+                          -234.7 -14.741 -4.78816,
+                          -234.7 -14.741 4.78816,
+                          -234.7 -9.11272 12.5378,
+                          -159.7 -9.11067 12.5398,
+                          -234.7 -9.11272 12.5378,
+                          -234.7 -14.741 4.78816,
+                          -234.7 -9.11272 -12.5378,
+                          -234.7 -14.741 -4.78816,
+                          -234.7 -9.11272 12.5378,
+                          -159.7 -9.11067 12.5398,
+                          -159.7 -7.85409e-14 15.5,
+                          -234.7 -9.11272 12.5378,
+                          -159.7 -14.7414 4.78976,
+                          -234.7 -14.741 4.78816,
+                          -234.7 -14.741 -4.78816,
+                          -159.7 -14.7414 4.78976,
+                          -159.7 -9.11067 12.5398,
+                          -234.7 -14.741 4.78816,
+                          -159.7 -14.7414 -4.78976,
+                          -234.7 -14.741 -4.78816,
+                          -234.7 -9.11272 -12.5378,
+                          -159.7 -14.7414 -4.78976,
+                          -159.7 -14.7414 4.78976,
+                          -234.7 -14.741 -4.78816,
+                          -159.7 -9.11067 -12.5398,
+                          -159.7 -14.7414 -4.78976,
+                          -234.7 -9.11272 -12.5378 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    1 1 1
+    }
+    Separator {
+        Normal {
+            vector      [ -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          3.88578e-16 -2.03185e-17 1,
+                          3.88578e-16 -2.03185e-17 1,
+                          3.88578e-16 -2.03185e-17 1,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          3.88578e-16 -2.03185e-17 1,
+                          3.88578e-16 -2.03185e-17 1,
+                          3.88578e-16 -2.03185e-17 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,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -3.88578e-16 2.03185e-17 -1,
+                          -3.88578e-16 2.03185e-17 -1,
+                          -3.88578e-16 2.03185e-17 -1,
+                          -3.88578e-16 2.03185e-17 -1,
+                          -3.88578e-16 2.03185e-17 -1,
+                          -3.88578e-16 2.03185e-17 -1,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -3.88578e-16 2.03185e-17 -1,
+                          -3.88578e-16 2.03185e-17 -1,
+                          -3.88578e-16 2.03185e-17 -1,
+                          -3.88578e-16 2.03185e-17 -1,
+                          -3.88578e-16 2.03185e-17 -1,
+                          -3.88578e-16 2.03185e-17 -1,
+                          -3.88578e-16 2.03185e-17 -1,
+                          -3.88578e-16 2.03185e-17 -1,
+                          -3.88578e-16 2.03185e-17 -1,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          3.88578e-16 -2.03185e-17 1,
+                          3.88578e-16 -2.03185e-17 1,
+                          3.88578e-16 -2.03185e-17 1,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          -0.586822 6.09507e-17 -0.809716,
+                          -0.274423 4.03479e-17 -0.961609,
+                          -0.274423 4.03479e-17 -0.961609,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.586822 6.09507e-17 -0.809716,
+                          -0.586822 6.09507e-17 -0.809716,
+                          -0.274423 4.03479e-17 -0.961609,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -3.88578e-16 2.03185e-17 -1,
+                          -3.88578e-16 2.03185e-17 -1,
+                          -3.88578e-16 2.03185e-17 -1,
+                          -0.586822 6.09507e-17 -0.809716,
+                          -0.274423 4.03479e-17 -0.961609,
+                          -0.274423 4.03479e-17 -0.961609,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.586822 6.09507e-17 -0.809716,
+                          -0.586822 6.09507e-17 -0.809716,
+                          -0.274423 4.03479e-17 -0.961609,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          3.88578e-16 -2.03185e-17 1,
+                          3.88578e-16 -2.03185e-17 1,
+                          3.88578e-16 -2.03185e-17 1,
+                          3.88578e-16 -2.03185e-17 1,
+                          3.88578e-16 -2.03185e-17 1,
+                          3.88578e-16 -2.03185e-17 1,
+                          3.88578e-16 -2.03185e-17 1,
+                          3.88578e-16 -2.03185e-17 1,
+                          3.88578e-16 -2.03185e-17 1,
+                          -0.0860263 -1.37198e-17 0.996293,
+                          -0.0860263 -1.37198e-17 0.996293,
+                          0.328256 -4.40842e-17 0.944589,
+                          0.328256 -4.40842e-17 0.944589,
+                          0.328256 -4.40842e-17 0.944589,
+                          0.685323 -6.67645e-17 0.728239,
+                          -0.0860263 -1.37198e-17 0.996293,
+                          0.328256 -4.40842e-17 0.944589,
+                          0.328256 -4.40842e-17 0.944589,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.685323 -6.67645e-17 0.728239,
+                          0.685323 -6.67645e-17 0.728239,
+                          0.685323 -6.67645e-17 0.728239,
+                          0.685323 -6.67645e-17 0.728239,
+                          0.685323 -6.67645e-17 0.728239,
+                          0.685323 -6.67645e-17 0.728239,
+                          0.328256 -4.40842e-17 0.944589,
+                          0.685323 -6.67645e-17 0.728239,
+                          0.685323 -6.67645e-17 0.728239,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.685323 -6.67645e-17 0.728239,
+                          0.685323 -6.67645e-17 0.728239,
+                          -0.101855 -1.24892e-17 0.994799,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.101855 -1.24892e-17 0.994799,
+                          -0.101855 -1.24892e-17 0.994799,
+                          -0.818681 5.04124e-17 0.574249,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.685323 -6.67645e-17 0.728239,
+                          -0.101855 -1.24892e-17 0.994799,
+                          -0.101855 -1.24892e-17 0.994799,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.818681 5.04124e-17 0.574249,
+                          -0.818681 5.04124e-17 0.574249,
+                          -0.970042 7.84941e-17 -0.242937,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.101855 -1.24892e-17 0.994799,
+                          -0.818681 5.04124e-17 0.574249,
+                          -0.818681 5.04124e-17 0.574249,
+                          -0.970042 7.84941e-17 -0.242937,
+                          -0.970042 7.84941e-17 -0.242937,
+                          -0.970042 7.84941e-17 -0.242937,
+                          -0.970042 7.84941e-17 -0.242937,
+                          -0.970042 7.84941e-17 -0.242937,
+                          -0.970042 7.84941e-17 -0.242937,
+                          -0.818681 5.04124e-17 0.574249,
+                          -0.970042 7.84941e-17 -0.242937,
+                          -0.970042 7.84941e-17 -0.242937,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.970042 7.84941e-17 -0.242937,
+                          -0.970042 7.84941e-17 -0.242937,
+                          -0.828412 7.4199e-17 -0.56012,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.828412 7.4199e-17 -0.56012,
+                          -0.828412 7.4199e-17 -0.56012,
+                          -0.586822 6.09507e-17 -0.809716,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.970042 7.84941e-17 -0.242937,
+                          -0.828412 7.4199e-17 -0.56012,
+                          -0.828412 7.4199e-17 -0.56012,
+                          -0.828412 7.4199e-17 -0.56012,
+                          -0.586822 6.09507e-17 -0.809716,
+                          -0.586822 6.09507e-17 -0.809716,
+                          -1 7.58296e-17 3.00432e-16,
+                          -1 7.58296e-17 3.00432e-16,
+                          -0.5 2.03185e-17 0.866025,
+                          -0.5 5.55112e-17 -0.866025,
+                          -0.5 5.55112e-17 -0.866025,
+                          -1 7.58296e-17 5.55112e-17,
+                          -0.5 5.55112e-17 -0.866025,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -0.5 2.03185e-17 0.866025,
+                          -0.5 2.03185e-17 0.866025,
+                          0.5 -5.55112e-17 0.866025,
+                          -0.5 2.03185e-17 0.866025,
+                          -1 7.58296e-17 3.00432e-16,
+                          -0.5 2.03185e-17 0.866025,
+                          0.5 -5.55112e-17 0.866025,
+                          0.5 -5.55112e-17 0.866025,
+                          1 -7.58296e-17 -1.77972e-16,
+                          -0.5 2.03185e-17 0.866025,
+                          0.5 -5.55112e-17 0.866025,
+                          0.5 -5.55112e-17 0.866025,
+                          1 -7.58296e-17 -1.77972e-16,
+                          1 -7.58296e-17 -1.77972e-16,
+                          0.5 -2.03185e-17 -0.866025,
+                          0.5 -5.55112e-17 0.866025,
+                          1 -7.58296e-17 -1.77972e-16,
+                          1 -7.58296e-17 -1.77972e-16,
+                          0.5 -2.03185e-17 -0.866025,
+                          0.5 -2.03185e-17 -0.866025,
+                          -0.5 5.55112e-17 -0.866025,
+                          1 -7.58296e-17 -1.77972e-16,
+                          0.5 -2.03185e-17 -0.866025,
+                          0.5 -2.03185e-17 -0.866025,
+                          0.5 -2.03185e-17 -0.866025,
+                          -0.5 5.55112e-17 -0.866025,
+                          -0.5 5.55112e-17 -0.866025,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          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 7.58296e-17 3.00432e-16,
+                          -1 7.58296e-17 3.00432e-16,
+                          -0.5 2.03185e-17 0.866025,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.5 5.55112e-17 -0.866025,
+                          -0.5 5.55112e-17 -0.866025,
+                          -1 7.58296e-17 5.55112e-17,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.5 5.55112e-17 -0.866025,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.5 2.03185e-17 0.866025,
+                          -0.5 2.03185e-17 0.866025,
+                          0.5 -5.55112e-17 0.866025,
+                          -0.5 2.03185e-17 0.866025,
+                          -1 7.58296e-17 3.00432e-16,
+                          -0.5 2.03185e-17 0.866025,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.5 -5.55112e-17 0.866025,
+                          0.5 -5.55112e-17 0.866025,
+                          1 -7.58296e-17 -1.77972e-16,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.5 2.03185e-17 0.866025,
+                          0.5 -5.55112e-17 0.866025,
+                          0.5 -5.55112e-17 0.866025,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          1 -7.58296e-17 -1.77972e-16,
+                          1 -7.58296e-17 -1.77972e-16,
+                          0.5 -2.03185e-17 -0.866025,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.5 -5.55112e-17 0.866025,
+                          1 -7.58296e-17 -1.77972e-16,
+                          1 -7.58296e-17 -1.77972e-16,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.5 -2.03185e-17 -0.866025,
+                          0.5 -2.03185e-17 -0.866025,
+                          -0.5 5.55112e-17 -0.866025,
+                          1 -7.58296e-17 -1.77972e-16,
+                          0.5 -2.03185e-17 -0.866025,
+                          0.5 -2.03185e-17 -0.866025,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.5 -2.03185e-17 -0.866025,
+                          -0.5 5.55112e-17 -0.866025,
+                          -0.5 5.55112e-17 -0.866025,
+                          3.27348e-16 -2.03185e-17 1,
+                          3.27348e-16 -2.03185e-17 1,
+                          0.382683 -4.77906e-17 0.92388,
+                          0.382683 -4.77906e-17 0.92388,
+                          0.382683 -4.77906e-17 0.92388,
+                          0.707107 -6.7987e-17 0.707107,
+                          3.27348e-16 -2.03185e-17 1,
+                          0.382683 -4.77906e-17 0.92388,
+                          0.382683 -4.77906e-17 0.92388,
+                          0.707107 -6.7987e-17 0.707107,
+                          0.707107 -6.7987e-17 0.707107,
+                          0.707107 -6.7987e-17 0.707107,
+                          0.382683 -4.77906e-17 0.92388,
+                          0.707107 -6.7987e-17 0.707107,
+                          0.707107 -6.7987e-17 0.707107,
+                          0.707107 -6.7987e-17 0.707107,
+                          0.707107 -6.7987e-17 0.707107,
+                          2.04887e-16 -2.03185e-17 1,
+                          0.707107 -6.7987e-17 0.707107,
+                          0.707107 -6.7987e-17 0.707107,
+                          0.707107 -6.7987e-17 0.707107,
+                          2.04887e-16 -2.03185e-17 1,
+                          2.04887e-16 -2.03185e-17 1,
+                          -0.707107 3.92523e-17 0.707107,
+                          0.707107 -6.7987e-17 0.707107,
+                          2.04887e-16 -2.03185e-17 1,
+                          2.04887e-16 -2.03185e-17 1,
+                          -0.707107 3.92523e-17 0.707107,
+                          -0.707107 3.92523e-17 0.707107,
+                          -0.707107 3.92523e-17 0.707107,
+                          2.04887e-16 -2.03185e-17 1,
+                          -0.707107 3.92523e-17 0.707107,
+                          -0.707107 3.92523e-17 0.707107,
+                          -0.707107 3.92523e-17 0.707107,
+                          -0.707107 3.92523e-17 0.707107,
+                          -0.382683 1.02469e-17 0.92388,
+                          -0.707107 3.92523e-17 0.707107,
+                          -0.707107 3.92523e-17 0.707107,
+                          -0.707107 3.92523e-17 0.707107,
+                          -0.382683 1.02469e-17 0.92388,
+                          -0.382683 1.02469e-17 0.92388,
+                          3.27348e-16 -2.03185e-17 1,
+                          -0.707107 3.92523e-17 0.707107,
+                          -0.382683 1.02469e-17 0.92388,
+                          -0.382683 1.02469e-17 0.92388,
+                          3.88578e-16 -2.03185e-17 1,
+                          3.88578e-16 -2.03185e-17 1,
+                          3.88578e-16 -2.03185e-17 1,
+                          -0.382683 1.02469e-17 0.92388,
+                          3.27348e-16 -2.03185e-17 1,
+                          3.27348e-16 -2.03185e-17 1,
+                          3.88578e-16 -2.03185e-17 1,
+                          3.88578e-16 -2.03185e-17 1,
+                          3.88578e-16 -2.03185e-17 1,
+                          -0.0860263 -1.37198e-17 0.996293,
+                          -0.0860263 -1.37198e-17 0.996293,
+                          0.328256 -4.40842e-17 0.944589,
+                          0.328256 -4.40842e-17 0.944589,
+                          0.328256 -4.40842e-17 0.944589,
+                          0.685323 -6.67645e-17 0.728239,
+                          -0.0860263 -1.37198e-17 0.996293,
+                          0.328256 -4.40842e-17 0.944589,
+                          0.328256 -4.40842e-17 0.944589,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0.685323 -6.67645e-17 0.728239,
+                          0.685323 -6.67645e-17 0.728239,
+                          0.685323 -6.67645e-17 0.728239,
+                          0.685323 -6.67645e-17 0.728239,
+                          0.685323 -6.67645e-17 0.728239,
+                          0.685323 -6.67645e-17 0.728239,
+                          0.328256 -4.40842e-17 0.944589,
+                          0.685323 -6.67645e-17 0.728239,
+                          0.685323 -6.67645e-17 0.728239,
+                          0.685323 -6.67645e-17 0.728239,
+                          0.685323 -6.67645e-17 0.728239,
+                          -0.101855 -1.24892e-17 0.994799,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.101855 -1.24892e-17 0.994799,
+                          -0.101855 -1.24892e-17 0.994799,
+                          -0.818681 5.04124e-17 0.574249,
+                          0.685323 -6.67645e-17 0.728239,
+                          -0.101855 -1.24892e-17 0.994799,
+                          -0.101855 -1.24892e-17 0.994799,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -0.818681 5.04124e-17 0.574249,
+                          -0.818681 5.04124e-17 0.574249,
+                          -0.970042 7.84941e-17 -0.242937,
+                          -0.101855 -1.24892e-17 0.994799,
+                          -0.818681 5.04124e-17 0.574249,
+                          -0.818681 5.04124e-17 0.574249,
+                          -0.970042 7.84941e-17 -0.242937,
+                          -0.970042 7.84941e-17 -0.242937,
+                          -0.970042 7.84941e-17 -0.242937,
+                          -0.970042 7.84941e-17 -0.242937,
+                          -0.970042 7.84941e-17 -0.242937,
+                          -0.970042 7.84941e-17 -0.242937,
+                          -0.818681 5.04124e-17 0.574249,
+                          -0.970042 7.84941e-17 -0.242937,
+                          -0.970042 7.84941e-17 -0.242937,
+                          -0.970042 7.84941e-17 -0.242937,
+                          -0.970042 7.84941e-17 -0.242937,
+                          -0.828412 7.4199e-17 -0.56012,
+                          -0.828412 7.4199e-17 -0.56012,
+                          -0.828412 7.4199e-17 -0.56012,
+                          -0.586822 6.09507e-17 -0.809716,
+                          -0.970042 7.84941e-17 -0.242937,
+                          -0.828412 7.4199e-17 -0.56012,
+                          -0.828412 7.4199e-17 -0.56012,
+                          -0.828412 7.4199e-17 -0.56012,
+                          -0.586822 6.09507e-17 -0.809716,
+                          -0.586822 6.09507e-17 -0.809716,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -234.7 33.5 18.5,
+                          -234.7 -18.5 -22,
+                          -234.7 -18.5 18.5,
+                          -267.7 -18.5 -22,
+                          -234.7 -18.5 18.5,
+                          -234.7 -18.5 -22,
+                          -230.7 37.5 18.5,
+                          -234.7 33.5 18.5,
+                          -234.7 -18.5 18.5,
+                          -240.872 -18.5 26.3284,
+                          -234.7 -18.5 18.5,
+                          -267.7 -18.5 -22,
+                          -230.972 -18.5 18.5,
+                          -230.7 37.5 18.5,
+                          -234.7 -18.5 18.5,
+                          -232.885 -18.5 18.8806,
+                          -230.972 -18.5 18.5,
+                          -234.7 -18.5 18.5,
+                          -234.508 -18.5 19.9645,
+                          -232.885 -18.5 18.8806,
+                          -234.7 -18.5 18.5,
+                          -240.872 -18.5 26.3284,
+                          -234.508 -18.5 19.9645,
+                          -234.7 -18.5 18.5,
+                          -234.7 33.5 18.5,
+                          -234.7 33.5 -22,
+                          -234.7 -18.5 -22,
+                          -230.7 -22.5 -22,
+                          -234.7 -18.5 -22,
+                          -234.7 33.5 -22,
+                          -230.7 -22.5 -22,
+                          -267.7 -18.5 -22,
+                          -234.7 -18.5 -22,
+                          -258.717 33.5 18.5,
+                          -234.7 33.5 -22,
+                          -234.7 33.5 18.5,
+                          -267.7 37.5 -22,
+                          -230.7 37.5 -22,
+                          -234.7 33.5 -22,
+                          -230.7 -22.5 -22,
+                          -234.7 33.5 -22,
+                          -230.7 37.5 -22,
+                          -267.7 33.5 -22,
+                          -267.7 37.5 -22,
+                          -234.7 33.5 -22,
+                          -267.657 33.5 19.6158,
+                          -267.7 33.5 -22,
+                          -234.7 33.5 -22,
+                          -258.717 33.5 18.5,
+                          -267.657 33.5 19.6158,
+                          -234.7 33.5 -22,
+                          -258.717 33.5 18.5,
+                          -234.7 33.5 18.5,
+                          -230.7 37.5 18.5,
+                          -230.7 37.5 18.5,
+                          -230.7 37.5 -22,
+                          -267.7 37.5 -22,
+                          -230.7 -22.5 18.5,
+                          -230.7 -22.5 -22,
+                          -230.7 37.5 -22,
+                          -230.7 37.5 18.5,
+                          -230.7 -22.5 18.5,
+                          -230.7 37.5 -22,
+                          -277.262 33.5 -17.3508,
+                          -267.7 37.5 -22,
+                          -267.7 33.5 -22,
+                          -258.717 37.5 18.5,
+                          -230.7 37.5 18.5,
+                          -267.7 37.5 -22,
+                          -267.657 37.5 19.6158,
+                          -258.717 37.5 18.5,
+                          -267.7 37.5 -22,
+                          -275.363 37.5 24.2846,
+                          -267.657 37.5 19.6158,
+                          -267.7 37.5 -22,
+                          -277.262 37.5 -17.3508,
+                          -275.363 37.5 24.2846,
+                          -267.7 37.5 -22,
+                          -277.262 33.5 -17.3508,
+                          -277.262 37.5 -17.3508,
+                          -267.7 37.5 -22,
+                          -275.363 33.5 24.2846,
+                          -277.262 33.5 -17.3508,
+                          -267.7 33.5 -22,
+                          -267.657 33.5 19.6158,
+                          -275.363 33.5 24.2846,
+                          -267.7 33.5 -22,
+                          -230.7 -22.5 -22,
+                          -267.7 -22.5 -22,
+                          -267.7 -18.5 -22,
+                          -277.262 -22.5 -17.3508,
+                          -267.7 -18.5 -22,
+                          -267.7 -22.5 -22,
+                          -243.7 -18.5 27.5,
+                          -240.872 -18.5 26.3284,
+                          -267.7 -18.5 -22,
+                          -246.528 -18.5 26.3284,
+                          -243.7 -18.5 27.5,
+                          -267.7 -18.5 -22,
+                          -252.892 -18.5 19.9645,
+                          -246.528 -18.5 26.3284,
+                          -267.7 -18.5 -22,
+                          -254.515 -18.5 18.8806,
+                          -252.892 -18.5 19.9645,
+                          -267.7 -18.5 -22,
+                          -256.428 -18.5 18.5,
+                          -254.515 -18.5 18.8806,
+                          -267.7 -18.5 -22,
+                          -258.717 -18.5 18.5,
+                          -256.428 -18.5 18.5,
+                          -267.7 -18.5 -22,
+                          -267.657 -18.5 19.6158,
+                          -258.717 -18.5 18.5,
+                          -267.7 -18.5 -22,
+                          -275.363 -18.5 24.2846,
+                          -267.657 -18.5 19.6158,
+                          -267.7 -18.5 -22,
+                          -277.262 -18.5 -17.3508,
+                          -275.363 -18.5 24.2846,
+                          -267.7 -18.5 -22,
+                          -277.262 -22.5 -17.3508,
+                          -277.262 -18.5 -17.3508,
+                          -267.7 -18.5 -22,
+                          -267.657 -22.5 19.6158,
+                          -267.7 -22.5 -22,
+                          -230.7 -22.5 -22,
+                          -275.363 -22.5 24.2846,
+                          -277.262 -22.5 -17.3508,
+                          -267.7 -22.5 -22,
+                          -267.657 -22.5 19.6158,
+                          -275.363 -22.5 24.2846,
+                          -267.7 -22.5 -22,
+                          -230.972 -22.5 18.5,
+                          -230.7 -22.5 -22,
+                          -230.7 -22.5 18.5,
+                          -254.515 -22.5 18.8806,
+                          -256.428 -22.5 18.5,
+                          -230.7 -22.5 -22,
+                          -258.717 -22.5 18.5,
+                          -230.7 -22.5 -22,
+                          -256.428 -22.5 18.5,
+                          -252.892 -22.5 19.9645,
+                          -254.515 -22.5 18.8806,
+                          -230.7 -22.5 -22,
+                          -246.528 -22.5 26.3284,
+                          -252.892 -22.5 19.9645,
+                          -230.7 -22.5 -22,
+                          -243.7 -22.5 27.5,
+                          -246.528 -22.5 26.3284,
+                          -230.7 -22.5 -22,
+                          -240.872 -22.5 26.3284,
+                          -243.7 -22.5 27.5,
+                          -230.7 -22.5 -22,
+                          -234.508 -22.5 19.9645,
+                          -240.872 -22.5 26.3284,
+                          -230.7 -22.5 -22,
+                          -232.885 -22.5 18.8806,
+                          -234.508 -22.5 19.9645,
+                          -230.7 -22.5 -22,
+                          -230.972 -22.5 18.5,
+                          -232.885 -22.5 18.8806,
+                          -230.7 -22.5 -22,
+                          -258.717 -22.5 18.5,
+                          -267.657 -22.5 19.6158,
+                          -230.7 -22.5 -22,
+                          -230.972 -22.5 18.5,
+                          -230.7 -22.5 18.5,
+                          -230.7 37.5 18.5,
+                          -258.717 33.5 18.5,
+                          -230.7 37.5 18.5,
+                          -258.717 37.5 18.5,
+                          -230.972 -22.5 18.5,
+                          -230.7 37.5 18.5,
+                          -230.972 -18.5 18.5,
+                          -258.717 33.5 18.5,
+                          -258.717 37.5 18.5,
+                          -267.657 37.5 19.6158,
+                          -267.657 33.5 19.6158,
+                          -267.657 37.5 19.6158,
+                          -275.363 37.5 24.2846,
+                          -258.717 33.5 18.5,
+                          -267.657 37.5 19.6158,
+                          -267.657 33.5 19.6158,
+                          -277.262 37.5 -17.3508,
+                          -278.799 37.5 27.518,
+                          -275.363 37.5 24.2846,
+                          -278.799 33.5 27.518,
+                          -275.363 37.5 24.2846,
+                          -278.799 37.5 27.518,
+                          -275.363 33.5 24.2846,
+                          -275.363 37.5 24.2846,
+                          -278.799 33.5 27.518,
+                          -267.657 33.5 19.6158,
+                          -275.363 37.5 24.2846,
+                          -275.363 33.5 24.2846,
+                          -282.701 37.5 23.4642,
+                          -285.882 37.5 29.9169,
+                          -278.799 37.5 27.518,
+                          -278.799 33.5 27.518,
+                          -278.799 37.5 27.518,
+                          -285.882 37.5 29.9169,
+                          -277.262 37.5 -17.3508,
+                          -284.659 37.5 -9.7084,
+                          -278.799 37.5 27.518,
+                          -280.7 37.5 20,
+                          -278.799 37.5 27.518,
+                          -284.659 37.5 -9.7084,
+                          -282.701 37.5 23.4642,
+                          -278.799 37.5 27.518,
+                          -280.7 37.5 20,
+                          -288.7 37.5 20,
+                          -292.335 37.5 26.1312,
+                          -285.882 37.5 29.9169,
+                          -285.882 33.5 29.9169,
+                          -285.882 37.5 29.9169,
+                          -292.335 37.5 26.1312,
+                          -286.699 37.5 23.4642,
+                          -288.7 37.5 20,
+                          -285.882 37.5 29.9169,
+                          -282.701 37.5 23.4642,
+                          -286.699 37.5 23.4642,
+                          -285.882 37.5 29.9169,
+                          -278.799 33.5 27.518,
+                          -285.882 37.5 29.9169,
+                          -285.882 33.5 29.9169,
+                          -288.994 37.5 8.47264e-14,
+                          -293.697 37.5 18.7774,
+                          -292.335 37.5 26.1312,
+                          -292.335 33.5 26.1312,
+                          -292.335 37.5 26.1312,
+                          -293.697 37.5 18.7774,
+                          -288.7 37.5 20,
+                          -288.994 37.5 8.47264e-14,
+                          -292.335 37.5 26.1312,
+                          -285.882 33.5 29.9169,
+                          -292.335 37.5 26.1312,
+                          -292.335 33.5 26.1312,
+                          -288.994 33.5 8.47264e-14,
+                          -293.697 37.5 18.7774,
+                          -288.994 37.5 8.47264e-14,
+                          -293.697 33.5 18.7774,
+                          -293.697 37.5 18.7774,
+                          -288.994 33.5 8.47264e-14,
+                          -292.335 33.5 26.1312,
+                          -293.697 37.5 18.7774,
+                          -293.697 33.5 18.7774,
+                          -286.699 37.5 16.5358,
+                          -284.659 37.5 -9.7084,
+                          -288.994 37.5 8.47264e-14,
+                          -288.994 33.5 8.47264e-14,
+                          -288.994 37.5 8.47264e-14,
+                          -284.659 37.5 -9.7084,
+                          -288.7 37.5 20,
+                          -286.699 37.5 16.5358,
+                          -288.994 37.5 8.47264e-14,
+                          -284.659 33.5 -9.7084,
+                          -284.659 37.5 -9.7084,
+                          -277.262 37.5 -17.3508,
+                          -282.701 37.5 16.5358,
+                          -280.7 37.5 20,
+                          -284.659 37.5 -9.7084,
+                          -286.699 37.5 16.5358,
+                          -282.701 37.5 16.5358,
+                          -284.659 37.5 -9.7084,
+                          -288.994 33.5 8.47264e-14,
+                          -284.659 37.5 -9.7084,
+                          -284.659 33.5 -9.7084,
+                          -284.659 33.5 -9.7084,
+                          -277.262 37.5 -17.3508,
+                          -277.262 33.5 -17.3508,
+                          -280.7 33.5 20,
+                          -280.7 37.5 20,
+                          -282.701 37.5 16.5358,
+                          -282.701 33.5 23.4642,
+                          -282.701 37.5 23.4642,
+                          -280.7 37.5 20,
+                          -282.701 33.5 23.4642,
+                          -280.7 37.5 20,
+                          -280.7 33.5 20,
+                          -282.701 33.5 16.5358,
+                          -282.701 37.5 16.5358,
+                          -286.699 37.5 16.5358,
+                          -282.701 33.5 16.5358,
+                          -280.7 33.5 20,
+                          -282.701 37.5 16.5358,
+                          -286.699 33.5 16.5358,
+                          -286.699 37.5 16.5358,
+                          -288.7 37.5 20,
+                          -282.701 33.5 16.5358,
+                          -286.699 37.5 16.5358,
+                          -286.699 33.5 16.5358,
+                          -288.7 33.5 20,
+                          -288.7 37.5 20,
+                          -286.699 37.5 23.4642,
+                          -286.699 33.5 16.5358,
+                          -288.7 37.5 20,
+                          -288.7 33.5 20,
+                          -286.699 33.5 23.4642,
+                          -286.699 37.5 23.4642,
+                          -282.701 37.5 23.4642,
+                          -288.7 33.5 20,
+                          -286.699 37.5 23.4642,
+                          -286.699 33.5 23.4642,
+                          -286.699 33.5 23.4642,
+                          -282.701 37.5 23.4642,
+                          -282.701 33.5 23.4642,
+                          -282.701 33.5 16.5358,
+                          -284.659 33.5 -9.7084,
+                          -277.262 33.5 -17.3508,
+                          -275.363 33.5 24.2846,
+                          -278.799 33.5 27.518,
+                          -277.262 33.5 -17.3508,
+                          -280.7 33.5 20,
+                          -277.262 33.5 -17.3508,
+                          -278.799 33.5 27.518,
+                          -282.701 33.5 16.5358,
+                          -277.262 33.5 -17.3508,
+                          -280.7 33.5 20,
+                          -288.7 33.5 20,
+                          -288.994 33.5 8.47264e-14,
+                          -284.659 33.5 -9.7084,
+                          -286.699 33.5 16.5358,
+                          -288.7 33.5 20,
+                          -284.659 33.5 -9.7084,
+                          -282.701 33.5 16.5358,
+                          -286.699 33.5 16.5358,
+                          -284.659 33.5 -9.7084,
+                          -292.335 33.5 26.1312,
+                          -293.697 33.5 18.7774,
+                          -288.994 33.5 8.47264e-14,
+                          -288.7 33.5 20,
+                          -292.335 33.5 26.1312,
+                          -288.994 33.5 8.47264e-14,
+                          -286.699 33.5 23.4642,
+                          -285.882 33.5 29.9169,
+                          -292.335 33.5 26.1312,
+                          -288.7 33.5 20,
+                          -286.699 33.5 23.4642,
+                          -292.335 33.5 26.1312,
+                          -280.7 33.5 20,
+                          -278.799 33.5 27.518,
+                          -285.882 33.5 29.9169,
+                          -282.701 33.5 23.4642,
+                          -280.7 33.5 20,
+                          -285.882 33.5 29.9169,
+                          -286.699 33.5 23.4642,
+                          -282.701 33.5 23.4642,
+                          -285.882 33.5 29.9169,
+                          -284.659 -18.5 -9.7084,
+                          -282.701 -18.5 16.5358,
+                          -280.7 -18.5 20,
+                          -280.7 -22.5 20,
+                          -280.7 -18.5 20,
+                          -282.701 -18.5 16.5358,
+                          -278.799 -18.5 27.518,
+                          -280.7 -18.5 20,
+                          -282.701 -18.5 23.4642,
+                          -282.701 -22.5 23.4642,
+                          -282.701 -18.5 23.4642,
+                          -280.7 -18.5 20,
+                          -284.659 -18.5 -9.7084,
+                          -280.7 -18.5 20,
+                          -278.799 -18.5 27.518,
+                          -282.701 -22.5 23.4642,
+                          -280.7 -18.5 20,
+                          -280.7 -22.5 20,
+                          -284.659 -18.5 -9.7084,
+                          -286.699 -18.5 16.5358,
+                          -282.701 -18.5 16.5358,
+                          -282.701 -22.5 16.5358,
+                          -282.701 -18.5 16.5358,
+                          -286.699 -18.5 16.5358,
+                          -282.701 -22.5 16.5358,
+                          -280.7 -22.5 20,
+                          -282.701 -18.5 16.5358,
+                          -288.994 -18.5 8.47264e-14,
+                          -288.7 -18.5 20,
+                          -286.699 -18.5 16.5358,
+                          -286.699 -22.5 16.5358,
+                          -286.699 -18.5 16.5358,
+                          -288.7 -18.5 20,
+                          -284.659 -18.5 -9.7084,
+                          -288.994 -18.5 8.47264e-14,
+                          -286.699 -18.5 16.5358,
+                          -282.701 -22.5 16.5358,
+                          -286.699 -18.5 16.5358,
+                          -286.699 -22.5 16.5358,
+                          -285.882 -18.5 29.9169,
+                          -286.699 -18.5 23.4642,
+                          -288.7 -18.5 20,
+                          -288.7 -22.5 20,
+                          -288.7 -18.5 20,
+                          -286.699 -18.5 23.4642,
+                          -292.335 -18.5 26.1312,
+                          -285.882 -18.5 29.9169,
+                          -288.7 -18.5 20,
+                          -288.994 -18.5 8.47264e-14,
+                          -292.335 -18.5 26.1312,
+                          -288.7 -18.5 20,
+                          -286.699 -22.5 16.5358,
+                          -288.7 -18.5 20,
+                          -288.7 -22.5 20,
+                          -285.882 -18.5 29.9169,
+                          -282.701 -18.5 23.4642,
+                          -286.699 -18.5 23.4642,
+                          -286.699 -22.5 23.4642,
+                          -286.699 -18.5 23.4642,
+                          -282.701 -18.5 23.4642,
+                          -288.7 -22.5 20,
+                          -286.699 -18.5 23.4642,
+                          -286.699 -22.5 23.4642,
+                          -285.882 -18.5 29.9169,
+                          -278.799 -18.5 27.518,
+                          -282.701 -18.5 23.4642,
+                          -286.699 -22.5 23.4642,
+                          -282.701 -18.5 23.4642,
+                          -282.701 -22.5 23.4642,
+                          -230.972 -22.5 18.5,
+                          -230.972 -18.5 18.5,
+                          -232.885 -18.5 18.8806,
+                          -232.885 -22.5 18.8806,
+                          -232.885 -18.5 18.8806,
+                          -234.508 -18.5 19.9645,
+                          -230.972 -22.5 18.5,
+                          -232.885 -18.5 18.8806,
+                          -232.885 -22.5 18.8806,
+                          -234.508 -22.5 19.9645,
+                          -234.508 -18.5 19.9645,
+                          -240.872 -18.5 26.3284,
+                          -232.885 -22.5 18.8806,
+                          -234.508 -18.5 19.9645,
+                          -234.508 -22.5 19.9645,
+                          -240.872 -22.5 26.3284,
+                          -240.872 -18.5 26.3284,
+                          -243.7 -18.5 27.5,
+                          -234.508 -22.5 19.9645,
+                          -240.872 -18.5 26.3284,
+                          -240.872 -22.5 26.3284,
+                          -243.7 -22.5 27.5,
+                          -243.7 -18.5 27.5,
+                          -246.528 -18.5 26.3284,
+                          -240.872 -22.5 26.3284,
+                          -243.7 -18.5 27.5,
+                          -243.7 -22.5 27.5,
+                          -246.528 -22.5 26.3284,
+                          -246.528 -18.5 26.3284,
+                          -252.892 -18.5 19.9645,
+                          -243.7 -22.5 27.5,
+                          -246.528 -18.5 26.3284,
+                          -246.528 -22.5 26.3284,
+                          -252.892 -22.5 19.9645,
+                          -252.892 -18.5 19.9645,
+                          -254.515 -18.5 18.8806,
+                          -246.528 -22.5 26.3284,
+                          -252.892 -18.5 19.9645,
+                          -252.892 -22.5 19.9645,
+                          -254.515 -22.5 18.8806,
+                          -254.515 -18.5 18.8806,
+                          -256.428 -18.5 18.5,
+                          -252.892 -22.5 19.9645,
+                          -254.515 -18.5 18.8806,
+                          -254.515 -22.5 18.8806,
+                          -258.717 -22.5 18.5,
+                          -256.428 -18.5 18.5,
+                          -258.717 -18.5 18.5,
+                          -254.515 -22.5 18.8806,
+                          -256.428 -18.5 18.5,
+                          -256.428 -22.5 18.5,
+                          -258.717 -22.5 18.5,
+                          -256.428 -22.5 18.5,
+                          -256.428 -18.5 18.5,
+                          -258.717 -22.5 18.5,
+                          -258.717 -18.5 18.5,
+                          -267.657 -18.5 19.6158,
+                          -267.657 -22.5 19.6158,
+                          -267.657 -18.5 19.6158,
+                          -275.363 -18.5 24.2846,
+                          -258.717 -22.5 18.5,
+                          -267.657 -18.5 19.6158,
+                          -267.657 -22.5 19.6158,
+                          -277.262 -18.5 -17.3508,
+                          -278.799 -18.5 27.518,
+                          -275.363 -18.5 24.2846,
+                          -278.799 -22.5 27.518,
+                          -275.363 -18.5 24.2846,
+                          -278.799 -18.5 27.518,
+                          -275.363 -22.5 24.2846,
+                          -275.363 -18.5 24.2846,
+                          -278.799 -22.5 27.518,
+                          -267.657 -22.5 19.6158,
+                          -275.363 -18.5 24.2846,
+                          -275.363 -22.5 24.2846,
+                          -278.799 -22.5 27.518,
+                          -278.799 -18.5 27.518,
+                          -285.882 -18.5 29.9169,
+                          -277.262 -18.5 -17.3508,
+                          -284.659 -18.5 -9.7084,
+                          -278.799 -18.5 27.518,
+                          -285.882 -22.5 29.9169,
+                          -285.882 -18.5 29.9169,
+                          -292.335 -18.5 26.1312,
+                          -278.799 -22.5 27.518,
+                          -285.882 -18.5 29.9169,
+                          -285.882 -22.5 29.9169,
+                          -288.994 -18.5 8.47264e-14,
+                          -293.697 -18.5 18.7774,
+                          -292.335 -18.5 26.1312,
+                          -292.335 -22.5 26.1312,
+                          -292.335 -18.5 26.1312,
+                          -293.697 -18.5 18.7774,
+                          -285.882 -22.5 29.9169,
+                          -292.335 -18.5 26.1312,
+                          -292.335 -22.5 26.1312,
+                          -288.994 -22.5 8.47264e-14,
+                          -293.697 -18.5 18.7774,
+                          -288.994 -18.5 8.47264e-14,
+                          -293.697 -22.5 18.7774,
+                          -293.697 -18.5 18.7774,
+                          -288.994 -22.5 8.47264e-14,
+                          -292.335 -22.5 26.1312,
+                          -293.697 -18.5 18.7774,
+                          -293.697 -22.5 18.7774,
+                          -288.994 -22.5 8.47264e-14,
+                          -288.994 -18.5 8.47264e-14,
+                          -284.659 -18.5 -9.7084,
+                          -284.659 -22.5 -9.7084,
+                          -284.659 -18.5 -9.7084,
+                          -277.262 -18.5 -17.3508,
+                          -288.994 -22.5 8.47264e-14,
+                          -284.659 -18.5 -9.7084,
+                          -284.659 -22.5 -9.7084,
+                          -284.659 -22.5 -9.7084,
+                          -277.262 -18.5 -17.3508,
+                          -277.262 -22.5 -17.3508,
+                          -285.882 -22.5 29.9169,
+                          -282.701 -22.5 23.4642,
+                          -280.7 -22.5 20,
+                          -277.262 -22.5 -17.3508,
+                          -280.7 -22.5 20,
+                          -282.701 -22.5 16.5358,
+                          -278.799 -22.5 27.518,
+                          -280.7 -22.5 20,
+                          -277.262 -22.5 -17.3508,
+                          -278.799 -22.5 27.518,
+                          -285.882 -22.5 29.9169,
+                          -280.7 -22.5 20,
+                          -285.882 -22.5 29.9169,
+                          -286.699 -22.5 23.4642,
+                          -282.701 -22.5 23.4642,
+                          -292.335 -22.5 26.1312,
+                          -288.7 -22.5 20,
+                          -286.699 -22.5 23.4642,
+                          -285.882 -22.5 29.9169,
+                          -292.335 -22.5 26.1312,
+                          -286.699 -22.5 23.4642,
+                          -284.659 -22.5 -9.7084,
+                          -286.699 -22.5 16.5358,
+                          -288.7 -22.5 20,
+                          -288.994 -22.5 8.47264e-14,
+                          -284.659 -22.5 -9.7084,
+                          -288.7 -22.5 20,
+                          -292.335 -22.5 26.1312,
+                          -288.994 -22.5 8.47264e-14,
+                          -288.7 -22.5 20,
+                          -284.659 -22.5 -9.7084,
+                          -282.701 -22.5 16.5358,
+                          -286.699 -22.5 16.5358,
+                          -284.659 -22.5 -9.7084,
+                          -277.262 -22.5 -17.3508,
+                          -282.701 -22.5 16.5358,
+                          -275.363 -22.5 24.2846,
+                          -278.799 -22.5 27.518,
+                          -277.262 -22.5 -17.3508,
+                          -292.335 -22.5 26.1312,
+                          -293.697 -22.5 18.7774,
+                          -288.994 -22.5 8.47264e-14 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+    Separator {
+        Normal {
+            vector      [ -0.393775 -0.61625 0.682039,
+                          -0.379466 -0.651171 0.657254,
+                          -0.386729 -0.633847 0.669835,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -0.403122 -0.591582 0.698228,
+                          -0.379466 -0.651171 0.657254,
+                          -0.393775 -0.61625 0.682039,
+                          0 1 -1.83691e-16,
+                          -4.42482e-17 0.993495 -0.113872,
+                          9.61468e-17 0.968905 0.247432,
+                          0 1 -1.83691e-16,
+                          9.61468e-17 0.968905 0.247432,
+                          1.48702e-16 0.92388 0.382683,
+                          2.01913e-16 0.854398 0.519619,
+                          1.48702e-16 0.92388 0.382683,
+                          9.61468e-17 0.968905 0.247432,
+                          -0.403122 -0.591582 0.698228,
+                          -0.415667 -0.555774 0.719956,
+                          -0.379466 -0.651171 0.657254,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          8.64668e-17 -0.974928 0.222521,
+                          -8.49865e-17 -0.97579 -0.218712,
+                          8.7571e-17 -0.974275 0.225363,
+                          -8.64668e-17 -0.974928 -0.222521,
+                          -8.49865e-17 -0.97579 -0.218712,
+                          8.64668e-17 -0.974928 0.222521,
+                          -1.27509e-16 -0.944628 -0.328142,
+                          -8.49865e-17 -0.97579 -0.218712,
+                          -8.64668e-17 -0.974928 -0.222521,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          2.42274e-16 -0.781832 0.62349,
+                          8.7571e-17 -0.974275 0.225363,
+                          2.42861e-16 -0.780624 0.625,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          8.64668e-17 -0.974928 0.222521,
+                          8.7571e-17 -0.974275 0.225363,
+                          2.42274e-16 -0.781832 0.62349,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          3.50097e-16 -0.433884 0.900969,
+                          2.42861e-16 -0.780624 0.625,
+                          3.50259e-16 -0.433018 0.901385,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          2.42274e-16 -0.781832 0.62349,
+                          2.42861e-16 -0.780624 0.625,
+                          3.50097e-16 -0.433884 0.900969,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          3.50097e-16 -0.433884 0.900969,
+                          3.50259e-16 -0.433018 0.901385,
+                          3.88578e-16 1.02142e-16 1,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          3.50097e-16 -0.433884 0.900969,
+                          3.88578e-16 1.02142e-16 1,
+                          3.88578e-16 1.02142e-16 1,
+                          -3.88578e-16 -1.02142e-16 -1,
+                          -3.88578e-16 -1.02142e-16 -1,
+                          -3.63092e-16 0.356192 -0.934413,
+                          -3.58999e-16 0.382683 -0.92388,
+                          -3.63092e-16 0.356192 -0.934413,
+                          -2.89982e-16 0.665649 -0.746265,
+                          -3.58999e-16 0.382683 -0.92388,
+                          -3.88578e-16 -1.02142e-16 -1,
+                          -3.63092e-16 0.356192 -0.934413,
+                          -2.74766e-16 0.707107 -0.707107,
+                          -2.89982e-16 0.665649 -0.746265,
+                          -1.78842e-16 0.887791 -0.460246,
+                          -3.58999e-16 0.382683 -0.92388,
+                          -2.89982e-16 0.665649 -0.746265,
+                          -2.74766e-16 0.707107 -0.707107,
+                          -1.48702e-16 0.92388 -0.382683,
+                          -1.78842e-16 0.887791 -0.460246,
+                          -4.42482e-17 0.993495 -0.113872,
+                          -2.74766e-16 0.707107 -0.707107,
+                          -1.78842e-16 0.887791 -0.460246,
+                          -1.48702e-16 0.92388 -0.382683,
+                          -1.48702e-16 0.92388 -0.382683,
+                          -4.42482e-17 0.993495 -0.113872,
+                          0 1 -1.83691e-16,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          -1.27509e-16 -0.944628 -0.328142,
+                          -8.64668e-17 -0.974928 -0.222521,
+                          -2.42274e-16 -0.781832 -0.62349,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          -2.44823e-16 -0.776556 -0.630049,
+                          -2.42274e-16 -0.781832 -0.62349,
+                          -3.50097e-16 -0.433884 -0.900969,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          -1.74699e-16 -0.893237 -0.449586,
+                          -1.27509e-16 -0.944628 -0.328142,
+                          -2.42274e-16 -0.781832 -0.62349,
+                          -2.44823e-16 -0.776556 -0.630049,
+                          -1.74699e-16 -0.893237 -0.449586,
+                          -2.42274e-16 -0.781832 -0.62349,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          -3.60884e-16 -0.37076 -0.928729,
+                          -3.50097e-16 -0.433884 -0.900969,
+                          -3.88578e-16 -2.24603e-16 -1,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          -3.18118e-16 -0.57426 -0.818673,
+                          -2.44823e-16 -0.776556 -0.630049,
+                          -3.50097e-16 -0.433884 -0.900969,
+                          -3.60884e-16 -0.37076 -0.928729,
+                          -3.18118e-16 -0.57426 -0.818673,
+                          -3.50097e-16 -0.433884 -0.900969,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          0 -1 0,
+                          -3.81918e-16 -0.184353 -0.98286,
+                          -3.88578e-16 -2.24603e-16 -1,
+                          -3.88578e-16 -2.24603e-16 -1,
+                          -3.81918e-16 -0.184353 -0.98286,
+                          -3.60884e-16 -0.37076 -0.928729,
+                          -3.88578e-16 -2.24603e-16 -1,
+                          3.88578e-16 2.24603e-16 1,
+                          3.88578e-16 2.24603e-16 1,
+                          3.58999e-16 0.382683 0.92388,
+                          3.55538e-16 0.403517 0.914972,
+                          3.58999e-16 0.382683 0.92388,
+                          2.74766e-16 0.707107 0.707107,
+                          3.8509e-16 0.133686 0.991024,
+                          3.88578e-16 2.24603e-16 1,
+                          3.58999e-16 0.382683 0.92388,
+                          3.74905e-16 0.26294 0.964812,
+                          3.8509e-16 0.133686 0.991024,
+                          3.58999e-16 0.382683 0.92388,
+                          3.55538e-16 0.403517 0.914972,
+                          3.74905e-16 0.26294 0.964812,
+                          3.58999e-16 0.382683 0.92388,
+                          2.73525e-16 0.710286 0.703913,
+                          2.74766e-16 0.707107 0.707107,
+                          1.48702e-16 0.92388 0.382683,
+                          3.23727e-16 0.553111 0.833108,
+                          3.55538e-16 0.403517 0.914972,
+                          2.74766e-16 0.707107 0.707107,
+                          2.73525e-16 0.710286 0.703913,
+                          3.23727e-16 0.553111 0.833108,
+                          2.74766e-16 0.707107 0.707107,
+                          2.01913e-16 0.854398 0.519619,
+                          2.73525e-16 0.710286 0.703913,
+                          1.48702e-16 0.92388 0.382683,
+                          -0.493859 0.15625 0.855388,
+                          -0.493859 0.15625 0.855388,
+                          -0.499497 0.0448453 0.865154,
+                          -0.499973 0.0103031 0.865979,
+                          -0.499497 0.0448453 0.865154,
+                          -0.499011 -0.0628673 0.864312,
+                          -0.499973 0.0103031 0.865979,
+                          -0.493859 0.15625 0.855388,
+                          -0.499497 0.0448453 0.865154,
+                          -0.495267 -0.13727 0.857827,
+                          -0.499011 -0.0628673 0.864312,
+                          -0.491832 -0.180015 0.851878,
+                          -0.499973 0.0103031 0.865979,
+                          -0.499011 -0.0628673 0.864312,
+                          -0.495267 -0.13727 0.857827,
+                          -0.477225 -0.298368 0.826579,
+                          -0.491832 -0.180015 0.851878,
+                          -0.476229 -0.304672 0.824852,
+                          -0.495267 -0.13727 0.857827,
+                          -0.491832 -0.180015 0.851878,
+                          -0.477225 -0.298368 0.826579,
+                          -0.477225 -0.298368 0.826579,
+                          -0.476229 -0.304672 0.824852,
+                          -0.450057 -0.435654 0.779522,
+                          -0.444342 -0.458519 0.769623,
+                          -0.450057 -0.435654 0.779522,
+                          -0.415667 -0.555774 0.719956,
+                          -0.477225 -0.298368 0.826579,
+                          -0.450057 -0.435654 0.779522,
+                          -0.444342 -0.458519 0.769623,
+                          -0.417285 -0.5509 0.72276,
+                          -0.415667 -0.555774 0.719956,
+                          -0.403122 -0.591582 0.698228,
+                          -0.444342 -0.458519 0.769623,
+                          -0.415667 -0.555774 0.719956,
+                          -0.417285 -0.5509 0.72276 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -230.7 37.08 8.31104,
+                          -230.7 38.7562 9.89729,
+                          -230.7 37.9247 9.0921,
+                          -230.7 39.7398 -4.55489,
+                          -230.7 37.9247 9.0921,
+                          -230.7 38.7562 9.89729,
+                          -221.703 35.8959 12.4694,
+                          -230.7 38.7562 9.89729,
+                          -230.7 37.08 8.31104,
+                          -69.2 39.9998 4.049e-14,
+                          -230.7 39.7398 -4.55489,
+                          -230.7 38.7562 9.89729,
+                          -69.2 39.9998 4.049e-14,
+                          -230.7 38.7562 9.89729,
+                          -69.2 36.9547 15.308,
+                          -204.891 34.1759 20.7848,
+                          -69.2 36.9547 15.308,
+                          -230.7 38.7562 9.89729,
+                          -221.703 35.8959 12.4694,
+                          -204.891 34.1759 20.7848,
+                          -230.7 38.7562 9.89729,
+                          -230.7 39.7398 -4.55489,
+                          -230.7 37.08 8.31104,
+                          -230.7 37.9247 9.0921,
+                          -230.7 39.7398 -4.55489,
+                          -230.7 37.0222 -8.56373,
+                          -230.7 37.08 8.31104,
+                          -69.2 37.0468 -8.45697,
+                          -230.7 37.08 8.31104,
+                          -230.7 37.0222 -8.56373,
+                          -69.2 37.0468 8.45697,
+                          -230.7 37.08 8.31104,
+                          -69.2 37.0468 -8.45697,
+                          -221.703 35.8959 12.4694,
+                          -230.7 37.08 8.31104,
+                          -69.2 37.0468 8.45697,
+                          -230.7 35.5117 -18.4099,
+                          -230.7 29.6637 -23.75,
+                          -230.7 37.0222 -8.56373,
+                          -69.2 29.7103 -23.6916,
+                          -230.7 37.0222 -8.56373,
+                          -230.7 29.6637 -23.75,
+                          -230.7 39.7398 -4.55489,
+                          -230.7 35.5117 -18.4099,
+                          -230.7 37.0222 -8.56373,
+                          -69.2 37.0468 -8.45697,
+                          -230.7 37.0222 -8.56373,
+                          -69.2 29.7103 -23.6916,
+                          -230.7 26.6259 -29.8506,
+                          -230.7 16.4546 -34.2524,
+                          -230.7 29.6637 -23.75,
+                          -69.2 16.487 -34.2368,
+                          -230.7 29.6637 -23.75,
+                          -230.7 16.4546 -34.2524,
+                          -230.7 35.5117 -18.4099,
+                          -230.7 26.6259 -29.8506,
+                          -230.7 29.6637 -23.75,
+                          -69.2 29.7103 -23.6916,
+                          -230.7 29.6637 -23.75,
+                          -69.2 16.487 -34.2368,
+                          -230.7 14.2477 -37.3765,
+                          -230.7 -7.6712e-14 -38,
+                          -230.7 16.4546 -34.2524,
+                          -69.2 16.487 -34.2368,
+                          -230.7 16.4546 -34.2524,
+                          -230.7 -7.6712e-14 -38,
+                          -230.7 26.6259 -29.8506,
+                          -230.7 14.2477 -37.3765,
+                          -230.7 16.4546 -34.2524,
+                          -230.7 14.2477 -37.3765,
+                          -230.7 -7.69163e-14 -40,
+                          -230.7 -7.6712e-14 -38,
+                          -69.2 -8.91628e-14 -40,
+                          -230.7 -7.6712e-14 -38,
+                          -230.7 -7.69163e-14 -40,
+                          -69.2 -8.89585e-14 -38,
+                          -230.7 -7.6712e-14 -38,
+                          -69.2 -8.91628e-14 -40,
+                          -69.2 16.487 -34.2368,
+                          -230.7 -7.6712e-14 -38,
+                          -69.2 -8.89585e-14 -38,
+                          -69.2 -8.91628e-14 -40,
+                          -230.7 -7.69163e-14 -40,
+                          -230.7 14.2477 -37.3765,
+                          -69.2 15.3063 -36.9556,
+                          -230.7 14.2477 -37.3765,
+                          -230.7 26.6259 -29.8506,
+                          -69.2 15.3063 -36.9556,
+                          -69.2 -8.91628e-14 -40,
+                          -230.7 14.2477 -37.3765,
+                          -69.2 28.2833 -28.2851,
+                          -230.7 26.6259 -29.8506,
+                          -230.7 35.5117 -18.4099,
+                          -69.2 15.3063 -36.9556,
+                          -230.7 26.6259 -29.8506,
+                          -69.2 28.2833 -28.2851,
+                          -69.2 36.9547 -15.308,
+                          -230.7 35.5117 -18.4099,
+                          -230.7 39.7398 -4.55489,
+                          -69.2 28.2833 -28.2851,
+                          -230.7 35.5117 -18.4099,
+                          -69.2 36.9547 -15.308,
+                          -69.2 36.9547 -15.308,
+                          -230.7 39.7398 -4.55489,
+                          -69.2 39.9998 4.049e-14,
+                          -69.2 15.3063 -36.9556,
+                          -69.2 -8.89585e-14 -38,
+                          -69.2 -8.91628e-14 -40,
+                          -69.2 15.3063 -36.9556,
+                          -69.2 16.487 -34.2368,
+                          -69.2 -8.89585e-14 -38,
+                          -69.2 28.2833 -28.2851,
+                          -69.2 29.7103 -23.6916,
+                          -69.2 16.487 -34.2368,
+                          -69.2 15.3063 -36.9556,
+                          -69.2 28.2833 -28.2851,
+                          -69.2 16.487 -34.2368,
+                          -69.2 36.9547 -15.308,
+                          -69.2 37.0468 -8.45697,
+                          -69.2 29.7103 -23.6916,
+                          -69.2 28.2833 -28.2851,
+                          -69.2 36.9547 -15.308,
+                          -69.2 29.7103 -23.6916,
+                          -69.2 39.9998 4.049e-14,
+                          -69.2 37.0468 8.45697,
+                          -69.2 37.0468 -8.45697,
+                          -69.2 36.9547 -15.308,
+                          -69.2 39.9998 4.049e-14,
+                          -69.2 37.0468 -8.45697,
+                          -69.2 36.9547 15.308,
+                          -69.2 29.7103 23.6916,
+                          -69.2 37.0468 8.45697,
+                          -221.703 35.8959 12.4694,
+                          -69.2 37.0468 8.45697,
+                          -69.2 29.7103 23.6916,
+                          -69.2 39.9998 4.049e-14,
+                          -69.2 36.9547 15.308,
+                          -69.2 37.0468 8.45697,
+                          -69.2 28.2833 28.2851,
+                          -69.2 16.487 34.2368,
+                          -69.2 29.7103 23.6916,
+                          -193.919 29.5091 23.9419,
+                          -69.2 29.7103 23.6916,
+                          -69.2 16.487 34.2368,
+                          -69.2 36.9547 15.308,
+                          -69.2 28.2833 28.2851,
+                          -69.2 29.7103 23.6916,
+                          -210.99 33.943 17.0843,
+                          -221.703 35.8959 12.4694,
+                          -69.2 29.7103 23.6916,
+                          -193.919 29.5091 23.9419,
+                          -210.99 33.943 17.0843,
+                          -69.2 29.7103 23.6916,
+                          -69.2 15.3063 36.9556,
+                          -69.2 -7.65422e-14 38,
+                          -69.2 16.487 34.2368,
+                          -164.482 14.0889 35.2917,
+                          -69.2 16.487 34.2368,
+                          -69.2 -7.65422e-14 38,
+                          -69.2 28.2833 28.2851,
+                          -69.2 15.3063 36.9556,
+                          -69.2 16.487 34.2368,
+                          -175.19 21.8219 31.1096,
+                          -193.919 29.5091 23.9419,
+                          -69.2 16.487 34.2368,
+                          -164.482 14.0889 35.2917,
+                          -175.19 21.8219 31.1096,
+                          -69.2 16.487 34.2368,
+                          -69.2 15.3063 36.9556,
+                          -69.2 -7.6093e-14 40,
+                          -69.2 -7.65422e-14 38,
+                          -156.597 -6.94657e-14 40,
+                          -69.2 -7.65422e-14 38,
+                          -69.2 -7.6093e-14 40,
+                          -160.061 -6.91624e-14 38,
+                          -69.2 -7.65422e-14 38,
+                          -156.597 -6.94657e-14 40,
+                          -160.015 7.00542 37.3487,
+                          -69.2 -7.65422e-14 38,
+                          -160.061 -6.91624e-14 38,
+                          -160.015 7.00542 37.3487,
+                          -164.482 14.0889 35.2917,
+                          -69.2 -7.65422e-14 38,
+                          -156.597 -6.94657e-14 40,
+                          -69.2 -7.6093e-14 40,
+                          -69.2 15.3063 36.9556,
+                          -162.877 16.1407 36.5989,
+                          -69.2 15.3063 36.9556,
+                          -69.2 28.2833 28.2851,
+                          -156.136 5.34742 39.641,
+                          -156.597 -6.94657e-14 40,
+                          -69.2 15.3063 36.9556,
+                          -158.045 10.5176 38.5925,
+                          -156.136 5.34742 39.641,
+                          -69.2 15.3063 36.9556,
+                          -162.877 16.1407 36.5989,
+                          -158.045 10.5176 38.5925,
+                          -69.2 15.3063 36.9556,
+                          -185.521 28.4114 28.1565,
+                          -69.2 28.2833 28.2851,
+                          -69.2 36.9547 15.308,
+                          -171.546 22.1244 33.3243,
+                          -162.877 16.1407 36.5989,
+                          -69.2 28.2833 28.2851,
+                          -185.521 28.4114 28.1565,
+                          -171.546 22.1244 33.3243,
+                          -69.2 28.2833 28.2851,
+                          -204.891 34.1759 20.7848,
+                          -185.521 28.4114 28.1565,
+                          -69.2 36.9547 15.308,
+                          -160.061 -6.91624e-14 38,
+                          -156.597 -6.94657e-14 40,
+                          -156.136 5.34742 39.641,
+                          -160.015 7.00542 37.3487,
+                          -156.136 5.34742 39.641,
+                          -158.045 10.5176 38.5925,
+                          -160.015 7.00542 37.3487,
+                          -160.061 -6.91624e-14 38,
+                          -156.136 5.34742 39.641,
+                          -164.482 14.0889 35.2917,
+                          -158.045 10.5176 38.5925,
+                          -162.877 16.1407 36.5989,
+                          -160.015 7.00542 37.3487,
+                          -158.045 10.5176 38.5925,
+                          -164.482 14.0889 35.2917,
+                          -175.19 21.8219 31.1096,
+                          -162.877 16.1407 36.5989,
+                          -171.546 22.1244 33.3243,
+                          -164.482 14.0889 35.2917,
+                          -162.877 16.1407 36.5989,
+                          -175.19 21.8219 31.1096,
+                          -175.19 21.8219 31.1096,
+                          -171.546 22.1244 33.3243,
+                          -185.521 28.4114 28.1565,
+                          -193.919 29.5091 23.9419,
+                          -185.521 28.4114 28.1565,
+                          -204.891 34.1759 20.7848,
+                          -175.19 21.8219 31.1096,
+                          -185.521 28.4114 28.1565,
+                          -193.919 29.5091 23.9419,
+                          -210.99 33.943 17.0843,
+                          -204.891 34.1759 20.7848,
+                          -221.703 35.8959 12.4694,
+                          -193.919 29.5091 23.9419,
+                          -204.891 34.1759 20.7848,
+                          -210.99 33.943 17.0843 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0 0 1
+    }
+    Separator {
+        Normal {
+            vector      [ -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          1.68598e-16 -0.900969 0.433884,
+                          2.15813e-16 -0.831589 0.555392,
+                          1.41559e-16 -0.931282 0.3643,
+                          -0.346117 0.721672 0.599493,
+                          -0.277453 0.831913 0.480563,
+                          -0.270845 0.840578 0.469118,
+                          2.42274e-16 -0.781832 0.62349,
+                          2.15813e-16 -0.831589 0.555392,
+                          1.68598e-16 -0.900969 0.433884,
+                          2.82328e-16 -0.687095 0.726567,
+                          2.15813e-16 -0.831589 0.555392,
+                          2.42274e-16 -0.781832 0.62349,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          8.64668e-17 -0.974928 0.222521,
+                          1.41559e-16 -0.931282 0.3643,
+                          6.07282e-17 -0.987712 0.156283,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          1.68598e-16 -0.900969 0.433884,
+                          1.41559e-16 -0.931282 0.3643,
+                          8.64668e-17 -0.974928 0.222521,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          0 -1 1.83691e-16,
+                          6.07282e-17 -0.987712 0.156283,
+                          -2.29241e-17 -0.998258 -0.0589948,
+                          8.64668e-17 -0.974928 0.222521,
+                          6.07282e-17 -0.987712 0.156283,
+                          0 -1 1.83691e-16,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -8.64668e-17 -0.974928 -0.222521,
+                          -2.29241e-17 -0.998258 -0.0589948,
+                          -1.05512e-16 -0.962429 -0.271534,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          0 -1 1.83691e-16,
+                          -2.29241e-17 -0.998258 -0.0589948,
+                          -8.64668e-17 -0.974928 -0.222521,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1.68598e-16 -0.900969 -0.433884,
+                          -1.05512e-16 -0.962429 -0.271534,
+                          -1.83199e-16 -0.881887 -0.47146,
+                          -8.64668e-17 -0.974928 -0.222521,
+                          -1.05512e-16 -0.962429 -0.271534,
+                          -1.68598e-16 -0.900969 -0.433884,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -2.42274e-16 -0.781832 -0.62349,
+                          -1.83199e-16 -0.881887 -0.47146,
+                          -2.52376e-16 -0.760374 -0.649486,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1.68598e-16 -0.900969 -0.433884,
+                          -1.83199e-16 -0.881887 -0.47146,
+                          -2.42274e-16 -0.781832 -0.62349,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -3.03803e-16 -0.62349 -0.781832,
+                          -2.52376e-16 -0.760374 -0.649486,
+                          -3.09829e-16 -0.603531 -0.797339,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -2.42274e-16 -0.781832 -0.62349,
+                          -2.52376e-16 -0.760374 -0.649486,
+                          -3.03803e-16 -0.62349 -0.781832,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -3.50097e-16 -0.433884 -0.900969,
+                          -3.09829e-16 -0.603531 -0.797339,
+                          -3.52887e-16 -0.418645 -0.90815,
+                          -3.03803e-16 -0.62349 -0.781832,
+                          -3.09829e-16 -0.603531 -0.797339,
+                          -3.50097e-16 -0.433884 -0.900969,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -3.78836e-16 -0.222521 -0.974928,
+                          -3.52887e-16 -0.418645 -0.90815,
+                          -3.7955e-16 -0.214304 -0.976767,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -3.50097e-16 -0.433884 -0.900969,
+                          -3.52887e-16 -0.418645 -0.90815,
+                          -3.78836e-16 -0.222521 -0.974928,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -1 7.58296e-17 5.55112e-17,
+                          -3.78836e-16 -0.222521 -0.974928,
+                          -3.7955e-16 -0.214304 -0.976767,
+                          -3.88578e-16 -2.24603e-16 -1,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          -3.78836e-16 -0.222521 -0.974928,
+                          -3.88578e-16 -2.24603e-16 -1,
+                          -3.88578e-16 -2.24603e-16 -1,
+                          3.88578e-16 2.24603e-16 1,
+                          3.88578e-16 2.24603e-16 1,
+                          3.53519e-16 0.415098 0.909777,
+                          3.50097e-16 0.433884 0.900969,
+                          3.53519e-16 0.415098 0.909777,
+                          2.54678e-16 0.755274 0.655409,
+                          3.88578e-16 2.24603e-16 1,
+                          3.53519e-16 0.415098 0.909777,
+                          3.50097e-16 0.433884 0.900969,
+                          2.42274e-16 0.781832 0.62349,
+                          2.54678e-16 0.755274 0.655409,
+                          1.09893e-16 0.959177 0.282808,
+                          3.50097e-16 0.433884 0.900969,
+                          2.54678e-16 0.755274 0.655409,
+                          2.42274e-16 0.781832 0.62349,
+                          8.64668e-17 0.974928 0.222521,
+                          1.09893e-16 0.959177 0.282808,
+                          -5.47141e-17 0.990037 -0.140806,
+                          2.42274e-16 0.781832 0.62349,
+                          1.09893e-16 0.959177 0.282808,
+                          8.64668e-17 0.974928 0.222521,
+                          -8.64668e-17 0.974928 -0.222521,
+                          -5.47141e-17 0.990037 -0.140806,
+                          -2.09451e-16 0.842293 -0.539019,
+                          8.64668e-17 0.974928 0.222521,
+                          -5.47141e-17 0.990037 -0.140806,
+                          -8.64668e-17 0.974928 -0.222521,
+                          -0.346117 0.721672 0.599493,
+                          -0.283973 0.823066 0.491856,
+                          -0.277453 0.831913 0.480563,
+                          -8.64668e-17 0.974928 -0.222521,
+                          -2.09451e-16 0.842293 -0.539019,
+                          -2.42274e-16 0.781832 -0.62349,
+                          -2.78749e-16 0.696706 -0.717357,
+                          -2.42274e-16 0.781832 -0.62349,
+                          -2.09451e-16 0.842293 -0.539019,
+                          -0.353202 0.707809 0.611764,
+                          -0.283973 0.823066 0.491856,
+                          -0.346117 0.721672 0.599493,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          3.80301e-16 -0.205299 0.978699,
+                          3.78836e-16 -0.222521 0.974928,
+                          3.88578e-16 1.02142e-16 1,
+                          3.80301e-16 -0.205299 0.978699,
+                          3.88578e-16 1.02142e-16 1,
+                          3.88578e-16 1.02142e-16 1,
+                          0 1 0,
+                          0 1 0,
+                          0 1 0,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          -3.88578e-16 -1.02142e-16 -1,
+                          -3.88578e-16 -1.02142e-16 -1,
+                          -3.50097e-16 0.433884 -0.900969,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          -3.22361e-16 0.55837 -0.829592,
+                          -3.50097e-16 0.433884 -0.900969,
+                          -2.42274e-16 0.781832 -0.62349,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          -3.79745e-16 0.212003 -0.977269,
+                          -3.88578e-16 -1.02142e-16 -1,
+                          -3.50097e-16 0.433884 -0.900969,
+                          -3.59124e-16 0.381905 -0.924201,
+                          -3.79745e-16 0.212003 -0.977269,
+                          -3.50097e-16 0.433884 -0.900969,
+                          -3.22361e-16 0.55837 -0.829592,
+                          -3.59124e-16 0.381905 -0.924201,
+                          -3.50097e-16 0.433884 -0.900969,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          -2.78749e-16 0.696706 -0.717357,
+                          -3.22361e-16 0.55837 -0.829592,
+                          -2.42274e-16 0.781832 -0.62349,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          1 -7.58296e-17 -5.55112e-17,
+                          2.82328e-16 -0.687095 0.726567,
+                          2.42274e-16 -0.781832 0.62349,
+                          3.03803e-16 -0.62349 0.781832,
+                          3.25323e-16 -0.546876 0.837213,
+                          3.03803e-16 -0.62349 0.781832,
+                          3.50097e-16 -0.433884 0.900969,
+                          3.25323e-16 -0.546876 0.837213,
+                          2.82328e-16 -0.687095 0.726567,
+                          3.03803e-16 -0.62349 0.781832,
+                          3.61287e-16 -0.36815 0.929766,
+                          3.50097e-16 -0.433884 0.900969,
+                          3.78836e-16 -0.222521 0.974928,
+                          3.61287e-16 -0.36815 0.929766,
+                          3.25323e-16 -0.546876 0.837213,
+                          3.50097e-16 -0.433884 0.900969,
+                          3.80301e-16 -0.205299 0.978699,
+                          3.61287e-16 -0.36815 0.929766,
+                          3.78836e-16 -0.222521 0.974928,
+                          -0.473014 0.324085 0.819284,
+                          -0.472824 0.325194 0.818955,
+                          -0.493859 0.15625 0.855388,
+                          -0.473014 0.324085 0.819284,
+                          -0.493859 0.15625 0.855388,
+                          -0.493859 0.15625 0.855388,
+                          -0.353202 0.707809 0.611764,
+                          -0.346117 0.721672 0.599493,
+                          -0.397624 0.606284 0.688705,
+                          -0.400639 0.598293 0.693927,
+                          -0.397624 0.606284 0.688705,
+                          -0.444165 0.459207 0.769316,
+                          -0.353202 0.707809 0.611764,
+                          -0.397624 0.606284 0.688705,
+                          -0.400639 0.598293 0.693927,
+                          -0.444324 0.458592 0.769591,
+                          -0.444165 0.459207 0.769316,
+                          -0.472824 0.325194 0.818955,
+                          -0.400639 0.598293 0.693927,
+                          -0.444165 0.459207 0.769316,
+                          -0.444324 0.458592 0.769591,
+                          -0.444324 0.458592 0.769591,
+                          -0.472824 0.325194 0.818955,
+                          -0.473014 0.324085 0.819284 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -230.7 -32.4318 21.2055,
+                          -230.7 -36.7859 14.3887,
+                          -230.7 -32.8477 21.938,
+                          -69.2 -35.5883 17.1378,
+                          -230.7 -32.8477 21.938,
+                          -230.7 -36.7859 14.3887,
+                          -204.537 -27.1403 28.6994,
+                          -230.7 -32.4318 21.2055,
+                          -230.7 -32.8477 21.938,
+                          -69.2 -30.8831 24.6268,
+                          -230.7 -32.8477 21.938,
+                          -69.2 -35.5883 17.1378,
+                          -204.537 -27.1403 28.6994,
+                          -230.7 -32.8477 21.938,
+                          -69.2 -30.8831 24.6268,
+                          -230.7 -37.6211 5.3512,
+                          -230.7 -39.0143 6.17379,
+                          -230.7 -36.7859 14.3887,
+                          -69.2 -38.5092 8.7908,
+                          -230.7 -36.7859 14.3887,
+                          -230.7 -39.0143 6.17379,
+                          -230.7 -32.0071 20.4827,
+                          -230.7 -37.6211 5.3512,
+                          -230.7 -36.7859 14.3887,
+                          -230.7 -32.4318 21.2055,
+                          -230.7 -32.0071 20.4827,
+                          -230.7 -36.7859 14.3887,
+                          -69.2 -35.5883 17.1378,
+                          -230.7 -36.7859 14.3887,
+                          -69.2 -38.5092 8.7908,
+                          -230.7 -37.6211 5.3512,
+                          -230.7 -39.4312 -2.32932,
+                          -230.7 -39.0143 6.17379,
+                          -69.2 -39.5 6.58426e-14,
+                          -230.7 -39.0143 6.17379,
+                          -230.7 -39.4312 -2.32932,
+                          -69.2 -38.5092 8.7908,
+                          -230.7 -39.0143 6.17379,
+                          -69.2 -39.5 6.58426e-14,
+                          -230.7 -36.4483 -10.7478,
+                          -230.7 -38.0155 -10.7268,
+                          -230.7 -39.4312 -2.32932,
+                          -69.2 -38.5092 -8.7908,
+                          -230.7 -39.4312 -2.32932,
+                          -230.7 -38.0155 -10.7268,
+                          -230.7 -37.6211 5.3512,
+                          -230.7 -36.4483 -10.7478,
+                          -230.7 -39.4312 -2.32932,
+                          -69.2 -39.5 6.58426e-14,
+                          -230.7 -39.4312 -2.32932,
+                          -69.2 -38.5092 -8.7908,
+                          -230.7 -36.4483 -10.7478,
+                          -230.7 -34.8343 -18.6226,
+                          -230.7 -38.0155 -10.7268,
+                          -69.2 -35.5883 -17.1378,
+                          -230.7 -38.0155 -10.7268,
+                          -230.7 -34.8343 -18.6226,
+                          -69.2 -38.5092 -8.7908,
+                          -230.7 -38.0155 -10.7268,
+                          -69.2 -35.5883 -17.1378,
+                          -230.7 -28.7011 -24.9046,
+                          -230.7 -30.0355 -25.6536,
+                          -230.7 -34.8343 -18.6226,
+                          -69.2 -30.8831 -24.6268,
+                          -230.7 -34.8343 -18.6226,
+                          -230.7 -30.0355 -25.6536,
+                          -230.7 -36.4483 -10.7478,
+                          -230.7 -28.7011 -24.9046,
+                          -230.7 -34.8343 -18.6226,
+                          -69.2 -35.5883 -17.1378,
+                          -230.7 -34.8343 -18.6226,
+                          -69.2 -30.8831 -24.6268,
+                          -230.7 -15.7731 -34.5716,
+                          -230.7 -23.8387 -31.4955,
+                          -230.7 -30.0355 -25.6536,
+                          -69.2 -24.6268 -30.8831,
+                          -230.7 -30.0355 -25.6536,
+                          -230.7 -23.8387 -31.4955,
+                          -230.7 -28.7011 -24.9046,
+                          -230.7 -15.7731 -34.5716,
+                          -230.7 -30.0355 -25.6536,
+                          -69.2 -30.8831 -24.6268,
+                          -230.7 -30.0355 -25.6536,
+                          -69.2 -24.6268 -30.8831,
+                          -230.7 -15.7731 -34.5716,
+                          -230.7 -16.5358 -35.872,
+                          -230.7 -23.8387 -31.4955,
+                          -69.2 -17.1378 -35.5883,
+                          -230.7 -23.8387 -31.4955,
+                          -230.7 -16.5358 -35.872,
+                          -69.2 -24.6268 -30.8831,
+                          -230.7 -23.8387 -31.4955,
+                          -69.2 -17.1378 -35.5883,
+                          -230.7 -8.89151e-14 -38,
+                          -230.7 -8.46609 -38.5819,
+                          -230.7 -16.5358 -35.872,
+                          -69.2 -8.7908 -38.5092,
+                          -230.7 -16.5358 -35.872,
+                          -230.7 -8.46609 -38.5819,
+                          -230.7 -15.7731 -34.5716,
+                          -230.7 -8.89151e-14 -38,
+                          -230.7 -16.5358 -35.872,
+                          -69.2 -17.1378 -35.5883,
+                          -230.7 -16.5358 -35.872,
+                          -69.2 -8.7908 -38.5092,
+                          -230.7 -8.89151e-14 -38,
+                          -230.7 -8.9252e-14 -39.5,
+                          -230.7 -8.46609 -38.5819,
+                          -69.2 -8.7908 -38.5092,
+                          -230.7 -8.46609 -38.5819,
+                          -230.7 -8.9252e-14 -39.5,
+                          -69.2 -1.01162e-13 -38,
+                          -230.7 -8.9252e-14 -39.5,
+                          -230.7 -8.89151e-14 -38,
+                          -69.2 -1.01498e-13 -39.5,
+                          -230.7 -8.9252e-14 -39.5,
+                          -69.2 -1.01162e-13 -38,
+                          -69.2 -8.7908 -38.5092,
+                          -230.7 -8.9252e-14 -39.5,
+                          -69.2 -1.01498e-13 -39.5,
+                          -69.2 -1.01162e-13 -38,
+                          -230.7 -8.89151e-14 -38,
+                          -230.7 -15.7731 -34.5716,
+                          -69.2 -16.487 -34.2368,
+                          -230.7 -15.7731 -34.5716,
+                          -230.7 -28.7011 -24.9046,
+                          -69.2 -1.01162e-13 -38,
+                          -230.7 -15.7731 -34.5716,
+                          -69.2 -16.487 -34.2368,
+                          -69.2 -29.7103 -23.6916,
+                          -230.7 -28.7011 -24.9046,
+                          -230.7 -36.4483 -10.7478,
+                          -69.2 -16.487 -34.2368,
+                          -230.7 -28.7011 -24.9046,
+                          -69.2 -29.7103 -23.6916,
+                          -69.2 -37.0468 -8.45697,
+                          -230.7 -36.4483 -10.7478,
+                          -230.7 -37.6211 5.3512,
+                          -69.2 -29.7103 -23.6916,
+                          -230.7 -36.4483 -10.7478,
+                          -69.2 -37.0468 -8.45697,
+                          -69.2 -37.0468 8.45697,
+                          -230.7 -37.6211 5.3512,
+                          -230.7 -32.0071 20.4827,
+                          -69.2 -37.0468 -8.45697,
+                          -230.7 -37.6211 5.3512,
+                          -69.2 -37.0468 8.45697,
+                          -204.537 -27.1403 28.6994,
+                          -230.7 -32.0071 20.4827,
+                          -230.7 -32.4318 21.2055,
+                          -69.2 -37.0468 8.45697,
+                          -230.7 -32.0071 20.4827,
+                          -69.2 -29.7103 23.6916,
+                          -205.67 -26.4748 27.2596,
+                          -69.2 -29.7103 23.6916,
+                          -230.7 -32.0071 20.4827,
+                          -205.67 -26.4748 27.2596,
+                          -230.7 -32.0071 20.4827,
+                          -204.537 -27.1403 28.6994,
+                          -69.2 -8.7908 38.5092,
+                          -69.2 -8.87452e-14 38,
+                          -69.2 -8.8592e-14 39.5,
+                          -160.061 -8.18553e-14 38,
+                          -69.2 -8.8592e-14 39.5,
+                          -69.2 -8.87452e-14 38,
+                          -162.959 -8.10932 38.6586,
+                          -69.2 -8.7908 38.5092,
+                          -69.2 -8.8592e-14 39.5,
+                          -162.959 -8.10932 38.6586,
+                          -69.2 -8.8592e-14 39.5,
+                          -157.463 -8.20828e-14 39.5,
+                          -160.061 -8.18553e-14 38,
+                          -157.463 -8.20828e-14 39.5,
+                          -69.2 -8.8592e-14 39.5,
+                          -69.2 -17.1378 35.5883,
+                          -69.2 -16.487 34.2368,
+                          -69.2 -8.87452e-14 38,
+                          -160.061 -8.18553e-14 38,
+                          -69.2 -8.87452e-14 38,
+                          -69.2 -16.487 34.2368,
+                          -69.2 -8.7908 38.5092,
+                          -69.2 -17.1378 35.5883,
+                          -69.2 -8.87452e-14 38,
+                          -69.2 -30.8831 24.6268,
+                          -69.2 -29.7103 23.6916,
+                          -69.2 -16.487 34.2368,
+                          -189.175 -21.218 31.5245,
+                          -69.2 -16.487 34.2368,
+                          -69.2 -29.7103 23.6916,
+                          -69.2 -24.6268 30.8831,
+                          -69.2 -30.8831 24.6268,
+                          -69.2 -16.487 34.2368,
+                          -69.2 -17.1378 35.5883,
+                          -69.2 -24.6268 30.8831,
+                          -69.2 -16.487 34.2368,
+                          -165.559 -8.0561 37.1362,
+                          -160.061 -8.18553e-14 38,
+                          -69.2 -16.487 34.2368,
+                          -174.561 -14.5124 35.1197,
+                          -165.559 -8.0561 37.1362,
+                          -69.2 -16.487 34.2368,
+                          -189.175 -21.218 31.5245,
+                          -174.561 -14.5124 35.1197,
+                          -69.2 -16.487 34.2368,
+                          -69.2 -38.5092 8.7908,
+                          -69.2 -37.0468 8.45697,
+                          -69.2 -29.7103 23.6916,
+                          -69.2 -35.5883 17.1378,
+                          -69.2 -38.5092 8.7908,
+                          -69.2 -29.7103 23.6916,
+                          -69.2 -30.8831 24.6268,
+                          -69.2 -35.5883 17.1378,
+                          -69.2 -29.7103 23.6916,
+                          -205.67 -26.4748 27.2596,
+                          -189.175 -21.218 31.5245,
+                          -69.2 -29.7103 23.6916,
+                          -69.2 -39.5 6.58426e-14,
+                          -69.2 -37.0468 -8.45697,
+                          -69.2 -37.0468 8.45697,
+                          -69.2 -38.5092 8.7908,
+                          -69.2 -39.5 6.58426e-14,
+                          -69.2 -37.0468 8.45697,
+                          -69.2 -35.5883 -17.1378,
+                          -69.2 -29.7103 -23.6916,
+                          -69.2 -37.0468 -8.45697,
+                          -69.2 -38.5092 -8.7908,
+                          -69.2 -35.5883 -17.1378,
+                          -69.2 -37.0468 -8.45697,
+                          -69.2 -39.5 6.58426e-14,
+                          -69.2 -38.5092 -8.7908,
+                          -69.2 -37.0468 -8.45697,
+                          -69.2 -24.6268 -30.8831,
+                          -69.2 -16.487 -34.2368,
+                          -69.2 -29.7103 -23.6916,
+                          -69.2 -30.8831 -24.6268,
+                          -69.2 -24.6268 -30.8831,
+                          -69.2 -29.7103 -23.6916,
+                          -69.2 -35.5883 -17.1378,
+                          -69.2 -30.8831 -24.6268,
+                          -69.2 -29.7103 -23.6916,
+                          -69.2 -17.1378 -35.5883,
+                          -69.2 -1.01162e-13 -38,
+                          -69.2 -16.487 -34.2368,
+                          -69.2 -24.6268 -30.8831,
+                          -69.2 -17.1378 -35.5883,
+                          -69.2 -16.487 -34.2368,
+                          -69.2 -8.7908 -38.5092,
+                          -69.2 -1.01498e-13 -39.5,
+                          -69.2 -1.01162e-13 -38,
+                          -69.2 -17.1378 -35.5883,
+                          -69.2 -8.7908 -38.5092,
+                          -69.2 -1.01162e-13 -38,
+                          -204.537 -27.1403 28.6994,
+                          -69.2 -30.8831 24.6268,
+                          -69.2 -24.6268 30.8831,
+                          -187.077 -21.6016 33.0699,
+                          -69.2 -24.6268 30.8831,
+                          -69.2 -17.1378 35.5883,
+                          -187.077 -21.6016 33.0699,
+                          -204.537 -27.1403 28.6994,
+                          -69.2 -24.6268 30.8831,
+                          -171.809 -14.5419 36.7258,
+                          -69.2 -17.1378 35.5883,
+                          -69.2 -8.7908 38.5092,
+                          -171.809 -14.5419 36.7258,
+                          -187.077 -21.6016 33.0699,
+                          -69.2 -17.1378 35.5883,
+                          -162.959 -8.10932 38.6586,
+                          -171.809 -14.5419 36.7258,
+                          -69.2 -8.7908 38.5092,
+                          -165.559 -8.0561 37.1362,
+                          -162.959 -8.10932 38.6586,
+                          -157.463 -8.20828e-14 39.5,
+                          -165.559 -8.0561 37.1362,
+                          -157.463 -8.20828e-14 39.5,
+                          -160.061 -8.18553e-14 38,
+                          -205.67 -26.4748 27.2596,
+                          -204.537 -27.1403 28.6994,
+                          -187.077 -21.6016 33.0699,
+                          -189.175 -21.218 31.5245,
+                          -187.077 -21.6016 33.0699,
+                          -171.809 -14.5419 36.7258,
+                          -205.67 -26.4748 27.2596,
+                          -187.077 -21.6016 33.0699,
+                          -189.175 -21.218 31.5245,
+                          -174.561 -14.5124 35.1197,
+                          -171.809 -14.5419 36.7258,
+                          -162.959 -8.10932 38.6586,
+                          -189.175 -21.218 31.5245,
+                          -171.809 -14.5419 36.7258,
+                          -174.561 -14.5124 35.1197,
+                          -174.561 -14.5124 35.1197,
+                          -162.959 -8.10932 38.6586,
+                          -165.559 -8.0561 37.1362 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/torso/hd_torso.iv b/data/RobotAPI/robots/Armar3/fullmodel/armar/torso/hd_torso.iv
new file mode 100644
index 0000000000000000000000000000000000000000..75a56ce62a2313bee0f24df700198cdaf8af68bc
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/torso/hd_torso.iv
@@ -0,0 +1,22548 @@
+#Inventor V1.0 ascii
+
+Separator {
+    ShapeHints {
+        hints    (SOLID | ORDERED | CONVEX)
+    }
+    Units {
+            units MILLIMETERS
+    }
+
+    Material {
+        diffuseColor    0.65 0.65 0.65
+    }
+    Separator {
+        Normal {
+            vector      [ -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.866282 7.64751e-17 0.499556,
+                          0.866282 7.64751e-17 0.499556,
+                          0.866282 7.64751e-17 0.499556,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.866282 7.64751e-17 0.499556,
+                          0.866282 7.64751e-17 0.499556,
+                          0.866282 7.64751e-17 0.499556,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -0.866963 -2.98207e-16 0.498372,
+                          -0.866963 -2.98207e-16 0.498372,
+                          -0.866963 -2.98207e-16 0.498372,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -0.866963 -2.98207e-16 0.498372,
+                          -0.866963 -2.98207e-16 0.498372,
+                          -0.866963 -2.98207e-16 0.498372,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -2.44921e-16 2.22045e-16 -1,
+                          -2.44921e-16 2.22045e-16 -1,
+                          -0.587785 5.2485e-17 -0.809017,
+                          0.587785 3.06791e-16 -0.809017,
+                          0.587785 3.06791e-16 -0.809017,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.587785 3.06791e-16 -0.809017,
+                          0 2.22045e-16 -1,
+                          -0.587785 5.2485e-17 -0.809017,
+                          -0.587785 5.2485e-17 -0.809017,
+                          -0.951057 -1.37122e-16 -0.309017,
+                          -0.587785 5.2485e-17 -0.809017,
+                          -2.44921e-16 2.22045e-16 -1,
+                          -0.587785 5.2485e-17 -0.809017,
+                          -0.951057 -1.37122e-16 -0.309017,
+                          -0.951057 -1.37122e-16 -0.309017,
+                          -0.951057 -2.74353e-16 0.309017,
+                          -0.951057 -1.37122e-16 -0.309017,
+                          -0.587785 5.2485e-17 -0.809017,
+                          -0.951057 -1.37122e-16 -0.309017,
+                          -0.951057 -2.74353e-16 0.309017,
+                          -0.951057 -2.74353e-16 0.309017,
+                          -0.587785 -3.06791e-16 0.809017,
+                          -0.951057 -2.74353e-16 0.309017,
+                          -0.951057 -1.37122e-16 -0.309017,
+                          -0.951057 -2.74353e-16 0.309017,
+                          -0.587785 -3.06791e-16 0.809017,
+                          -0.587785 -3.06791e-16 0.809017,
+                          1.22461e-16 -2.22045e-16 1,
+                          -0.587785 -3.06791e-16 0.809017,
+                          -0.951057 -2.74353e-16 0.309017,
+                          -0.587785 -3.06791e-16 0.809017,
+                          1.22461e-16 -2.22045e-16 1,
+                          1.22461e-16 -2.22045e-16 1,
+                          0.587785 -5.2485e-17 0.809017,
+                          -0.587785 -3.06791e-16 0.809017,
+                          1.22461e-16 -2.22045e-16 1,
+                          1.22461e-16 -2.22045e-16 1,
+                          0.587785 -5.2485e-17 0.809017,
+                          0.587785 -5.2485e-17 0.809017,
+                          0.951057 1.37122e-16 0.309017,
+                          0.587785 -5.2485e-17 0.809017,
+                          1.22461e-16 -2.22045e-16 1,
+                          0.587785 -5.2485e-17 0.809017,
+                          0.951057 1.37122e-16 0.309017,
+                          0.951057 1.37122e-16 0.309017,
+                          0.951057 2.74353e-16 -0.309017,
+                          0.951057 1.37122e-16 0.309017,
+                          0.587785 -5.2485e-17 0.809017,
+                          0.951057 1.37122e-16 0.309017,
+                          0.951057 2.74353e-16 -0.309017,
+                          0.951057 2.74353e-16 -0.309017,
+                          0.587785 3.06791e-16 -0.809017,
+                          0.951057 2.74353e-16 -0.309017,
+                          0.951057 1.37122e-16 0.309017,
+                          0.951057 2.74353e-16 -0.309017,
+                          0.587785 3.06791e-16 -0.809017,
+                          0.951057 2.74353e-16 -0.309017,
+                          0.587785 3.06791e-16 -0.809017,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          0.809017 4.44964e-17 0.587785,
+                          0.809017 3.05525e-16 -0.587785,
+                          0.809017 3.05525e-16 -0.587785,
+                          1 2.16325e-16 -2.44921e-16,
+                          0.809017 3.05525e-16 -0.587785,
+                          1 2.16325e-16 -2.44921e-16,
+                          1 2.16325e-16 -2.44921e-16,
+                          0.809017 4.44964e-17 0.587785,
+                          0.809017 4.44964e-17 0.587785,
+                          0.309017 -1.44329e-16 0.951057,
+                          0.809017 4.44964e-17 0.587785,
+                          1 2.16325e-16 0,
+                          0.809017 4.44964e-17 0.587785,
+                          0.309017 -1.44329e-16 0.951057,
+                          0.309017 -1.44329e-16 0.951057,
+                          -0.309017 -2.78025e-16 0.951057,
+                          0.809017 4.44964e-17 0.587785,
+                          0.309017 -1.44329e-16 0.951057,
+                          0.309017 -1.44329e-16 0.951057,
+                          -0.309017 -2.78025e-16 0.951057,
+                          -0.309017 -2.78025e-16 0.951057,
+                          -0.809017 -3.05525e-16 0.587785,
+                          0.309017 -1.44329e-16 0.951057,
+                          -0.309017 -2.78025e-16 0.951057,
+                          -0.309017 -2.78025e-16 0.951057,
+                          -0.809017 -3.05525e-16 0.587785,
+                          -0.809017 -3.05525e-16 0.587785,
+                          -1 -2.16325e-16 1.22461e-16,
+                          -0.309017 -2.78025e-16 0.951057,
+                          -0.809017 -3.05525e-16 0.587785,
+                          -0.809017 -3.05525e-16 0.587785,
+                          -1 -2.16325e-16 1.22461e-16,
+                          -1 -2.16325e-16 1.22461e-16,
+                          -0.809017 -4.44964e-17 -0.587785,
+                          -0.809017 -3.05525e-16 0.587785,
+                          -1 -2.16325e-16 1.22461e-16,
+                          -1 -2.16325e-16 1.22461e-16,
+                          -0.809017 -4.44964e-17 -0.587785,
+                          -0.809017 -4.44964e-17 -0.587785,
+                          -0.309017 1.44329e-16 -0.951057,
+                          -1 -2.16325e-16 1.22461e-16,
+                          -0.809017 -4.44964e-17 -0.587785,
+                          -0.809017 -4.44964e-17 -0.587785,
+                          -0.309017 1.44329e-16 -0.951057,
+                          -0.309017 1.44329e-16 -0.951057,
+                          0.309017 2.78025e-16 -0.951057,
+                          -0.809017 -4.44964e-17 -0.587785,
+                          -0.309017 1.44329e-16 -0.951057,
+                          -0.309017 1.44329e-16 -0.951057,
+                          0.309017 2.78025e-16 -0.951057,
+                          0.309017 2.78025e-16 -0.951057,
+                          0.809017 3.05525e-16 -0.587785,
+                          -0.309017 1.44329e-16 -0.951057,
+                          0.309017 2.78025e-16 -0.951057,
+                          0.309017 2.78025e-16 -0.951057,
+                          0.309017 2.78025e-16 -0.951057,
+                          0.809017 3.05525e-16 -0.587785,
+                          0.809017 3.05525e-16 -0.587785,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 25.97 -111 509,
+                          36 -111 361,
+                          -1 -111 361,
+                          -1 -117 361,
+                          -1 -111 361,
+                          36 -111 361,
+                          18.97 -111 509,
+                          25.97 -111 509,
+                          -1 -111 361,
+                          10.97 -111 509,
+                          18.97 -111 509,
+                          -1 -111 361,
+                          -26.9162 -111 482.374,
+                          10.97 -111 509,
+                          -1 -111 361,
+                          -26.9162 -111 482.374,
+                          -1 -111 361,
+                          -36 -111 361,
+                          -36 -117 361,
+                          -36 -111 361,
+                          -1 -111 361,
+                          -36 -117 361,
+                          -1 -111 361,
+                          -1 -117 361,
+                          45 -111 476,
+                          45 -111 361,
+                          36 -111 361,
+                          36 -117 361,
+                          36 -111 361,
+                          45 -111 361,
+                          25.97 -111 509,
+                          45 -111 476,
+                          36 -111 361,
+                          36 -117 361,
+                          -1 -117 361,
+                          36 -111 361,
+                          45 -117 361,
+                          45 -111 361,
+                          45 -111 476,
+                          36 -117 361,
+                          45 -111 361,
+                          45 -117 361,
+                          45 -117 476,
+                          45 -111 476,
+                          25.97 -111 509,
+                          45 -117 361,
+                          45 -111 476,
+                          45 -117 476,
+                          25.97 -117 509,
+                          25.97 -111 509,
+                          18.97 -111 509,
+                          45 -117 476,
+                          25.97 -111 509,
+                          25.97 -117 509,
+                          18.97 -117 509,
+                          18.97 -111 509,
+                          10.97 -111 509,
+                          25.97 -117 509,
+                          18.97 -111 509,
+                          18.97 -117 509,
+                          -39.9973 -111 491.876,
+                          -81.03 -111 509,
+                          10.97 -111 509,
+                          10.97 -117 509,
+                          10.97 -111 509,
+                          -81.03 -111 509,
+                          -30.0027 -111 491.876,
+                          -35 -111 493.5,
+                          10.97 -111 509,
+                          -39.9973 -111 491.876,
+                          10.97 -111 509,
+                          -35 -111 493.5,
+                          -26.9162 -111 487.626,
+                          -30.0027 -111 491.876,
+                          10.97 -111 509,
+                          -26.9162 -111 482.374,
+                          -26.9162 -111 487.626,
+                          10.97 -111 509,
+                          18.97 -117 509,
+                          10.97 -111 509,
+                          10.97 -117 509,
+                          -94 -111 361,
+                          -96.03 -111 509,
+                          -81.03 -111 509,
+                          -81.03 -117 509,
+                          -81.03 -111 509,
+                          -96.03 -111 509,
+                          -43.0838 -111 487.626,
+                          -94 -111 361,
+                          -81.03 -111 509,
+                          -39.9973 -111 491.876,
+                          -43.0838 -111 487.626,
+                          -81.03 -111 509,
+                          10.97 -117 509,
+                          -81.03 -111 509,
+                          -81.03 -117 509,
+                          -115 -111 361,
+                          -115 -111 476,
+                          -96.03 -111 509,
+                          -96.03 -117 509,
+                          -96.03 -111 509,
+                          -115 -111 476,
+                          -94 -111 361,
+                          -115 -111 361,
+                          -96.03 -111 509,
+                          -81.03 -117 509,
+                          -96.03 -111 509,
+                          -96.03 -117 509,
+                          -115 -117 476,
+                          -115 -111 476,
+                          -115 -111 361,
+                          -96.03 -117 509,
+                          -115 -111 476,
+                          -115 -117 476,
+                          -115 -117 361,
+                          -115 -111 361,
+                          -94 -111 361,
+                          -115 -117 476,
+                          -115 -111 361,
+                          -115 -117 361,
+                          -39.9973 -111 478.124,
+                          -36 -111 361,
+                          -94 -111 361,
+                          -94 -117 361,
+                          -94 -111 361,
+                          -36 -111 361,
+                          -43.0838 -111 482.374,
+                          -39.9973 -111 478.124,
+                          -94 -111 361,
+                          -43.0838 -111 487.626,
+                          -43.0838 -111 482.374,
+                          -94 -111 361,
+                          -115 -117 361,
+                          -94 -111 361,
+                          -94 -117 361,
+                          -30.0027 -111 478.124,
+                          -26.9162 -111 482.374,
+                          -36 -111 361,
+                          -35 -111 476.5,
+                          -30.0027 -111 478.124,
+                          -36 -111 361,
+                          -39.9973 -111 478.124,
+                          -35 -111 476.5,
+                          -36 -111 361,
+                          -94 -117 361,
+                          -36 -111 361,
+                          -36 -117 361,
+                          -35 -122 493.5,
+                          -35 -111 493.5,
+                          -30.0027 -111 491.876,
+                          -39.9973 -122 491.876,
+                          -39.9973 -111 491.876,
+                          -35 -111 493.5,
+                          -35 -122 493.5,
+                          -39.9973 -122 491.876,
+                          -35 -111 493.5,
+                          -30.0027 -122 491.876,
+                          -30.0027 -111 491.876,
+                          -26.9162 -111 487.626,
+                          -30.0027 -122 491.876,
+                          -35 -122 493.5,
+                          -30.0027 -111 491.876,
+                          -26.9162 -122 487.626,
+                          -26.9162 -111 487.626,
+                          -26.9162 -111 482.374,
+                          -26.9162 -122 487.626,
+                          -30.0027 -122 491.876,
+                          -26.9162 -111 487.626,
+                          -26.9162 -122 482.374,
+                          -26.9162 -111 482.374,
+                          -30.0027 -111 478.124,
+                          -26.9162 -122 482.374,
+                          -26.9162 -122 487.626,
+                          -26.9162 -111 482.374,
+                          -30.0027 -122 478.124,
+                          -30.0027 -111 478.124,
+                          -35 -111 476.5,
+                          -30.0027 -122 478.124,
+                          -26.9162 -122 482.374,
+                          -30.0027 -111 478.124,
+                          -35 -122 476.5,
+                          -35 -111 476.5,
+                          -39.9973 -111 478.124,
+                          -30.0027 -122 478.124,
+                          -35 -111 476.5,
+                          -35 -122 476.5,
+                          -39.9973 -122 478.124,
+                          -39.9973 -111 478.124,
+                          -43.0838 -111 482.374,
+                          -39.9973 -122 478.124,
+                          -35 -122 476.5,
+                          -39.9973 -111 478.124,
+                          -43.0838 -122 482.374,
+                          -43.0838 -111 482.374,
+                          -43.0838 -111 487.626,
+                          -43.0838 -122 482.374,
+                          -39.9973 -122 478.124,
+                          -43.0838 -111 482.374,
+                          -43.0838 -122 487.626,
+                          -43.0838 -111 487.626,
+                          -39.9973 -111 491.876,
+                          -43.0838 -122 487.626,
+                          -43.0838 -122 482.374,
+                          -43.0838 -111 487.626,
+                          -39.9973 -122 491.876,
+                          -43.0838 -122 487.626,
+                          -39.9973 -111 491.876,
+                          -31.1373 -117 473.112,
+                          -36 -117 361,
+                          -1 -117 361,
+                          36 -117 361,
+                          10.97 -117 509,
+                          -1 -117 361,
+                          -22.5 -117 485,
+                          -1 -117 361,
+                          10.97 -117 509,
+                          -24.8873 -117 477.653,
+                          -1 -117 361,
+                          -22.5 -117 485,
+                          -24.8873 -117 477.653,
+                          -31.1373 -117 473.112,
+                          -1 -117 361,
+                          -81.03 -117 509,
+                          -94 -117 361,
+                          -36 -117 361,
+                          -47.5 -117 485,
+                          -81.03 -117 509,
+                          -36 -117 361,
+                          -45.1127 -117 477.653,
+                          -47.5 -117 485,
+                          -36 -117 361,
+                          -38.8627 -117 473.112,
+                          -45.1127 -117 477.653,
+                          -36 -117 361,
+                          -31.1373 -117 473.112,
+                          -38.8627 -117 473.112,
+                          -36 -117 361,
+                          -115 -117 476,
+                          -115 -117 361,
+                          -94 -117 361,
+                          -96.03 -117 509,
+                          -115 -117 476,
+                          -94 -117 361,
+                          -81.03 -117 509,
+                          -96.03 -117 509,
+                          -94 -117 361,
+                          -31.1373 -117 496.888,
+                          10.97 -117 509,
+                          -81.03 -117 509,
+                          -38.8627 -117 496.888,
+                          -31.1373 -117 496.888,
+                          -81.03 -117 509,
+                          -45.1127 -117 492.347,
+                          -38.8627 -117 496.888,
+                          -81.03 -117 509,
+                          -47.5 -117 485,
+                          -45.1127 -117 492.347,
+                          -81.03 -117 509,
+                          36 -117 361,
+                          18.97 -117 509,
+                          10.97 -117 509,
+                          -24.8873 -117 492.347,
+                          -22.5 -117 485,
+                          10.97 -117 509,
+                          -31.1373 -117 496.888,
+                          -24.8873 -117 492.347,
+                          10.97 -117 509,
+                          36 -117 361,
+                          25.97 -117 509,
+                          18.97 -117 509,
+                          45 -117 361,
+                          45 -117 476,
+                          25.97 -117 509,
+                          36 -117 361,
+                          45 -117 361,
+                          25.97 -117 509,
+                          -22.5 -122 485,
+                          -22.5 -117 485,
+                          -24.8873 -117 492.347,
+                          -24.8889 -122 477.651,
+                          -24.8873 -117 477.653,
+                          -22.5 -117 485,
+                          -24.8889 -122 477.651,
+                          -22.5 -117 485,
+                          -22.5 -122 485,
+                          -24.8889 -122 492.349,
+                          -24.8873 -117 492.347,
+                          -31.1373 -117 496.888,
+                          -24.8889 -122 492.349,
+                          -22.5 -122 485,
+                          -24.8873 -117 492.347,
+                          -31.1386 -122 496.888,
+                          -31.1373 -117 496.888,
+                          -38.8627 -117 496.888,
+                          -24.8889 -122 492.349,
+                          -31.1373 -117 496.888,
+                          -31.1386 -122 496.888,
+                          -38.8614 -122 496.888,
+                          -38.8627 -117 496.888,
+                          -45.1127 -117 492.347,
+                          -31.1386 -122 496.888,
+                          -38.8627 -117 496.888,
+                          -38.8614 -122 496.888,
+                          -45.1111 -122 492.349,
+                          -45.1127 -117 492.347,
+                          -47.5 -117 485,
+                          -38.8614 -122 496.888,
+                          -45.1127 -117 492.347,
+                          -45.1111 -122 492.349,
+                          -47.5 -122 485,
+                          -47.5 -117 485,
+                          -45.1127 -117 477.653,
+                          -45.1111 -122 492.349,
+                          -47.5 -117 485,
+                          -47.5 -122 485,
+                          -45.1111 -122 477.651,
+                          -45.1127 -117 477.653,
+                          -38.8627 -117 473.112,
+                          -47.5 -122 485,
+                          -45.1127 -117 477.653,
+                          -45.1111 -122 477.651,
+                          -38.8614 -122 473.112,
+                          -38.8627 -117 473.112,
+                          -31.1373 -117 473.112,
+                          -45.1111 -122 477.651,
+                          -38.8627 -117 473.112,
+                          -38.8614 -122 473.112,
+                          -31.1386 -122 473.112,
+                          -31.1373 -117 473.112,
+                          -24.8873 -117 477.653,
+                          -38.8614 -122 473.112,
+                          -31.1373 -117 473.112,
+                          -31.1386 -122 473.112,
+                          -31.1386 -122 473.112,
+                          -24.8873 -117 477.653,
+                          -24.8889 -122 477.651,
+                          -45.1111 -122 477.651,
+                          -35 -122 476.5,
+                          -39.9973 -122 478.124,
+                          -24.8889 -122 477.651,
+                          -30.0027 -122 478.124,
+                          -35 -122 476.5,
+                          -38.8614 -122 473.112,
+                          -24.8889 -122 477.651,
+                          -35 -122 476.5,
+                          -45.1111 -122 477.651,
+                          -38.8614 -122 473.112,
+                          -35 -122 476.5,
+                          -45.1111 -122 477.651,
+                          -39.9973 -122 478.124,
+                          -43.0838 -122 482.374,
+                          -47.5 -122 485,
+                          -43.0838 -122 482.374,
+                          -43.0838 -122 487.626,
+                          -47.5 -122 485,
+                          -45.1111 -122 477.651,
+                          -43.0838 -122 482.374,
+                          -47.5 -122 485,
+                          -43.0838 -122 487.626,
+                          -39.9973 -122 491.876,
+                          -45.1111 -122 492.349,
+                          -39.9973 -122 491.876,
+                          -35 -122 493.5,
+                          -45.1111 -122 492.349,
+                          -47.5 -122 485,
+                          -39.9973 -122 491.876,
+                          -24.8889 -122 492.349,
+                          -35 -122 493.5,
+                          -30.0027 -122 491.876,
+                          -31.1386 -122 496.888,
+                          -45.1111 -122 492.349,
+                          -35 -122 493.5,
+                          -24.8889 -122 492.349,
+                          -31.1386 -122 496.888,
+                          -35 -122 493.5,
+                          -24.8889 -122 492.349,
+                          -30.0027 -122 491.876,
+                          -26.9162 -122 487.626,
+                          -22.5 -122 485,
+                          -26.9162 -122 487.626,
+                          -26.9162 -122 482.374,
+                          -24.8889 -122 492.349,
+                          -26.9162 -122 487.626,
+                          -22.5 -122 485,
+                          -22.5 -122 485,
+                          -26.9162 -122 482.374,
+                          -30.0027 -122 478.124,
+                          -24.8889 -122 477.651,
+                          -22.5 -122 485,
+                          -30.0027 -122 478.124,
+                          -38.8614 -122 473.112,
+                          -31.1386 -122 473.112,
+                          -24.8889 -122 477.651,
+                          -31.1386 -122 496.888,
+                          -38.8614 -122 496.888,
+                          -45.1111 -122 492.349 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.866282 -2.98322e-16 0.499556,
+                          -0.866282 -2.98322e-16 0.499556,
+                          -0.866282 -2.98322e-16 0.499556,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.866282 -2.98322e-16 0.499556,
+                          -0.866282 -2.98322e-16 0.499556,
+                          -0.866282 -2.98322e-16 0.499556,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          0.866963 7.68853e-17 0.498372,
+                          0.866963 7.68853e-17 0.498372,
+                          0.866963 7.68853e-17 0.498372,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          0.866963 7.68853e-17 0.498372,
+                          0.866963 7.68853e-17 0.498372,
+                          0.866963 7.68853e-17 0.498372,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          2.44921e-16 2.22045e-16 -1,
+                          2.44921e-16 2.22045e-16 -1,
+                          0.587785 3.06791e-16 -0.809017,
+                          -0.587785 5.2485e-17 -0.809017,
+                          -0.587785 5.2485e-17 -0.809017,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.587785 5.2485e-17 -0.809017,
+                          0 2.22045e-16 -1,
+                          0.587785 3.06791e-16 -0.809017,
+                          0.587785 3.06791e-16 -0.809017,
+                          0.951057 2.74353e-16 -0.309017,
+                          0.587785 3.06791e-16 -0.809017,
+                          2.44921e-16 2.22045e-16 -1,
+                          0.587785 3.06791e-16 -0.809017,
+                          0.951057 2.74353e-16 -0.309017,
+                          0.951057 2.74353e-16 -0.309017,
+                          0.951057 1.37122e-16 0.309017,
+                          0.951057 2.74353e-16 -0.309017,
+                          0.587785 3.06791e-16 -0.809017,
+                          0.951057 2.74353e-16 -0.309017,
+                          0.951057 1.37122e-16 0.309017,
+                          0.951057 1.37122e-16 0.309017,
+                          0.587785 -5.2485e-17 0.809017,
+                          0.951057 1.37122e-16 0.309017,
+                          0.951057 2.74353e-16 -0.309017,
+                          0.951057 1.37122e-16 0.309017,
+                          0.587785 -5.2485e-17 0.809017,
+                          0.587785 -5.2485e-17 0.809017,
+                          -1.22461e-16 -2.22045e-16 1,
+                          0.587785 -5.2485e-17 0.809017,
+                          0.951057 1.37122e-16 0.309017,
+                          0.587785 -5.2485e-17 0.809017,
+                          -1.22461e-16 -2.22045e-16 1,
+                          -1.22461e-16 -2.22045e-16 1,
+                          -0.587785 -3.06791e-16 0.809017,
+                          0.587785 -5.2485e-17 0.809017,
+                          -1.22461e-16 -2.22045e-16 1,
+                          -1.22461e-16 -2.22045e-16 1,
+                          -0.587785 -3.06791e-16 0.809017,
+                          -0.587785 -3.06791e-16 0.809017,
+                          -0.951057 -2.74353e-16 0.309017,
+                          -0.587785 -3.06791e-16 0.809017,
+                          -1.22461e-16 -2.22045e-16 1,
+                          -0.587785 -3.06791e-16 0.809017,
+                          -0.951057 -2.74353e-16 0.309017,
+                          -0.951057 -2.74353e-16 0.309017,
+                          -0.951057 -1.37122e-16 -0.309017,
+                          -0.951057 -2.74353e-16 0.309017,
+                          -0.587785 -3.06791e-16 0.809017,
+                          -0.951057 -2.74353e-16 0.309017,
+                          -0.951057 -1.37122e-16 -0.309017,
+                          -0.951057 -1.37122e-16 -0.309017,
+                          -0.587785 5.2485e-17 -0.809017,
+                          -0.951057 -1.37122e-16 -0.309017,
+                          -0.951057 -2.74353e-16 0.309017,
+                          -0.951057 -1.37122e-16 -0.309017,
+                          -0.587785 5.2485e-17 -0.809017,
+                          -0.951057 -1.37122e-16 -0.309017,
+                          -0.587785 5.2485e-17 -0.809017,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -0.809017 -3.05525e-16 0.587785,
+                          -0.809017 -4.44964e-17 -0.587785,
+                          -0.809017 -4.44964e-17 -0.587785,
+                          -1 -2.16325e-16 -2.44921e-16,
+                          -0.809017 -4.44964e-17 -0.587785,
+                          -1 -2.16325e-16 -2.44921e-16,
+                          -1 -2.16325e-16 -2.44921e-16,
+                          -0.809017 -3.05525e-16 0.587785,
+                          -0.809017 -3.05525e-16 0.587785,
+                          -0.309017 -2.78025e-16 0.951057,
+                          -0.809017 -3.05525e-16 0.587785,
+                          -1 -2.16325e-16 0,
+                          -0.809017 -3.05525e-16 0.587785,
+                          -0.309017 -2.78025e-16 0.951057,
+                          -0.309017 -2.78025e-16 0.951057,
+                          0.309017 -1.44329e-16 0.951057,
+                          -0.809017 -3.05525e-16 0.587785,
+                          -0.309017 -2.78025e-16 0.951057,
+                          -0.309017 -2.78025e-16 0.951057,
+                          0.309017 -1.44329e-16 0.951057,
+                          0.309017 -1.44329e-16 0.951057,
+                          0.809017 4.44964e-17 0.587785,
+                          -0.309017 -2.78025e-16 0.951057,
+                          0.309017 -1.44329e-16 0.951057,
+                          0.309017 -1.44329e-16 0.951057,
+                          0.809017 4.44964e-17 0.587785,
+                          0.809017 4.44964e-17 0.587785,
+                          1 2.16325e-16 1.22461e-16,
+                          0.309017 -1.44329e-16 0.951057,
+                          0.809017 4.44964e-17 0.587785,
+                          0.809017 4.44964e-17 0.587785,
+                          1 2.16325e-16 1.22461e-16,
+                          1 2.16325e-16 1.22461e-16,
+                          0.809017 3.05525e-16 -0.587785,
+                          0.809017 4.44964e-17 0.587785,
+                          1 2.16325e-16 1.22461e-16,
+                          1 2.16325e-16 1.22461e-16,
+                          0.809017 3.05525e-16 -0.587785,
+                          0.809017 3.05525e-16 -0.587785,
+                          0.309017 2.78025e-16 -0.951057,
+                          1 2.16325e-16 1.22461e-16,
+                          0.809017 3.05525e-16 -0.587785,
+                          0.809017 3.05525e-16 -0.587785,
+                          0.309017 2.78025e-16 -0.951057,
+                          0.309017 2.78025e-16 -0.951057,
+                          -0.309017 1.44329e-16 -0.951057,
+                          0.809017 3.05525e-16 -0.587785,
+                          0.309017 2.78025e-16 -0.951057,
+                          0.309017 2.78025e-16 -0.951057,
+                          -0.309017 1.44329e-16 -0.951057,
+                          -0.309017 1.44329e-16 -0.951057,
+                          -0.809017 -4.44964e-17 -0.587785,
+                          0.309017 2.78025e-16 -0.951057,
+                          -0.309017 1.44329e-16 -0.951057,
+                          -0.309017 1.44329e-16 -0.951057,
+                          -0.309017 1.44329e-16 -0.951057,
+                          -0.809017 -4.44964e-17 -0.587785,
+                          -0.809017 -4.44964e-17 -0.587785,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -95.97 111 509,
+                          -106 111 361,
+                          -69 111 361,
+                          -69 117 361,
+                          -69 111 361,
+                          -106 111 361,
+                          -88.97 111 509,
+                          -95.97 111 509,
+                          -69 111 361,
+                          -80.97 111 509,
+                          -88.97 111 509,
+                          -69 111 361,
+                          -43.0838 111 482.374,
+                          -80.97 111 509,
+                          -69 111 361,
+                          -43.0838 111 482.374,
+                          -69 111 361,
+                          -34 111 361,
+                          -34 117 361,
+                          -34 111 361,
+                          -69 111 361,
+                          -34 117 361,
+                          -69 111 361,
+                          -69 117 361,
+                          -115 111 476,
+                          -115 111 361,
+                          -106 111 361,
+                          -106 117 361,
+                          -106 111 361,
+                          -115 111 361,
+                          -95.97 111 509,
+                          -115 111 476,
+                          -106 111 361,
+                          -106 117 361,
+                          -69 117 361,
+                          -106 111 361,
+                          -115 117 361,
+                          -115 111 361,
+                          -115 111 476,
+                          -106 117 361,
+                          -115 111 361,
+                          -115 117 361,
+                          -115 117 476,
+                          -115 111 476,
+                          -95.97 111 509,
+                          -115 117 361,
+                          -115 111 476,
+                          -115 117 476,
+                          -95.97 117 509,
+                          -95.97 111 509,
+                          -88.97 111 509,
+                          -115 117 476,
+                          -95.97 111 509,
+                          -95.97 117 509,
+                          -88.97 117 509,
+                          -88.97 111 509,
+                          -80.97 111 509,
+                          -95.97 117 509,
+                          -88.97 111 509,
+                          -88.97 117 509,
+                          -30.0027 111 491.876,
+                          11.03 111 509,
+                          -80.97 111 509,
+                          -80.97 117 509,
+                          -80.97 111 509,
+                          11.03 111 509,
+                          -39.9973 111 491.876,
+                          -35 111 493.5,
+                          -80.97 111 509,
+                          -30.0027 111 491.876,
+                          -80.97 111 509,
+                          -35 111 493.5,
+                          -43.0838 111 487.626,
+                          -39.9973 111 491.876,
+                          -80.97 111 509,
+                          -43.0838 111 482.374,
+                          -43.0838 111 487.626,
+                          -80.97 111 509,
+                          -88.97 117 509,
+                          -80.97 111 509,
+                          -80.97 117 509,
+                          24 111 361,
+                          26.03 111 509,
+                          11.03 111 509,
+                          11.03 117 509,
+                          11.03 111 509,
+                          26.03 111 509,
+                          -26.9162 111 487.626,
+                          24 111 361,
+                          11.03 111 509,
+                          -30.0027 111 491.876,
+                          -26.9162 111 487.626,
+                          11.03 111 509,
+                          -80.97 117 509,
+                          11.03 111 509,
+                          11.03 117 509,
+                          45 111 361,
+                          45 111 476,
+                          26.03 111 509,
+                          26.03 117 509,
+                          26.03 111 509,
+                          45 111 476,
+                          24 111 361,
+                          45 111 361,
+                          26.03 111 509,
+                          11.03 117 509,
+                          26.03 111 509,
+                          26.03 117 509,
+                          45 117 476,
+                          45 111 476,
+                          45 111 361,
+                          26.03 117 509,
+                          45 111 476,
+                          45 117 476,
+                          45 117 361,
+                          45 111 361,
+                          24 111 361,
+                          45 117 476,
+                          45 111 361,
+                          45 117 361,
+                          -30.0027 111 478.124,
+                          -34 111 361,
+                          24 111 361,
+                          24 117 361,
+                          24 111 361,
+                          -34 111 361,
+                          -26.9162 111 482.374,
+                          -30.0027 111 478.124,
+                          24 111 361,
+                          -26.9162 111 487.626,
+                          -26.9162 111 482.374,
+                          24 111 361,
+                          45 117 361,
+                          24 111 361,
+                          24 117 361,
+                          -39.9973 111 478.124,
+                          -43.0838 111 482.374,
+                          -34 111 361,
+                          -35 111 476.5,
+                          -39.9973 111 478.124,
+                          -34 111 361,
+                          -30.0027 111 478.124,
+                          -35 111 476.5,
+                          -34 111 361,
+                          24 117 361,
+                          -34 111 361,
+                          -34 117 361,
+                          -35 122 493.5,
+                          -35 111 493.5,
+                          -39.9973 111 491.876,
+                          -30.0027 122 491.876,
+                          -30.0027 111 491.876,
+                          -35 111 493.5,
+                          -35 122 493.5,
+                          -30.0027 122 491.876,
+                          -35 111 493.5,
+                          -39.9973 122 491.876,
+                          -39.9973 111 491.876,
+                          -43.0838 111 487.626,
+                          -39.9973 122 491.876,
+                          -35 122 493.5,
+                          -39.9973 111 491.876,
+                          -43.0838 122 487.626,
+                          -43.0838 111 487.626,
+                          -43.0838 111 482.374,
+                          -43.0838 122 487.626,
+                          -39.9973 122 491.876,
+                          -43.0838 111 487.626,
+                          -43.0838 122 482.374,
+                          -43.0838 111 482.374,
+                          -39.9973 111 478.124,
+                          -43.0838 122 482.374,
+                          -43.0838 122 487.626,
+                          -43.0838 111 482.374,
+                          -39.9973 122 478.124,
+                          -39.9973 111 478.124,
+                          -35 111 476.5,
+                          -39.9973 122 478.124,
+                          -43.0838 122 482.374,
+                          -39.9973 111 478.124,
+                          -35 122 476.5,
+                          -35 111 476.5,
+                          -30.0027 111 478.124,
+                          -39.9973 122 478.124,
+                          -35 111 476.5,
+                          -35 122 476.5,
+                          -30.0027 122 478.124,
+                          -30.0027 111 478.124,
+                          -26.9162 111 482.374,
+                          -30.0027 122 478.124,
+                          -35 122 476.5,
+                          -30.0027 111 478.124,
+                          -26.9162 122 482.374,
+                          -26.9162 111 482.374,
+                          -26.9162 111 487.626,
+                          -26.9162 122 482.374,
+                          -30.0027 122 478.124,
+                          -26.9162 111 482.374,
+                          -26.9162 122 487.626,
+                          -26.9162 111 487.626,
+                          -30.0027 111 491.876,
+                          -26.9162 122 487.626,
+                          -26.9162 122 482.374,
+                          -26.9162 111 487.626,
+                          -30.0027 122 491.876,
+                          -26.9162 122 487.626,
+                          -30.0027 111 491.876,
+                          -38.8627 117 473.112,
+                          -34 117 361,
+                          -69 117 361,
+                          -106 117 361,
+                          -80.97 117 509,
+                          -69 117 361,
+                          -47.5 117 485,
+                          -69 117 361,
+                          -80.97 117 509,
+                          -45.1127 117 477.653,
+                          -69 117 361,
+                          -47.5 117 485,
+                          -45.1127 117 477.653,
+                          -38.8627 117 473.112,
+                          -69 117 361,
+                          11.03 117 509,
+                          24 117 361,
+                          -34 117 361,
+                          -22.5 117 485,
+                          11.03 117 509,
+                          -34 117 361,
+                          -24.8873 117 477.653,
+                          -22.5 117 485,
+                          -34 117 361,
+                          -31.1373 117 473.112,
+                          -24.8873 117 477.653,
+                          -34 117 361,
+                          -38.8627 117 473.112,
+                          -31.1373 117 473.112,
+                          -34 117 361,
+                          45 117 476,
+                          45 117 361,
+                          24 117 361,
+                          26.03 117 509,
+                          45 117 476,
+                          24 117 361,
+                          11.03 117 509,
+                          26.03 117 509,
+                          24 117 361,
+                          -38.8627 117 496.888,
+                          -80.97 117 509,
+                          11.03 117 509,
+                          -31.1373 117 496.888,
+                          -38.8627 117 496.888,
+                          11.03 117 509,
+                          -24.8873 117 492.347,
+                          -31.1373 117 496.888,
+                          11.03 117 509,
+                          -22.5 117 485,
+                          -24.8873 117 492.347,
+                          11.03 117 509,
+                          -106 117 361,
+                          -88.97 117 509,
+                          -80.97 117 509,
+                          -45.1127 117 492.347,
+                          -47.5 117 485,
+                          -80.97 117 509,
+                          -38.8627 117 496.888,
+                          -45.1127 117 492.347,
+                          -80.97 117 509,
+                          -106 117 361,
+                          -95.97 117 509,
+                          -88.97 117 509,
+                          -115 117 361,
+                          -115 117 476,
+                          -95.97 117 509,
+                          -106 117 361,
+                          -115 117 361,
+                          -95.97 117 509,
+                          -47.5 122 485,
+                          -47.5 117 485,
+                          -45.1127 117 492.347,
+                          -45.1111 122 477.651,
+                          -45.1127 117 477.653,
+                          -47.5 117 485,
+                          -45.1111 122 477.651,
+                          -47.5 117 485,
+                          -47.5 122 485,
+                          -45.1111 122 492.349,
+                          -45.1127 117 492.347,
+                          -38.8627 117 496.888,
+                          -45.1111 122 492.349,
+                          -47.5 122 485,
+                          -45.1127 117 492.347,
+                          -38.8614 122 496.888,
+                          -38.8627 117 496.888,
+                          -31.1373 117 496.888,
+                          -45.1111 122 492.349,
+                          -38.8627 117 496.888,
+                          -38.8614 122 496.888,
+                          -31.1386 122 496.888,
+                          -31.1373 117 496.888,
+                          -24.8873 117 492.347,
+                          -38.8614 122 496.888,
+                          -31.1373 117 496.888,
+                          -31.1386 122 496.888,
+                          -24.8889 122 492.349,
+                          -24.8873 117 492.347,
+                          -22.5 117 485,
+                          -31.1386 122 496.888,
+                          -24.8873 117 492.347,
+                          -24.8889 122 492.349,
+                          -22.5 122 485,
+                          -22.5 117 485,
+                          -24.8873 117 477.653,
+                          -24.8889 122 492.349,
+                          -22.5 117 485,
+                          -22.5 122 485,
+                          -24.8889 122 477.651,
+                          -24.8873 117 477.653,
+                          -31.1373 117 473.112,
+                          -22.5 122 485,
+                          -24.8873 117 477.653,
+                          -24.8889 122 477.651,
+                          -31.1386 122 473.112,
+                          -31.1373 117 473.112,
+                          -38.8627 117 473.112,
+                          -24.8889 122 477.651,
+                          -31.1373 117 473.112,
+                          -31.1386 122 473.112,
+                          -38.8614 122 473.112,
+                          -38.8627 117 473.112,
+                          -45.1127 117 477.653,
+                          -31.1386 122 473.112,
+                          -38.8627 117 473.112,
+                          -38.8614 122 473.112,
+                          -38.8614 122 473.112,
+                          -45.1127 117 477.653,
+                          -45.1111 122 477.651,
+                          -24.8889 122 477.651,
+                          -35 122 476.5,
+                          -30.0027 122 478.124,
+                          -45.1111 122 477.651,
+                          -39.9973 122 478.124,
+                          -35 122 476.5,
+                          -31.1386 122 473.112,
+                          -45.1111 122 477.651,
+                          -35 122 476.5,
+                          -24.8889 122 477.651,
+                          -31.1386 122 473.112,
+                          -35 122 476.5,
+                          -24.8889 122 477.651,
+                          -30.0027 122 478.124,
+                          -26.9162 122 482.374,
+                          -22.5 122 485,
+                          -26.9162 122 482.374,
+                          -26.9162 122 487.626,
+                          -22.5 122 485,
+                          -24.8889 122 477.651,
+                          -26.9162 122 482.374,
+                          -22.5 122 485,
+                          -26.9162 122 487.626,
+                          -30.0027 122 491.876,
+                          -24.8889 122 492.349,
+                          -30.0027 122 491.876,
+                          -35 122 493.5,
+                          -24.8889 122 492.349,
+                          -22.5 122 485,
+                          -30.0027 122 491.876,
+                          -45.1111 122 492.349,
+                          -35 122 493.5,
+                          -39.9973 122 491.876,
+                          -38.8614 122 496.888,
+                          -24.8889 122 492.349,
+                          -35 122 493.5,
+                          -45.1111 122 492.349,
+                          -38.8614 122 496.888,
+                          -35 122 493.5,
+                          -45.1111 122 492.349,
+                          -39.9973 122 491.876,
+                          -43.0838 122 487.626,
+                          -47.5 122 485,
+                          -43.0838 122 487.626,
+                          -43.0838 122 482.374,
+                          -45.1111 122 492.349,
+                          -43.0838 122 487.626,
+                          -47.5 122 485,
+                          -47.5 122 485,
+                          -43.0838 122 482.374,
+                          -39.9973 122 478.124,
+                          -45.1111 122 477.651,
+                          -47.5 122 485,
+                          -39.9973 122 478.124,
+                          -31.1386 122 473.112,
+                          -38.8614 122 473.112,
+                          -45.1111 122 477.651,
+                          -38.8614 122 496.888,
+                          -31.1386 122 496.888,
+                          -24.8889 122 492.349 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    1 1 1
+    }
+    Separator {
+        Normal {
+            vector      [ -2.22045e-16 2.22045e-16 -1,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -5.71917e-18 -1 -2.22045e-16,
+                          -5.71917e-18 -1 -2.22045e-16,
+                          -5.71917e-18 -1 -2.22045e-16,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -1 5.71917e-18 2.22045e-16,
+                          -1 5.71917e-18 2.22045e-16,
+                          -1 5.71917e-18 2.22045e-16,
+                          -1 5.71917e-18 2.22045e-16,
+                          -1 5.71917e-18 2.22045e-16,
+                          -1 5.71917e-18 2.22045e-16,
+                          1 -5.71917e-18 -2.22045e-16,
+                          1 -5.71917e-18 -2.22045e-16,
+                          1 -5.71917e-18 -2.22045e-16,
+                          -5.71917e-18 -1 -2.22045e-16,
+                          -5.71917e-18 -1 -2.22045e-16,
+                          -5.71917e-18 -1 -2.22045e-16,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -2.22045e-16 2.22045e-16 -1,
+                          0.707107 -0.707107 -3.14018e-16,
+                          0.707107 -0.707107 -3.14018e-16,
+                          0.707107 -0.707107 -3.14018e-16,
+                          1 -5.71917e-18 -2.22045e-16,
+                          1 -5.71917e-18 -2.22045e-16,
+                          1 -5.71917e-18 -2.22045e-16,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -0.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -2.22045e-16 2.22045e-16 -1,
+                          0.707107 -0.707107 -3.14018e-16,
+                          0.707107 -0.707107 -3.14018e-16,
+                          0.707107 -0.707107 -3.14018e-16,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -1 5.71917e-18 2.22045e-16,
+                          -1 5.71917e-18 2.22045e-16,
+                          -1 5.71917e-18 2.22045e-16,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -0.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          -0.707107 -0.707107 0,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -5.71917e-18 -1 -2.22045e-16,
+                          -5.71917e-18 -1 -2.22045e-16,
+                          -5.71917e-18 -1 -2.22045e-16,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -1 5.71917e-18 2.22045e-16,
+                          -1 5.71917e-18 2.22045e-16,
+                          -1 5.71917e-18 2.22045e-16,
+                          1 -5.71917e-18 -2.22045e-16,
+                          1 -5.71917e-18 -2.22045e-16,
+                          1 -5.71917e-18 -2.22045e-16,
+                          -5.71917e-18 -1 -2.22045e-16,
+                          -5.71917e-18 -1 -2.22045e-16,
+                          -5.71917e-18 -1 -2.22045e-16,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -2.22045e-16 2.22045e-16 -1,
+                          0.5 -0.866025 -3.03319e-16,
+                          0.5 -0.866025 -3.03319e-16,
+                          0.5 -0.866025 -3.03319e-16,
+                          1 -5.71917e-18 -2.22045e-16,
+                          1 -5.71917e-18 -2.22045e-16,
+                          1 -5.71917e-18 -2.22045e-16,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -2.22045e-16 2.22045e-16 -1,
+                          -5.71917e-18 -1 -2.22045e-16,
+                          -5.71917e-18 -1 -2.22045e-16,
+                          -5.71917e-18 -1 -2.22045e-16,
+                          0.5 -0.866025 -3.03319e-16,
+                          0.5 -0.866025 -3.03319e-16,
+                          0.5 -0.866025 -3.03319e-16,
+                          1 -5.71917e-18 -2.22045e-16,
+                          1 -5.71917e-18 -2.22045e-16,
+                          1 -5.71917e-18 -2.22045e-16,
+                          -5.71917e-18 -1 -2.22045e-16,
+                          -5.71917e-18 -1 -2.22045e-16,
+                          -5.71917e-18 -1 -2.22045e-16,
+                          5.71917e-18 1 2.22045e-16,
+                          5.71917e-18 1 2.22045e-16,
+                          5.71917e-18 1 2.22045e-16,
+                          1 -5.71917e-18 -2.22045e-16,
+                          1 -5.71917e-18 -2.22045e-16,
+                          1 -5.71917e-18 -2.22045e-16,
+                          -0.707107 0.707107 3.14018e-16,
+                          -0.707107 0.707107 3.14018e-16,
+                          -0.707107 0.707107 3.14018e-16,
+                          5.71917e-18 1 2.22045e-16,
+                          5.71917e-18 1 2.22045e-16,
+                          5.71917e-18 1 2.22045e-16,
+                          -0.707107 0.707107 3.14018e-16,
+                          -0.707107 0.707107 3.14018e-16,
+                          -0.707107 0.707107 3.14018e-16,
+                          -0.707107 0.707107 3.14018e-16,
+                          -0.707107 0.707107 3.14018e-16,
+                          -0.707107 0.707107 3.14018e-16,
+                          -0.707107 0.707107 3.14018e-16,
+                          -0.707107 0.707107 3.14018e-16,
+                          -0.707107 0.707107 3.14018e-16,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1,
+                          2.22045e-16 -2.22045e-16 1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -106 119.941 357,
+                          -106 110.941 357,
+                          -115 110.941 357,
+                          -115 110.941 361,
+                          -115 110.941 357,
+                          -106 110.941 357,
+                          -100 144.941 357,
+                          -106 119.941 357,
+                          -115 110.941 357,
+                          -115 129.941 357,
+                          -100 144.941 357,
+                          -115 110.941 357,
+                          -115 129.941 361,
+                          -115 129.941 357,
+                          -115 110.941 357,
+                          -115 129.941 361,
+                          -115 110.941 357,
+                          -115 110.941 361,
+                          -106 110.941 361,
+                          -106 110.941 357,
+                          -106 119.941 357,
+                          -106 110.941 361,
+                          -115 110.941 361,
+                          -106 110.941 357,
+                          -100 144.941 357,
+                          -87.5 138.441 357,
+                          -106 119.941 357,
+                          -106 119.941 361,
+                          -106 119.941 357,
+                          -87.5 138.441 357,
+                          -106 110.941 361,
+                          -106 119.941 357,
+                          -106 119.941 361,
+                          -74 170.941 357,
+                          -69 119.941 357,
+                          -87.5 138.441 357,
+                          -87.5 138.441 361,
+                          -87.5 138.441 357,
+                          -69 119.941 357,
+                          -100 144.941 357,
+                          -74 170.941 357,
+                          -87.5 138.441 357,
+                          -106 119.941 361,
+                          -87.5 138.441 357,
+                          -87.5 138.441 361,
+                          45 170.941 357,
+                          -69 110.941 357,
+                          -69 119.941 357,
+                          -69 119.941 361,
+                          -69 119.941 357,
+                          -69 110.941 357,
+                          -74 170.941 357,
+                          45 170.941 357,
+                          -69 119.941 357,
+                          -87.5 138.441 361,
+                          -69 119.941 357,
+                          -69 119.941 361,
+                          -34 119.496 357,
+                          -34 110.941 357,
+                          -69 110.941 357,
+                          -69 110.941 361,
+                          -69 110.941 357,
+                          -34 110.941 357,
+                          45 170.941 357,
+                          -34 119.496 357,
+                          -69 110.941 357,
+                          -69 119.941 361,
+                          -69 110.941 357,
+                          -69 110.941 361,
+                          -34 110.941 361,
+                          -34 110.941 357,
+                          -34 119.496 357,
+                          -69 110.941 361,
+                          -34 110.941 357,
+                          -34 110.941 361,
+                          45 170.941 357,
+                          17 148.941 357,
+                          -34 119.496 357,
+                          -34 119.496 361,
+                          -34 119.496 357,
+                          17 148.941 357,
+                          -34 110.941 361,
+                          -34 119.496 357,
+                          -34 119.496 361,
+                          45 170.941 357,
+                          45 148.941 357,
+                          17 148.941 357,
+                          17 148.941 361,
+                          17 148.941 357,
+                          45 148.941 357,
+                          -34 119.496 361,
+                          17 148.941 357,
+                          17 148.941 361,
+                          45 148.941 361,
+                          45 148.941 357,
+                          45 170.941 357,
+                          17 148.941 361,
+                          45 148.941 357,
+                          45 148.941 361,
+                          45 170.941 361,
+                          45 170.941 357,
+                          -74 170.941 357,
+                          45 148.941 361,
+                          45 170.941 357,
+                          45 170.941 361,
+                          -74 170.941 361,
+                          -74 170.941 357,
+                          -100 144.941 357,
+                          45 170.941 361,
+                          -74 170.941 357,
+                          -74 170.941 361,
+                          -100 144.941 361,
+                          -100 144.941 357,
+                          -115 129.941 357,
+                          -74 170.941 361,
+                          -100 144.941 357,
+                          -100 144.941 361,
+                          -100 144.941 361,
+                          -115 129.941 357,
+                          -115 129.941 361,
+                          -106 110.941 361,
+                          -115 129.941 361,
+                          -115 110.941 361,
+                          -106 119.941 361,
+                          -100 144.941 361,
+                          -115 129.941 361,
+                          -106 110.941 361,
+                          -106 119.941 361,
+                          -115 129.941 361,
+                          -87.5 138.441 361,
+                          -74 170.941 361,
+                          -100 144.941 361,
+                          -106 119.941 361,
+                          -87.5 138.441 361,
+                          -100 144.941 361,
+                          45 148.941 361,
+                          45 170.941 361,
+                          -74 170.941 361,
+                          17 148.941 361,
+                          45 148.941 361,
+                          -74 170.941 361,
+                          -34 119.496 361,
+                          17 148.941 361,
+                          -74 170.941 361,
+                          -34 110.941 361,
+                          -34 119.496 361,
+                          -74 170.941 361,
+                          -69 119.941 361,
+                          -34 110.941 361,
+                          -74 170.941 361,
+                          -87.5 138.441 361,
+                          -69 119.941 361,
+                          -74 170.941 361,
+                          -69 119.941 361,
+                          -69 110.941 361,
+                          -34 110.941 361 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.707107 0.707107 1.57009e-16,
+                          0.707107 0.707107 1.57009e-16,
+                          0.707107 0.707107 1.57009e-16,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.707107 0.707107 1.57009e-16,
+                          -0.707107 0.707107 1.57009e-16,
+                          -0.707107 0.707107 1.57009e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.707107 0.707107 1.57009e-16,
+                          0.707107 0.707107 1.57009e-16,
+                          0.707107 0.707107 1.57009e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.707107 0.707107 1.57009e-16,
+                          -0.707107 0.707107 1.57009e-16,
+                          -0.707107 0.707107 1.57009e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.5 0.866025 1.92296e-16,
+                          0.5 0.866025 1.92296e-16,
+                          0.5 0.866025 1.92296e-16,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          0.5 0.866025 1.92296e-16,
+                          0.5 0.866025 1.92296e-16,
+                          0.5 0.866025 1.92296e-16,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          -0.707107 -0.707107 -1.57009e-16,
+                          -0.707107 -0.707107 -1.57009e-16,
+                          -0.707107 -0.707107 -1.57009e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          -0.707107 -0.707107 -1.57009e-16,
+                          -0.707107 -0.707107 -1.57009e-16,
+                          -0.707107 -0.707107 -1.57009e-16,
+                          -0.707107 -0.707107 -1.57009e-16,
+                          -0.707107 -0.707107 -1.57009e-16,
+                          -0.707107 -0.707107 -1.57009e-16,
+                          -0.707107 -0.707107 -1.57009e-16,
+                          -0.707107 -0.707107 -1.57009e-16,
+                          -0.707107 -0.707107 -1.57009e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -106 -120 361,
+                          -106 -111 361,
+                          -115 -111 361,
+                          -115 -111 357,
+                          -115 -111 361,
+                          -106 -111 361,
+                          -100 -145 361,
+                          -106 -120 361,
+                          -115 -111 361,
+                          -115 -130 361,
+                          -100 -145 361,
+                          -115 -111 361,
+                          -115 -130 357,
+                          -115 -130 361,
+                          -115 -111 361,
+                          -115 -130 357,
+                          -115 -111 361,
+                          -115 -111 357,
+                          -106 -111 357,
+                          -106 -111 361,
+                          -106 -120 361,
+                          -106 -111 357,
+                          -115 -111 357,
+                          -106 -111 361,
+                          -100 -145 361,
+                          -87.5 -138.5 361,
+                          -106 -120 361,
+                          -106 -120 357,
+                          -106 -120 361,
+                          -87.5 -138.5 361,
+                          -106 -111 357,
+                          -106 -120 361,
+                          -106 -120 357,
+                          -74 -171 361,
+                          -69 -120 361,
+                          -87.5 -138.5 361,
+                          -87.5 -138.5 357,
+                          -87.5 -138.5 361,
+                          -69 -120 361,
+                          -100 -145 361,
+                          -74 -171 361,
+                          -87.5 -138.5 361,
+                          -106 -120 357,
+                          -87.5 -138.5 361,
+                          -87.5 -138.5 357,
+                          45 -171 361,
+                          -69 -111 361,
+                          -69 -120 361,
+                          -69 -120 357,
+                          -69 -120 361,
+                          -69 -111 361,
+                          -74 -171 361,
+                          45 -171 361,
+                          -69 -120 361,
+                          -87.5 -138.5 357,
+                          -69 -120 361,
+                          -69 -120 357,
+                          -34 -119.555 361,
+                          -34 -111 361,
+                          -69 -111 361,
+                          -69 -111 357,
+                          -69 -111 361,
+                          -34 -111 361,
+                          45 -171 361,
+                          -34 -119.555 361,
+                          -69 -111 361,
+                          -69 -120 357,
+                          -69 -111 361,
+                          -69 -111 357,
+                          -34 -111 357,
+                          -34 -111 361,
+                          -34 -119.555 361,
+                          -69 -111 357,
+                          -34 -111 361,
+                          -34 -111 357,
+                          45 -171 361,
+                          17 -149 361,
+                          -34 -119.555 361,
+                          -34 -119.555 357,
+                          -34 -119.555 361,
+                          17 -149 361,
+                          -34 -111 357,
+                          -34 -119.555 361,
+                          -34 -119.555 357,
+                          45 -171 361,
+                          45 -149 361,
+                          17 -149 361,
+                          17 -149 357,
+                          17 -149 361,
+                          45 -149 361,
+                          -34 -119.555 357,
+                          17 -149 361,
+                          17 -149 357,
+                          45 -149 357,
+                          45 -149 361,
+                          45 -171 361,
+                          17 -149 357,
+                          45 -149 361,
+                          45 -149 357,
+                          45 -171 357,
+                          45 -171 361,
+                          -74 -171 361,
+                          45 -149 357,
+                          45 -171 361,
+                          45 -171 357,
+                          -74 -171 357,
+                          -74 -171 361,
+                          -100 -145 361,
+                          45 -171 357,
+                          -74 -171 361,
+                          -74 -171 357,
+                          -100 -145 357,
+                          -100 -145 361,
+                          -115 -130 361,
+                          -74 -171 357,
+                          -100 -145 361,
+                          -100 -145 357,
+                          -100 -145 357,
+                          -115 -130 361,
+                          -115 -130 357,
+                          -106 -111 357,
+                          -115 -130 357,
+                          -115 -111 357,
+                          -106 -120 357,
+                          -100 -145 357,
+                          -115 -130 357,
+                          -106 -111 357,
+                          -106 -120 357,
+                          -115 -130 357,
+                          -87.5 -138.5 357,
+                          -74 -171 357,
+                          -100 -145 357,
+                          -106 -120 357,
+                          -87.5 -138.5 357,
+                          -100 -145 357,
+                          45 -149 357,
+                          45 -171 357,
+                          -74 -171 357,
+                          17 -149 357,
+                          45 -149 357,
+                          -74 -171 357,
+                          -34 -119.555 357,
+                          17 -149 357,
+                          -74 -171 357,
+                          -34 -111 357,
+                          -34 -119.555 357,
+                          -74 -171 357,
+                          -69 -120 357,
+                          -34 -111 357,
+                          -74 -171 357,
+                          -87.5 -138.5 357,
+                          -69 -120 357,
+                          -74 -171 357,
+                          -69 -120 357,
+                          -69 -111 357,
+                          -34 -111 357 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          5.07889e-16 -0.258816 0.965927,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          5.07889e-16 -0.258816 0.965927,
+                          5.07889e-16 -0.258816 0.965927,
+                          4.44089e-16 -1.33397e-16 1,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          3.50026e-16 0.258816 0.965927,
+                          4.44089e-16 2.70877e-15 1,
+                          4.44089e-16 2.70877e-15 1,
+                          3.50026e-16 0.258816 0.965927,
+                          3.50026e-16 0.258816 0.965927,
+                          4.44089e-16 2.70877e-15 1,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          9.85334e-17 0.706888 0.707325,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          9.85334e-17 0.706888 0.707325,
+                          4.44089e-16 -1.33397e-16 1,
+                          9.85334e-17 0.706888 0.707325,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          3.50026e-16 0.258816 0.965927,
+                          4.44089e-16 -2.76192e-16 1,
+                          4.44089e-16 -1.55448e-15 1,
+                          3.50026e-16 0.258816 0.965927,
+                          4.44089e-16 -2.76192e-16 1,
+                          3.50026e-16 0.258816 0.965927,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          5.29698e-16 -0.706888 0.707325,
+                          4.44089e-16 -1.90975e-15 1,
+                          4.44089e-16 -1.90975e-15 1,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          5.29698e-16 -0.706888 0.707325,
+                          5.29698e-16 -0.706888 0.707325,
+                          4.44089e-16 -1.90975e-15 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          5.07889e-16 -0.258816 0.965927,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          5.07889e-16 -0.258816 0.965927,
+                          4.44089e-16 -1.33397e-16 1,
+                          5.07889e-16 -0.258816 0.965927,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          2.32106e-16 0.5 0.866025,
+                          2.32106e-16 0.5 0.866025,
+                          2.32106e-16 0.5 0.866025,
+                          3.50026e-16 0.258816 0.965927,
+                          2.32106e-16 0.5 0.866025,
+                          2.32106e-16 0.5 0.866025,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          3.50026e-16 0.258816 0.965927,
+                          3.50026e-16 0.258816 0.965927,
+                          2.32106e-16 0.5 0.866025,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          2.32106e-16 0.5 0.866025,
+                          2.32106e-16 0.5 0.866025,
+                          2.32106e-16 0.5 0.866025,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          3.50026e-16 0.258816 0.965927,
+                          2.32106e-16 0.5 0.866025,
+                          2.32106e-16 0.5 0.866025,
+                          3.50026e-16 0.258816 0.965927,
+                          2.32106e-16 0.5 0.866025,
+                          3.50026e-16 0.258816 0.965927,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          5.37079e-16 -0.5 0.866025,
+                          5.37079e-16 -0.5 0.866025,
+                          5.37079e-16 -0.5 0.866025,
+                          5.07889e-16 -0.258816 0.965927,
+                          5.37079e-16 -0.5 0.866025,
+                          5.37079e-16 -0.5 0.866025,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          5.07889e-16 -0.258816 0.965927,
+                          5.07889e-16 -0.258816 0.965927,
+                          5.37079e-16 -0.5 0.866025,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          5.37079e-16 -0.5 0.866025,
+                          5.37079e-16 -0.5 0.866025,
+                          5.37079e-16 -0.5 0.866025,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          5.07889e-16 -0.258816 0.965927,
+                          5.37079e-16 -0.5 0.866025,
+                          5.37079e-16 -0.5 0.866025,
+                          5.07889e-16 -0.258816 0.965927,
+                          5.37079e-16 -0.5 0.866025,
+                          5.07889e-16 -0.258816 0.965927,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -5.29637e-16 0.707325 -0.706888,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -5.29637e-16 0.707325 -0.706888,
+                          -5.29637e-16 0.707325 -0.706888,
+                          -4.44089e-16 1.94627e-16 -1,
+                          -3.04973e-16 1 1.33397e-16,
+                          -5.29637e-16 0.707325 -0.706888,
+                          -5.29637e-16 0.707325 -0.706888,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -5.29637e-16 0.707325 -0.706888,
+                          -4.44089e-16 1.94627e-16 -1,
+                          -4.44089e-16 1.94627e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -9.85334e-17 -0.706888 -0.707325,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -9.85334e-17 -0.706888 -0.707325,
+                          -9.85334e-17 -0.706888 -0.707325,
+                          3.04973e-16 -1 -1.94627e-16,
+                          -9.85334e-17 -0.706888 -0.707325,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -9.85334e-17 -0.706888 -0.707325,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          -9.85334e-17 -0.706888 -0.707325,
+                          3.04973e-16 -1 -1.94627e-16,
+                          3.04973e-16 -1 -1.94627e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          9.85334e-17 0.706888 0.707325,
+                          9.85334e-17 0.706888 0.707325,
+                          -3.04973e-16 1 1.94627e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          9.85334e-17 0.706888 0.707325,
+                          -3.04973e-16 1 1.94627e-16,
+                          -3.04973e-16 1 1.94627e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          3.04973e-16 -1 -1.84852e-15,
+                          3.04973e-16 -1 -1.84852e-15,
+                          5.29698e-16 -0.706888 0.707325,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.84852e-15,
+                          5.29698e-16 -0.706888 0.707325,
+                          5.29698e-16 -0.706888 0.707325,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -81 -110.34 488,
+                          -84 -110.34 488,
+                          -84 -117 488,
+                          -84 -117 431,
+                          -84 -117 488,
+                          -84 -110.34 488,
+                          -81 -117 488,
+                          -81 -110.34 488,
+                          -84 -117 488,
+                          -84 -117 431,
+                          -81 -117 488,
+                          -84 -117 488,
+                          -81 -109.046 488.171,
+                          -84 -110.34 488,
+                          -81 -110.34 488,
+                          -84 -111 431,
+                          -84 -110.34 488,
+                          -84 -111 406,
+                          -84 -109.046 488.171,
+                          -84 -111 406,
+                          -84 -110.34 488,
+                          -84 -117 431,
+                          -84 -110.34 488,
+                          -84 -111 431,
+                          -81 -109.046 488.171,
+                          -84 -109.046 488.171,
+                          -84 -110.34 488,
+                          -81 -111 431,
+                          -81 -110.34 488,
+                          -81 -117 488,
+                          -81 -81 406,
+                          -81 -110.34 488,
+                          -81 -111 431,
+                          -81 -81 406,
+                          -81 -109.046 488.171,
+                          -81 -110.34 488,
+                          -81 -117 431,
+                          -81 -111 431,
+                          -81 -117 488,
+                          -81 -117 431,
+                          -81 -117 488,
+                          -84 -117 431,
+                          -81 -111 431,
+                          -84 -111 431,
+                          -84 -111 406,
+                          -81 -111 406,
+                          -81 -111 431,
+                          -84 -111 406,
+                          -84 -81 406,
+                          -81 -111 406,
+                          -84 -111 406,
+                          -84 -109.046 488.171,
+                          -84 -107.84 488.67,
+                          -84 -111 406,
+                          -84 -81 415.5,
+                          -84 -111 406,
+                          -84 -107.84 488.67,
+                          -84 -81 415.5,
+                          -84 -81 406,
+                          -84 -111 406,
+                          -81 -117 431,
+                          -84 -111 431,
+                          -81 -111 431,
+                          -81 -117 431,
+                          -84 -117 431,
+                          -84 -111 431,
+                          -81 -81 406,
+                          -81 -111 431,
+                          -81 -111 406,
+                          -81 -81 406,
+                          -81 -111 406,
+                          -84 -81 406,
+                          -84 111 431,
+                          -81 111 406,
+                          -84 111 406,
+                          -81 81 406,
+                          -84 111 406,
+                          -81 111 406,
+                          -84 81 406,
+                          -84 111 431,
+                          -84 111 406,
+                          -81 81 406,
+                          -84 81 406,
+                          -84 111 406,
+                          -84 111 431,
+                          -81 111 431,
+                          -81 111 406,
+                          -81 110.34 488,
+                          -81 111 406,
+                          -81 111 431,
+                          -81 109.046 488.171,
+                          -81 111 406,
+                          -81 110.34 488,
+                          -81 109.046 488.171,
+                          -81 107.84 488.67,
+                          -81 111 406,
+                          -81 81 415.5,
+                          -81 111 406,
+                          -81 107.84 488.67,
+                          -81 81 415.5,
+                          -81 81 406,
+                          -81 111 406,
+                          -84 117 431,
+                          -81 111 431,
+                          -84 111 431,
+                          -81 117 431,
+                          -81 110.34 488,
+                          -81 111 431,
+                          -81 117 431,
+                          -81 111 431,
+                          -84 117 431,
+                          -84 110.34 488,
+                          -84 117 488,
+                          -84 111 431,
+                          -84 117 431,
+                          -84 111 431,
+                          -84 117 488,
+                          -84 81 406,
+                          -84 110.34 488,
+                          -84 111 431,
+                          -84 110.34 488,
+                          -81 117 488,
+                          -84 117 488,
+                          -81 117 431,
+                          -84 117 488,
+                          -81 117 488,
+                          -81 117 431,
+                          -84 117 431,
+                          -84 117 488,
+                          -84 110.34 488,
+                          -81 110.34 488,
+                          -81 117 488,
+                          -81 117 431,
+                          -81 117 488,
+                          -81 110.34 488,
+                          -84 109.046 488.171,
+                          -81 110.34 488,
+                          -84 110.34 488,
+                          -84 109.046 488.171,
+                          -81 109.046 488.171,
+                          -81 110.34 488,
+                          -84 81 406,
+                          -84 109.046 488.171,
+                          -84 110.34 488,
+                          -81 60.8949 515,
+                          -84 46.5 515,
+                          -81 46.5 515,
+                          -84 43.6724 516.171,
+                          -81 46.5 515,
+                          -84 46.5 515,
+                          -81 77 419.5,
+                          -81 60.8949 515,
+                          -81 46.5 515,
+                          -81 43.6724 516.171,
+                          -81 46.5 515,
+                          -84 43.6724 516.171,
+                          -81 43.6724 516.171,
+                          -81 77 419.5,
+                          -81 46.5 515,
+                          -81 60.8949 515,
+                          -84 60.8949 515,
+                          -84 46.5 515,
+                          -84 -77 419.5,
+                          -84 46.5 515,
+                          -84 60.8949 515,
+                          -84 43.6724 516.171,
+                          -84 46.5 515,
+                          -84 -77 419.5,
+                          -81 62.1888 514.829,
+                          -84 60.8949 515,
+                          -81 60.8949 515,
+                          -84 62.1888 514.829,
+                          -84 60.8949 515,
+                          -81 62.1888 514.829,
+                          -84 -77 419.5,
+                          -84 60.8949 515,
+                          -84 62.1888 514.829,
+                          -81 77 419.5,
+                          -81 62.1888 514.829,
+                          -81 60.8949 515,
+                          -84 -60.8949 515,
+                          -81 -46.5 515,
+                          -84 -46.5 515,
+                          -81 -43.6724 516.171,
+                          -84 -46.5 515,
+                          -81 -46.5 515,
+                          -84 -77 419.5,
+                          -84 -60.8949 515,
+                          -84 -46.5 515,
+                          -84 -43.6724 516.171,
+                          -84 -77 419.5,
+                          -84 -46.5 515,
+                          -81 -43.6724 516.171,
+                          -84 -43.6724 516.171,
+                          -84 -46.5 515,
+                          -84 -60.8949 515,
+                          -81 -60.8949 515,
+                          -81 -46.5 515,
+                          -81 77 419.5,
+                          -81 -46.5 515,
+                          -81 -60.8949 515,
+                          -81 -43.6724 516.171,
+                          -81 -46.5 515,
+                          -81 77 419.5,
+                          -84 -62.1888 514.829,
+                          -81 -60.8949 515,
+                          -84 -60.8949 515,
+                          -81 -62.1888 514.829,
+                          -81 -60.8949 515,
+                          -84 -62.1888 514.829,
+                          -81 77 419.5,
+                          -81 -60.8949 515,
+                          -81 -62.1888 514.829,
+                          -84 -77 419.5,
+                          -84 -62.1888 514.829,
+                          -84 -60.8949 515,
+                          -81 107.84 488.67,
+                          -84 63.3949 514.33,
+                          -81 63.3949 514.33,
+                          -84 62.1888 514.829,
+                          -81 63.3949 514.33,
+                          -84 63.3949 514.33,
+                          -81 81 415.5,
+                          -81 107.84 488.67,
+                          -81 63.3949 514.33,
+                          -84 62.1888 514.829,
+                          -81 62.1888 514.829,
+                          -81 63.3949 514.33,
+                          -81 77 419.5,
+                          -81 63.3949 514.33,
+                          -81 62.1888 514.829,
+                          -81 79.8276 418.329,
+                          -81 63.3949 514.33,
+                          -81 77 419.5,
+                          -81 79.8276 418.329,
+                          -81 81 415.5,
+                          -81 63.3949 514.33,
+                          -81 107.84 488.67,
+                          -84 107.84 488.67,
+                          -84 63.3949 514.33,
+                          -84 77 419.5,
+                          -84 63.3949 514.33,
+                          -84 107.84 488.67,
+                          -84 -77 419.5,
+                          -84 62.1888 514.829,
+                          -84 63.3949 514.33,
+                          -84 77 419.5,
+                          -84 -77 419.5,
+                          -84 63.3949 514.33,
+                          -81 109.046 488.171,
+                          -84 107.84 488.67,
+                          -81 107.84 488.67,
+                          -84 109.046 488.171,
+                          -84 107.84 488.67,
+                          -81 109.046 488.171,
+                          -84 81 406,
+                          -84 107.84 488.67,
+                          -84 109.046 488.171,
+                          -84 79.8276 418.329,
+                          -84 77 419.5,
+                          -84 107.84 488.67,
+                          -84 81 415.5,
+                          -84 79.8276 418.329,
+                          -84 107.84 488.67,
+                          -84 81 406,
+                          -84 81 415.5,
+                          -84 107.84 488.67,
+                          -84 -107.84 488.67,
+                          -81 -63.3949 514.33,
+                          -84 -63.3949 514.33,
+                          -81 -62.1888 514.829,
+                          -84 -63.3949 514.33,
+                          -81 -63.3949 514.33,
+                          -84 -81 415.5,
+                          -84 -107.84 488.67,
+                          -84 -63.3949 514.33,
+                          -81 -62.1888 514.829,
+                          -84 -62.1888 514.829,
+                          -84 -63.3949 514.33,
+                          -84 -77 419.5,
+                          -84 -63.3949 514.33,
+                          -84 -62.1888 514.829,
+                          -84 -79.8293 418.328,
+                          -84 -81 415.5,
+                          -84 -63.3949 514.33,
+                          -84 -77 419.5,
+                          -84 -79.8293 418.328,
+                          -84 -63.3949 514.33,
+                          -84 -107.84 488.67,
+                          -81 -107.84 488.67,
+                          -81 -63.3949 514.33,
+                          -81 -77 419.5,
+                          -81 -63.3949 514.33,
+                          -81 -107.84 488.67,
+                          -81 77 419.5,
+                          -81 -62.1888 514.829,
+                          -81 -63.3949 514.33,
+                          -81 -77 419.5,
+                          -81 77 419.5,
+                          -81 -63.3949 514.33,
+                          -84 -109.046 488.171,
+                          -81 -107.84 488.67,
+                          -84 -107.84 488.67,
+                          -81 -109.046 488.171,
+                          -81 -107.84 488.67,
+                          -84 -109.046 488.171,
+                          -81 -81 406,
+                          -81 -107.84 488.67,
+                          -81 -109.046 488.171,
+                          -81 -79.8293 418.328,
+                          -81 -77 419.5,
+                          -81 -107.84 488.67,
+                          -81 -81 415.5,
+                          -81 -79.8293 418.328,
+                          -81 -107.84 488.67,
+                          -81 -81 406,
+                          -81 -81 415.5,
+                          -81 -107.84 488.67,
+                          -81 -81 406,
+                          -84 -81 406,
+                          -84 -81 415.5,
+                          -81 -81 415.5,
+                          -84 -81 415.5,
+                          -84 -79.8293 418.328,
+                          -81 -81 406,
+                          -84 -81 415.5,
+                          -81 -81 415.5,
+                          -81 -79.8293 418.328,
+                          -84 -79.8293 418.328,
+                          -84 -77 419.5,
+                          -81 -81 415.5,
+                          -84 -79.8293 418.328,
+                          -81 -79.8293 418.328,
+                          -81 -77 419.5,
+                          -84 -77 419.5,
+                          -84 77 419.5,
+                          -84 42.5 519,
+                          -84 43.6724 516.171,
+                          -84 -77 419.5,
+                          -84 42.5 535,
+                          -84 42.5 519,
+                          -84 -77 419.5,
+                          -84 -42.5 519,
+                          -84 42.5 535,
+                          -84 -77 419.5,
+                          -84 -43.6724 516.171,
+                          -84 -42.5 519,
+                          -84 -77 419.5,
+                          -81 -79.8293 418.328,
+                          -84 -77 419.5,
+                          -81 -77 419.5,
+                          -81 77 419.5,
+                          -84 77 419.5,
+                          -84 79.8276 418.329,
+                          -81 -77 419.5,
+                          -84 77 419.5,
+                          -81 77 419.5,
+                          -81 79.8276 418.329,
+                          -84 79.8276 418.329,
+                          -84 81 415.5,
+                          -81 79.8276 418.329,
+                          -81 77 419.5,
+                          -84 79.8276 418.329,
+                          -81 81 415.5,
+                          -84 81 415.5,
+                          -84 81 406,
+                          -81 79.8276 418.329,
+                          -84 81 415.5,
+                          -81 81 415.5,
+                          -81 81 415.5,
+                          -84 81 406,
+                          -81 81 406,
+                          -81 43.6724 516.171,
+                          -84 43.6724 516.171,
+                          -84 42.5 519,
+                          -81 42.5 519,
+                          -84 42.5 519,
+                          -84 42.5 535,
+                          -81 43.6724 516.171,
+                          -84 42.5 519,
+                          -81 42.5 519,
+                          -84 -42.5 519,
+                          -84 -42.5 535,
+                          -84 42.5 535,
+                          -81 42.5 535,
+                          -84 42.5 535,
+                          -84 -42.5 535,
+                          -81 42.5 519,
+                          -84 42.5 535,
+                          -81 42.5 535,
+                          -81 -42.5 535,
+                          -84 -42.5 535,
+                          -84 -42.5 519,
+                          -81 42.5 535,
+                          -84 -42.5 535,
+                          -81 -42.5 535,
+                          -81 -42.5 519,
+                          -84 -42.5 519,
+                          -84 -43.6724 516.171,
+                          -81 -42.5 535,
+                          -84 -42.5 519,
+                          -81 -42.5 519,
+                          -81 -42.5 519,
+                          -84 -43.6724 516.171,
+                          -81 -43.6724 516.171,
+                          -81 -42.5 519,
+                          -81 -43.6724 516.171,
+                          -81 77 419.5,
+                          -81 -42.5 535,
+                          -81 -42.5 519,
+                          -81 77 419.5,
+                          -81 42.5 519,
+                          -81 -42.5 535,
+                          -81 77 419.5,
+                          -81 43.6724 516.171,
+                          -81 42.5 519,
+                          -81 77 419.5,
+                          -81 42.5 519,
+                          -81 42.5 535,
+                          -81 -42.5 535 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          5.59884e-17 -0.258816 0.965927,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          5.59884e-17 -0.258816 0.965927,
+                          5.59884e-17 -0.258816 0.965927,
+                          0 -2.22045e-16 1,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          -5.59884e-17 0.258816 0.965927,
+                          0 2.62013e-15 1,
+                          0 2.62013e-15 1,
+                          -5.59884e-17 0.258816 0.965927,
+                          -5.59884e-17 0.258816 0.965927,
+                          0 2.62013e-15 1,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -1.52918e-16 0.706888 0.707325,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          -1.52918e-16 0.706888 0.707325,
+                          0 -2.22045e-16 1,
+                          -1.52918e-16 0.706888 0.707325,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -5.59884e-17 0.258816 0.965927,
+                          0 -3.64839e-16 1,
+                          0 -1.64313e-15 1,
+                          -5.59884e-17 0.258816 0.965927,
+                          0 -3.64839e-16 1,
+                          -5.59884e-17 0.258816 0.965927,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          1.52918e-16 -0.706888 0.707325,
+                          0 -1.9984e-15 1,
+                          0 -1.9984e-15 1,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          1.52918e-16 -0.706888 0.707325,
+                          1.52918e-16 -0.706888 0.707325,
+                          0 -1.9984e-15 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          5.59884e-17 -0.258816 0.965927,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          5.59884e-17 -0.258816 0.965927,
+                          0 -2.22045e-16 1,
+                          5.59884e-17 -0.258816 0.965927,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1.08163e-16 0.5 0.866025,
+                          -1.08163e-16 0.5 0.866025,
+                          -1.08163e-16 0.5 0.866025,
+                          -5.59884e-17 0.258816 0.965927,
+                          -1.08163e-16 0.5 0.866025,
+                          -1.08163e-16 0.5 0.866025,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          -5.59884e-17 0.258816 0.965927,
+                          -5.59884e-17 0.258816 0.965927,
+                          -1.08163e-16 0.5 0.866025,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          -1.08163e-16 0.5 0.866025,
+                          -1.08163e-16 0.5 0.866025,
+                          -1.08163e-16 0.5 0.866025,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -5.59884e-17 0.258816 0.965927,
+                          -1.08163e-16 0.5 0.866025,
+                          -1.08163e-16 0.5 0.866025,
+                          -5.59884e-17 0.258816 0.965927,
+                          -1.08163e-16 0.5 0.866025,
+                          -5.59884e-17 0.258816 0.965927,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          1.08163e-16 -0.5 0.866025,
+                          1.08163e-16 -0.5 0.866025,
+                          1.08163e-16 -0.5 0.866025,
+                          5.59884e-17 -0.258816 0.965927,
+                          1.08163e-16 -0.5 0.866025,
+                          1.08163e-16 -0.5 0.866025,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          5.59884e-17 -0.258816 0.965927,
+                          5.59884e-17 -0.258816 0.965927,
+                          1.08163e-16 -0.5 0.866025,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          1.08163e-16 -0.5 0.866025,
+                          1.08163e-16 -0.5 0.866025,
+                          1.08163e-16 -0.5 0.866025,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          5.59884e-17 -0.258816 0.965927,
+                          1.08163e-16 -0.5 0.866025,
+                          1.08163e-16 -0.5 0.866025,
+                          5.59884e-17 -0.258816 0.965927,
+                          1.08163e-16 -0.5 0.866025,
+                          5.59884e-17 -0.258816 0.965927,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -1.53012e-16 0.707325 -0.706888,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -1.53012e-16 0.707325 -0.706888,
+                          -1.53012e-16 0.707325 -0.706888,
+                          0 2.83275e-16 -1,
+                          -2.16325e-16 1 2.22045e-16,
+                          -1.53012e-16 0.707325 -0.706888,
+                          -1.53012e-16 0.707325 -0.706888,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1.53012e-16 0.707325 -0.706888,
+                          0 2.83275e-16 -1,
+                          0 2.83275e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1.52918e-16 -0.706888 -0.707325,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1.52918e-16 -0.706888 -0.707325,
+                          1.52918e-16 -0.706888 -0.707325,
+                          2.16325e-16 -1 -2.83275e-16,
+                          1.52918e-16 -0.706888 -0.707325,
+                          0 2.22045e-16 -1,
+                          1.52918e-16 -0.706888 -0.707325,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          1.52918e-16 -0.706888 -0.707325,
+                          2.16325e-16 -1 -2.83275e-16,
+                          2.16325e-16 -1 -2.83275e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          -1.52918e-16 0.706888 0.707325,
+                          -1.52918e-16 0.706888 0.707325,
+                          -2.16325e-16 1 2.83275e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -1.52918e-16 0.706888 0.707325,
+                          -2.16325e-16 1 2.83275e-16,
+                          -2.16325e-16 1 2.83275e-16,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          2.16325e-16 -1 -1.93717e-15,
+                          2.16325e-16 -1 -1.93717e-15,
+                          1.52918e-16 -0.706888 0.707325,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -1.93717e-15,
+                          1.52918e-16 -0.706888 0.707325,
+                          1.52918e-16 -0.706888 0.707325,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 14 -110.34 488,
+                          11 -110.34 488,
+                          11 -117 488,
+                          11 -117 431,
+                          11 -117 488,
+                          11 -110.34 488,
+                          14 -117 488,
+                          14 -110.34 488,
+                          11 -117 488,
+                          11 -117 431,
+                          14 -117 488,
+                          11 -117 488,
+                          14 -109.046 488.171,
+                          11 -110.34 488,
+                          14 -110.34 488,
+                          11 -111 431,
+                          11 -110.34 488,
+                          11 -111 406,
+                          11 -109.046 488.171,
+                          11 -111 406,
+                          11 -110.34 488,
+                          11 -117 431,
+                          11 -110.34 488,
+                          11 -111 431,
+                          14 -109.046 488.171,
+                          11 -109.046 488.171,
+                          11 -110.34 488,
+                          14 -111 431,
+                          14 -110.34 488,
+                          14 -117 488,
+                          14 -81 406,
+                          14 -110.34 488,
+                          14 -111 431,
+                          14 -81 406,
+                          14 -109.046 488.171,
+                          14 -110.34 488,
+                          14 -117 431,
+                          14 -111 431,
+                          14 -117 488,
+                          14 -117 431,
+                          14 -117 488,
+                          11 -117 431,
+                          14 -111 431,
+                          11 -111 431,
+                          11 -111 406,
+                          14 -111 406,
+                          14 -111 431,
+                          11 -111 406,
+                          11 -81 406,
+                          14 -111 406,
+                          11 -111 406,
+                          11 -109.046 488.171,
+                          11 -107.84 488.67,
+                          11 -111 406,
+                          11 -81 415.5,
+                          11 -111 406,
+                          11 -107.84 488.67,
+                          11 -81 415.5,
+                          11 -81 406,
+                          11 -111 406,
+                          14 -117 431,
+                          11 -111 431,
+                          14 -111 431,
+                          14 -117 431,
+                          11 -117 431,
+                          11 -111 431,
+                          14 -81 406,
+                          14 -111 431,
+                          14 -111 406,
+                          14 -81 406,
+                          14 -111 406,
+                          11 -81 406,
+                          11 111 431,
+                          14 111 406,
+                          11 111 406,
+                          14 81 406,
+                          11 111 406,
+                          14 111 406,
+                          11 81 406,
+                          11 111 431,
+                          11 111 406,
+                          14 81 406,
+                          11 81 406,
+                          11 111 406,
+                          11 111 431,
+                          14 111 431,
+                          14 111 406,
+                          14 110.34 488,
+                          14 111 406,
+                          14 111 431,
+                          14 109.046 488.171,
+                          14 111 406,
+                          14 110.34 488,
+                          14 109.046 488.171,
+                          14 107.84 488.67,
+                          14 111 406,
+                          14 81 415.5,
+                          14 111 406,
+                          14 107.84 488.67,
+                          14 81 415.5,
+                          14 81 406,
+                          14 111 406,
+                          11 117 431,
+                          14 111 431,
+                          11 111 431,
+                          14 117 431,
+                          14 110.34 488,
+                          14 111 431,
+                          14 117 431,
+                          14 111 431,
+                          11 117 431,
+                          11 110.34 488,
+                          11 117 488,
+                          11 111 431,
+                          11 117 431,
+                          11 111 431,
+                          11 117 488,
+                          11 81 406,
+                          11 110.34 488,
+                          11 111 431,
+                          11 110.34 488,
+                          14 117 488,
+                          11 117 488,
+                          14 117 431,
+                          11 117 488,
+                          14 117 488,
+                          14 117 431,
+                          11 117 431,
+                          11 117 488,
+                          11 110.34 488,
+                          14 110.34 488,
+                          14 117 488,
+                          14 117 431,
+                          14 117 488,
+                          14 110.34 488,
+                          11 109.046 488.171,
+                          14 110.34 488,
+                          11 110.34 488,
+                          11 109.046 488.171,
+                          14 109.046 488.171,
+                          14 110.34 488,
+                          11 81 406,
+                          11 109.046 488.171,
+                          11 110.34 488,
+                          14 60.8949 515,
+                          11 46.5 515,
+                          14 46.5 515,
+                          11 43.6724 516.171,
+                          14 46.5 515,
+                          11 46.5 515,
+                          14 77 419.5,
+                          14 60.8949 515,
+                          14 46.5 515,
+                          14 43.6724 516.171,
+                          14 46.5 515,
+                          11 43.6724 516.171,
+                          14 43.6724 516.171,
+                          14 77 419.5,
+                          14 46.5 515,
+                          14 60.8949 515,
+                          11 60.8949 515,
+                          11 46.5 515,
+                          11 -77 419.5,
+                          11 46.5 515,
+                          11 60.8949 515,
+                          11 43.6724 516.171,
+                          11 46.5 515,
+                          11 -77 419.5,
+                          14 62.1888 514.829,
+                          11 60.8949 515,
+                          14 60.8949 515,
+                          11 62.1888 514.829,
+                          11 60.8949 515,
+                          14 62.1888 514.829,
+                          11 -77 419.5,
+                          11 60.8949 515,
+                          11 62.1888 514.829,
+                          14 77 419.5,
+                          14 62.1888 514.829,
+                          14 60.8949 515,
+                          11 -60.8949 515,
+                          14 -46.5 515,
+                          11 -46.5 515,
+                          14 -43.6724 516.171,
+                          11 -46.5 515,
+                          14 -46.5 515,
+                          11 -77 419.5,
+                          11 -60.8949 515,
+                          11 -46.5 515,
+                          11 -43.6724 516.171,
+                          11 -77 419.5,
+                          11 -46.5 515,
+                          14 -43.6724 516.171,
+                          11 -43.6724 516.171,
+                          11 -46.5 515,
+                          11 -60.8949 515,
+                          14 -60.8949 515,
+                          14 -46.5 515,
+                          14 77 419.5,
+                          14 -46.5 515,
+                          14 -60.8949 515,
+                          14 -43.6724 516.171,
+                          14 -46.5 515,
+                          14 77 419.5,
+                          11 -62.1888 514.829,
+                          14 -60.8949 515,
+                          11 -60.8949 515,
+                          14 -62.1888 514.829,
+                          14 -60.8949 515,
+                          11 -62.1888 514.829,
+                          14 77 419.5,
+                          14 -60.8949 515,
+                          14 -62.1888 514.829,
+                          11 -77 419.5,
+                          11 -62.1888 514.829,
+                          11 -60.8949 515,
+                          14 107.84 488.67,
+                          11 63.3949 514.33,
+                          14 63.3949 514.33,
+                          11 62.1888 514.829,
+                          14 63.3949 514.33,
+                          11 63.3949 514.33,
+                          14 81 415.5,
+                          14 107.84 488.67,
+                          14 63.3949 514.33,
+                          11 62.1888 514.829,
+                          14 62.1888 514.829,
+                          14 63.3949 514.33,
+                          14 77 419.5,
+                          14 63.3949 514.33,
+                          14 62.1888 514.829,
+                          14 79.8276 418.329,
+                          14 63.3949 514.33,
+                          14 77 419.5,
+                          14 79.8276 418.329,
+                          14 81 415.5,
+                          14 63.3949 514.33,
+                          14 107.84 488.67,
+                          11 107.84 488.67,
+                          11 63.3949 514.33,
+                          11 77 419.5,
+                          11 63.3949 514.33,
+                          11 107.84 488.67,
+                          11 -77 419.5,
+                          11 62.1888 514.829,
+                          11 63.3949 514.33,
+                          11 77 419.5,
+                          11 -77 419.5,
+                          11 63.3949 514.33,
+                          14 109.046 488.171,
+                          11 107.84 488.67,
+                          14 107.84 488.67,
+                          11 109.046 488.171,
+                          11 107.84 488.67,
+                          14 109.046 488.171,
+                          11 81 406,
+                          11 107.84 488.67,
+                          11 109.046 488.171,
+                          11 79.8276 418.329,
+                          11 77 419.5,
+                          11 107.84 488.67,
+                          11 81 415.5,
+                          11 79.8276 418.329,
+                          11 107.84 488.67,
+                          11 81 406,
+                          11 81 415.5,
+                          11 107.84 488.67,
+                          11 -107.84 488.67,
+                          14 -63.3949 514.33,
+                          11 -63.3949 514.33,
+                          14 -62.1888 514.829,
+                          11 -63.3949 514.33,
+                          14 -63.3949 514.33,
+                          11 -81 415.5,
+                          11 -107.84 488.67,
+                          11 -63.3949 514.33,
+                          14 -62.1888 514.829,
+                          11 -62.1888 514.829,
+                          11 -63.3949 514.33,
+                          11 -77 419.5,
+                          11 -63.3949 514.33,
+                          11 -62.1888 514.829,
+                          11 -79.8293 418.328,
+                          11 -81 415.5,
+                          11 -63.3949 514.33,
+                          11 -77 419.5,
+                          11 -79.8293 418.328,
+                          11 -63.3949 514.33,
+                          11 -107.84 488.67,
+                          14 -107.84 488.67,
+                          14 -63.3949 514.33,
+                          14 -77 419.5,
+                          14 -63.3949 514.33,
+                          14 -107.84 488.67,
+                          14 77 419.5,
+                          14 -62.1888 514.829,
+                          14 -63.3949 514.33,
+                          14 -77 419.5,
+                          14 77 419.5,
+                          14 -63.3949 514.33,
+                          11 -109.046 488.171,
+                          14 -107.84 488.67,
+                          11 -107.84 488.67,
+                          14 -109.046 488.171,
+                          14 -107.84 488.67,
+                          11 -109.046 488.171,
+                          14 -81 406,
+                          14 -107.84 488.67,
+                          14 -109.046 488.171,
+                          14 -79.8293 418.328,
+                          14 -77 419.5,
+                          14 -107.84 488.67,
+                          14 -81 415.5,
+                          14 -79.8293 418.328,
+                          14 -107.84 488.67,
+                          14 -81 406,
+                          14 -81 415.5,
+                          14 -107.84 488.67,
+                          14 -81 406,
+                          11 -81 406,
+                          11 -81 415.5,
+                          14 -81 415.5,
+                          11 -81 415.5,
+                          11 -79.8293 418.328,
+                          14 -81 406,
+                          11 -81 415.5,
+                          14 -81 415.5,
+                          14 -79.8293 418.328,
+                          11 -79.8293 418.328,
+                          11 -77 419.5,
+                          14 -81 415.5,
+                          11 -79.8293 418.328,
+                          14 -79.8293 418.328,
+                          14 -77 419.5,
+                          11 -77 419.5,
+                          11 77 419.5,
+                          11 42.5 519,
+                          11 43.6724 516.171,
+                          11 -77 419.5,
+                          11 42.5 535,
+                          11 42.5 519,
+                          11 -77 419.5,
+                          11 -42.5 519,
+                          11 42.5 535,
+                          11 -77 419.5,
+                          11 -43.6724 516.171,
+                          11 -42.5 519,
+                          11 -77 419.5,
+                          14 -79.8293 418.328,
+                          11 -77 419.5,
+                          14 -77 419.5,
+                          14 77 419.5,
+                          11 77 419.5,
+                          11 79.8276 418.329,
+                          14 -77 419.5,
+                          11 77 419.5,
+                          14 77 419.5,
+                          14 79.8276 418.329,
+                          11 79.8276 418.329,
+                          11 81 415.5,
+                          14 79.8276 418.329,
+                          14 77 419.5,
+                          11 79.8276 418.329,
+                          14 81 415.5,
+                          11 81 415.5,
+                          11 81 406,
+                          14 79.8276 418.329,
+                          11 81 415.5,
+                          14 81 415.5,
+                          14 81 415.5,
+                          11 81 406,
+                          14 81 406,
+                          14 43.6724 516.171,
+                          11 43.6724 516.171,
+                          11 42.5 519,
+                          14 42.5 519,
+                          11 42.5 519,
+                          11 42.5 535,
+                          14 43.6724 516.171,
+                          11 42.5 519,
+                          14 42.5 519,
+                          11 -42.5 519,
+                          11 -42.5 535,
+                          11 42.5 535,
+                          14 42.5 535,
+                          11 42.5 535,
+                          11 -42.5 535,
+                          14 42.5 519,
+                          11 42.5 535,
+                          14 42.5 535,
+                          14 -42.5 535,
+                          11 -42.5 535,
+                          11 -42.5 519,
+                          14 42.5 535,
+                          11 -42.5 535,
+                          14 -42.5 535,
+                          14 -42.5 519,
+                          11 -42.5 519,
+                          11 -43.6724 516.171,
+                          14 -42.5 535,
+                          11 -42.5 519,
+                          14 -42.5 519,
+                          14 -42.5 519,
+                          11 -43.6724 516.171,
+                          14 -43.6724 516.171,
+                          14 -42.5 519,
+                          14 -43.6724 516.171,
+                          14 77 419.5,
+                          14 -42.5 535,
+                          14 -42.5 519,
+                          14 77 419.5,
+                          14 42.5 519,
+                          14 -42.5 535,
+                          14 77 419.5,
+                          14 43.6724 516.171,
+                          14 42.5 519,
+                          14 77 419.5,
+                          14 42.5 519,
+                          14 42.5 535,
+                          14 -42.5 535 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.5 0.5 0
+    }
+    Separator {
+        Normal {
+            vector      [ -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65354e-14 -9.99201e-16 1,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65354e-14 -9.99201e-16 1,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65354e-14 -9.99201e-16 1,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          5.44853e-15 -0.866025 0.5,
+                          5.44853e-15 -0.866025 0.5,
+                          5.44853e-15 -0.866025 0.5,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65354e-14 -9.99201e-16 1,
+                          5.44853e-15 -0.866025 0.5,
+                          5.44853e-15 -0.866025 0.5,
+                          5.44853e-15 -0.866025 0.5,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65354e-14 -9.99201e-16 1,
+                          -1.65354e-14 9.99201e-16 -1,
+                          -1.65354e-14 9.99201e-16 -1,
+                          -1.65354e-14 9.99201e-16 -1,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          3.25529e-15 1 9.99201e-16,
+                          3.25529e-15 1 9.99201e-16,
+                          3.25529e-15 1 9.99201e-16,
+                          -1.65354e-14 9.99201e-16 -1,
+                          -1.65354e-14 9.99201e-16 -1,
+                          -1.65354e-14 9.99201e-16 -1,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65354e-14 -9.99201e-16 1,
+                          3.25529e-15 1 9.99201e-16,
+                          3.25529e-15 1 9.99201e-16,
+                          3.25529e-15 1 9.99201e-16,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          3.25529e-15 1 9.99201e-16,
+                          3.25529e-15 1 9.99201e-16,
+                          3.25529e-15 1 9.99201e-16,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65354e-14 -9.99201e-16 1,
+                          3.25529e-15 1 9.99201e-16,
+                          3.25529e-15 1 9.99201e-16,
+                          3.25529e-15 1 9.99201e-16,
+                          3.25529e-15 1 9.99201e-16,
+                          3.25529e-15 1 9.99201e-16,
+                          3.25529e-15 1 9.99201e-16,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65354e-14 -9.99201e-16 1,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          3.25529e-15 1 9.99201e-16,
+                          3.25529e-15 1 9.99201e-16,
+                          3.25529e-15 1 9.99201e-16,
+                          3.25529e-15 1 9.99201e-16,
+                          3.25529e-15 1 9.99201e-16,
+                          3.25529e-15 1 9.99201e-16,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65354e-14 -9.99201e-16 1,
+                          3.25529e-15 1 9.99201e-16,
+                          3.25529e-15 1 9.99201e-16,
+                          3.25529e-15 1 9.99201e-16,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65354e-14 -9.99201e-16 1,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -118 -81 381,
+                          -118 -119 361,
+                          -118 -119 466,
+                          -115 -119 466,
+                          -118 -119 466,
+                          -118 -119 361,
+                          -118 -81 428,
+                          -118 -81 381,
+                          -118 -119 466,
+                          -118 -109 466,
+                          -118 -81 428,
+                          -118 -119 466,
+                          -115 -109 466,
+                          -118 -109 466,
+                          -118 -119 466,
+                          -115 -109 466,
+                          -118 -119 466,
+                          -115 -119 466,
+                          -118 -71 158,
+                          -118 -119 357,
+                          -118 -119 361,
+                          -115 -119 361,
+                          -118 -119 361,
+                          -118 -119 357,
+                          -118 -81 381,
+                          -118 -71 158,
+                          -118 -119 361,
+                          -115 -119 361,
+                          -115 -119 466,
+                          -118 -119 361,
+                          -118 -71 158,
+                          -118 -130 357,
+                          -118 -119 357,
+                          -115 -119 357,
+                          -118 -119 357,
+                          -118 -130 357,
+                          -115 -119 361,
+                          -118 -119 357,
+                          -115 -119 357,
+                          -118 -71 158,
+                          -118 -130 320.282,
+                          -118 -130 357,
+                          -115 -130 357,
+                          -118 -130 357,
+                          -118 -130 320.282,
+                          -115 -119 357,
+                          -118 -130 357,
+                          -115 -130 357,
+                          -118 -71 158,
+                          -118 -170 251,
+                          -118 -130 320.282,
+                          -115 -130 320.282,
+                          -118 -130 320.282,
+                          -118 -170 251,
+                          -115 -130 357,
+                          -118 -130 320.282,
+                          -115 -130 320.282,
+                          -118 -71 158,
+                          -118 -175 251,
+                          -118 -170 251,
+                          -115 -170 251,
+                          -118 -170 251,
+                          -118 -175 251,
+                          -115 -130 320.282,
+                          -118 -170 251,
+                          -115 -170 251,
+                          -118 -61 131,
+                          -118 -175 131,
+                          -118 -175 251,
+                          -115 -175 251,
+                          -118 -175 251,
+                          -118 -175 131,
+                          -118 -71 158,
+                          -118 -61 131,
+                          -118 -175 251,
+                          -115 -170 251,
+                          -118 -175 251,
+                          -115 -175 251,
+                          -115 -175 131,
+                          -118 -175 131,
+                          -118 -61 131,
+                          -115 -175 251,
+                          -118 -175 131,
+                          -115 -175 131,
+                          -118 -71 158,
+                          -118 -61 158,
+                          -118 -61 131,
+                          -115 -61 131,
+                          -118 -61 131,
+                          -118 -61 158,
+                          -115 -175 131,
+                          -118 -61 131,
+                          -115 -61 131,
+                          -115 -61 158,
+                          -118 -61 158,
+                          -118 -71 158,
+                          -115 -61 131,
+                          -118 -61 158,
+                          -115 -61 158,
+                          -118 -81 381,
+                          -118 -71 381,
+                          -118 -71 158,
+                          -115 -71 158,
+                          -118 -71 158,
+                          -118 -71 381,
+                          -115 -61 158,
+                          -118 -71 158,
+                          -115 -71 158,
+                          -115 -71 381,
+                          -118 -71 381,
+                          -118 -81 381,
+                          -115 -71 158,
+                          -118 -71 381,
+                          -115 -71 381,
+                          -115 -81 381,
+                          -118 -81 381,
+                          -118 -81 428,
+                          -115 -71 381,
+                          -118 -81 381,
+                          -115 -81 381,
+                          -118 -109 466,
+                          -118 -81 466,
+                          -118 -81 428,
+                          -115 -81 428,
+                          -118 -81 428,
+                          -118 -81 466,
+                          -115 -81 381,
+                          -118 -81 428,
+                          -115 -81 428,
+                          -115 -81 466,
+                          -118 -81 466,
+                          -118 -109 466,
+                          -115 -81 428,
+                          -118 -81 466,
+                          -115 -81 466,
+                          -115 -81 466,
+                          -118 -109 466,
+                          -115 -109 466,
+                          -115 -119 361,
+                          -115 -109 466,
+                          -115 -119 466,
+                          -115 -119 361,
+                          -115 -81 466,
+                          -115 -109 466,
+                          -115 -119 361,
+                          -115 -81 428,
+                          -115 -81 466,
+                          -115 -119 361,
+                          -115 -81 381,
+                          -115 -81 428,
+                          -115 -119 361,
+                          -115 -71 381,
+                          -115 -81 381,
+                          -115 -170 251,
+                          -115 -71 158,
+                          -115 -71 381,
+                          -115 -130 320.282,
+                          -115 -170 251,
+                          -115 -71 381,
+                          -115 -119 357,
+                          -115 -130 320.282,
+                          -115 -71 381,
+                          -115 -119 361,
+                          -115 -119 357,
+                          -115 -71 381,
+                          -115 -175 131,
+                          -115 -61 158,
+                          -115 -71 158,
+                          -115 -170 251,
+                          -115 -175 131,
+                          -115 -71 158,
+                          -115 -175 131,
+                          -115 -61 131,
+                          -115 -61 158,
+                          -115 -170 251,
+                          -115 -175 251,
+                          -115 -175 131,
+                          -115 -119 357,
+                          -115 -130 357,
+                          -115 -130 320.282 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.7 0.336 0
+    }
+    Separator {
+        Normal {
+            vector      [ 1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -1.87343e-16 0.866025 0.5,
+                          -1.87343e-16 0.866025 0.5,
+                          -1.87343e-16 0.866025 0.5,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -1.87343e-16 0.866025 0.5,
+                          -1.87343e-16 0.866025 0.5,
+                          -1.87343e-16 0.866025 0.5,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -115 71 281,
+                          -115 54 281,
+                          -115 54 131,
+                          -118 54 131,
+                          -115 54 131,
+                          -115 54 281,
+                          -115 170 251,
+                          -115 71 281,
+                          -115 54 131,
+                          -115 175 251,
+                          -115 170 251,
+                          -115 54 131,
+                          -115 175 131,
+                          -115 175 251,
+                          -115 54 131,
+                          -118 175 131,
+                          -115 175 131,
+                          -115 54 131,
+                          -118 175 131,
+                          -115 54 131,
+                          -118 54 131,
+                          -118 54 281,
+                          -115 54 281,
+                          -115 71 281,
+                          -118 54 131,
+                          -115 54 281,
+                          -118 54 281,
+                          -115 81 381,
+                          -115 71 381,
+                          -115 71 281,
+                          -118 71 281,
+                          -115 71 281,
+                          -115 71 381,
+                          -115 119 361,
+                          -115 81 381,
+                          -115 71 281,
+                          -115 119 357,
+                          -115 119 361,
+                          -115 71 281,
+                          -115 130 357,
+                          -115 119 357,
+                          -115 71 281,
+                          -115 130 320.282,
+                          -115 130 357,
+                          -115 71 281,
+                          -115 170 251,
+                          -115 130 320.282,
+                          -115 71 281,
+                          -118 54 281,
+                          -115 71 281,
+                          -118 71 281,
+                          -118 71 381,
+                          -115 71 381,
+                          -115 81 381,
+                          -118 71 381,
+                          -118 71 281,
+                          -115 71 381,
+                          -115 119 466,
+                          -115 81 428,
+                          -115 81 381,
+                          -118 81 381,
+                          -115 81 381,
+                          -115 81 428,
+                          -115 119 361,
+                          -115 119 466,
+                          -115 81 381,
+                          -118 71 381,
+                          -115 81 381,
+                          -118 81 381,
+                          -115 109 466,
+                          -115 81 466,
+                          -115 81 428,
+                          -118 81 428,
+                          -115 81 428,
+                          -115 81 466,
+                          -115 119 466,
+                          -115 109 466,
+                          -115 81 428,
+                          -118 81 381,
+                          -115 81 428,
+                          -118 81 428,
+                          -118 81 466,
+                          -115 81 466,
+                          -115 109 466,
+                          -118 81 428,
+                          -115 81 466,
+                          -118 81 466,
+                          -118 109 466,
+                          -115 109 466,
+                          -115 119 466,
+                          -118 81 466,
+                          -115 109 466,
+                          -118 109 466,
+                          -118 119 466,
+                          -115 119 466,
+                          -115 119 361,
+                          -118 109 466,
+                          -115 119 466,
+                          -118 119 466,
+                          -118 119 361,
+                          -115 119 361,
+                          -115 119 357,
+                          -118 119 466,
+                          -115 119 361,
+                          -118 119 361,
+                          -118 119 357,
+                          -115 119 357,
+                          -115 130 357,
+                          -118 119 361,
+                          -115 119 357,
+                          -118 119 357,
+                          -118 130 357,
+                          -115 130 357,
+                          -115 130 320.282,
+                          -118 119 357,
+                          -115 130 357,
+                          -118 130 357,
+                          -118 130 320.282,
+                          -115 130 320.282,
+                          -115 170 251,
+                          -118 130 357,
+                          -115 130 320.282,
+                          -118 130 320.282,
+                          -118 170 251,
+                          -115 170 251,
+                          -115 175 251,
+                          -118 130 320.282,
+                          -115 170 251,
+                          -118 170 251,
+                          -118 175 251,
+                          -115 175 251,
+                          -115 175 131,
+                          -118 170 251,
+                          -115 175 251,
+                          -118 175 251,
+                          -118 175 251,
+                          -115 175 131,
+                          -118 175 131,
+                          -118 170 251,
+                          -118 54 281,
+                          -118 71 281,
+                          -118 130 320.282,
+                          -118 170 251,
+                          -118 71 281,
+                          -118 71 381,
+                          -118 130 320.282,
+                          -118 71 281,
+                          -118 175 131,
+                          -118 54 131,
+                          -118 54 281,
+                          -118 170 251,
+                          -118 175 131,
+                          -118 54 281,
+                          -118 170 251,
+                          -118 175 251,
+                          -118 175 131,
+                          -118 119 357,
+                          -118 130 357,
+                          -118 130 320.282,
+                          -118 71 381,
+                          -118 119 357,
+                          -118 130 320.282,
+                          -118 71 381,
+                          -118 119 361,
+                          -118 119 357,
+                          -118 109 466,
+                          -118 119 466,
+                          -118 119 361,
+                          -118 81 466,
+                          -118 109 466,
+                          -118 119 361,
+                          -118 81 428,
+                          -118 81 466,
+                          -118 119 361,
+                          -118 81 381,
+                          -118 81 428,
+                          -118 119 361,
+                          -118 71 381,
+                          -118 81 381,
+                          -118 119 361 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    1 1 1
+    }
+    Separator {
+        Normal {
+            vector      [ -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 14 42.5 535,
+                          14 -42.5 535,
+                          -1 -42.5 535,
+                          -1 -42.5 540,
+                          -1 -42.5 535,
+                          14 -42.5 535,
+                          -1 42.5 535,
+                          14 42.5 535,
+                          -1 -42.5 535,
+                          -31 -42.5 535,
+                          -1 42.5 535,
+                          -1 -42.5 535,
+                          -31 -42.5 540,
+                          -31 -42.5 535,
+                          -1 -42.5 535,
+                          -31 -42.5 540,
+                          -1 -42.5 535,
+                          -1 -42.5 540,
+                          14 -42.5 540,
+                          14 -42.5 535,
+                          14 42.5 535,
+                          14 -42.5 540,
+                          -1 -42.5 540,
+                          14 -42.5 535,
+                          14 42.5 540,
+                          14 42.5 535,
+                          -1 42.5 535,
+                          14 -42.5 540,
+                          14 42.5 535,
+                          14 42.5 540,
+                          -31 -42.5 535,
+                          -48 42.5 535,
+                          -1 42.5 535,
+                          -1 42.5 540,
+                          -1 42.5 535,
+                          -48 42.5 535,
+                          14 42.5 540,
+                          -1 42.5 535,
+                          -1 42.5 540,
+                          -84 -42.5 535,
+                          -84 42.5 535,
+                          -48 42.5 535,
+                          -48 42.5 540,
+                          -48 42.5 535,
+                          -84 42.5 535,
+                          -31 -42.5 535,
+                          -84 -42.5 535,
+                          -48 42.5 535,
+                          -1 42.5 540,
+                          -48 42.5 535,
+                          -48 42.5 540,
+                          -84 42.5 540,
+                          -84 42.5 535,
+                          -84 -42.5 535,
+                          -48 42.5 540,
+                          -84 42.5 535,
+                          -84 42.5 540,
+                          -84 -42.5 540,
+                          -84 -42.5 535,
+                          -31 -42.5 535,
+                          -84 42.5 540,
+                          -84 -42.5 535,
+                          -84 -42.5 540,
+                          -84 -42.5 540,
+                          -31 -42.5 535,
+                          -31 -42.5 540,
+                          -48 42.5 540,
+                          -31 -42.5 540,
+                          -1 -42.5 540,
+                          -1 42.5 540,
+                          -48 42.5 540,
+                          -1 -42.5 540,
+                          14 -42.5 540,
+                          -1 42.5 540,
+                          -1 -42.5 540,
+                          -84 42.5 540,
+                          -84 -42.5 540,
+                          -31 -42.5 540,
+                          -48 42.5 540,
+                          -84 42.5 540,
+                          -31 -42.5 540,
+                          14 -42.5 540,
+                          14 42.5 540,
+                          -1 42.5 540 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    1 0.48 0
+    }
+    Separator {
+        Normal {
+            vector      [ 0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1.53205e-16 0.708217 -0.705995,
+                          -1.9059e-16 0.881032 -0.473056,
+                          -1.19578e-16 0.552771 -0.833333,
+                          -1.69902e-19 0.000785398 -1,
+                          -1.19578e-16 0.552771 -0.833333,
+                          0 4.05736e-16 -1,
+                          -1.69902e-19 0.000785398 -1,
+                          -1.53205e-16 0.708217 -0.705995,
+                          -1.19578e-16 0.552771 -0.833333,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1.52965e-16 -0.707107 -0.707107,
+                          1.19578e-16 -0.552771 -0.833333,
+                          1.9059e-16 -0.881032 -0.473056,
+                          -1.69902e-19 0.000785398 -1,
+                          0 4.05736e-16 -1,
+                          1.19578e-16 -0.552771 -0.833333,
+                          1.52965e-16 -0.707107 -0.707107,
+                          -1.69902e-19 0.000785398 -1,
+                          1.19578e-16 -0.552771 -0.833333,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          -1.52965e-16 0.707107 0.707107,
+                          -1.19578e-16 0.552771 0.833333,
+                          -1.9059e-16 0.881032 0.473056,
+                          1.69902e-19 -0.000785398 1,
+                          0 -6.12303e-17 1,
+                          -1.19578e-16 0.552771 0.833333,
+                          -1.52965e-16 0.707107 0.707107,
+                          1.69902e-19 -0.000785398 1,
+                          -1.19578e-16 0.552771 0.833333,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          1.53205e-16 -0.708217 0.705995,
+                          1.9059e-16 -0.881032 0.473056,
+                          1.19578e-16 -0.552771 0.833333,
+                          1.69902e-19 -0.000785398 1,
+                          1.19578e-16 -0.552771 0.833333,
+                          0 -6.12303e-17 1,
+                          1.69902e-19 -0.000785398 1,
+                          1.53205e-16 -0.708217 0.705995,
+                          1.19578e-16 -0.552771 0.833333,
+                          1.52965e-16 -0.707107 -0.707107,
+                          1.9059e-16 -0.881032 -0.473056,
+                          2.16325e-16 -1 -4.66966e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          1.9059e-16 -0.881032 0.473056,
+                          1.52965e-16 -0.707107 -0.707107,
+                          2.16325e-16 -1 -4.66966e-16,
+                          2.16325e-16 -1 -4.66966e-16,
+                          1.53205e-16 -0.708217 0.705995,
+                          2.16325e-16 -1 -2.22045e-16,
+                          1.9059e-16 -0.881032 0.473056,
+                          -1.52965e-16 0.707107 0.707107,
+                          -1.9059e-16 0.881032 0.473056,
+                          -2.16325e-16 1 3.44505e-16,
+                          -2.16325e-16 1 3.44505e-16,
+                          -2.16325e-16 1 3.44505e-16,
+                          -1.9059e-16 0.881032 -0.473056,
+                          -2.16325e-16 1 3.44505e-16,
+                          -1.52965e-16 0.707107 0.707107,
+                          -2.16325e-16 1 3.44505e-16,
+                          -1.53205e-16 0.708217 -0.705995,
+                          -2.16325e-16 1 3.44505e-16,
+                          -1.9059e-16 0.881032 -0.473056,
+                          0.271023 -0.654307 0.705995,
+                          3.38786e-16 -1 -9.9584e-17,
+                          2.39934e-16 -0.708217 0.705995,
+                          0.258819 -0.965926 -3.36939e-16,
+                          2.39558e-16 -0.707107 -0.707107,
+                          3.38786e-16 -1 -3.44505e-16,
+                          0.271023 -0.654307 0.705995,
+                          0.258819 -0.965926 -9.2018e-17,
+                          3.38786e-16 -1 -9.9584e-17,
+                          0.000300559 -0.000725613 1,
+                          2.39934e-16 -0.708217 0.705995,
+                          2.66082e-19 -0.000785398 1,
+                          0.000300559 -0.000725613 1,
+                          0.271023 -0.654307 0.705995,
+                          2.39934e-16 -0.708217 0.705995,
+                          -0.270598 0.653282 0.707107,
+                          2.66082e-19 -0.000785398 1,
+                          -2.39558e-16 0.707107 0.707107,
+                          -0.270598 0.653282 0.707107,
+                          0.000300559 -0.000725613 1,
+                          2.66082e-19 -0.000785398 1,
+                          -0.382683 0.92388 3.16165e-16,
+                          -2.39558e-16 0.707107 0.707107,
+                          -3.38786e-16 1 3.33067e-16,
+                          -0.382683 0.92388 3.16165e-16,
+                          -0.270598 0.653282 0.707107,
+                          -2.39558e-16 0.707107 0.707107,
+                          -0.271023 0.654307 -0.705995,
+                          -3.38786e-16 1 2.22045e-16,
+                          -2.39934e-16 0.708217 -0.705995,
+                          -0.271023 0.654307 -0.705995,
+                          -0.382683 0.92388 2.05142e-16,
+                          -3.38786e-16 1 2.22045e-16,
+                          -0.000300559 0.000725613 -1,
+                          -2.39934e-16 0.708217 -0.705995,
+                          -2.66082e-19 0.000785398 -1,
+                          -0.000300559 0.000725613 -1,
+                          -0.271023 0.654307 -0.705995,
+                          -2.39934e-16 0.708217 -0.705995,
+                          0.270598 -0.653282 -0.707107,
+                          -2.66082e-19 0.000785398 -1,
+                          2.39558e-16 -0.707107 -0.707107,
+                          0.270598 -0.653282 -0.707107,
+                          -0.000300559 0.000725613 -1,
+                          -2.66082e-19 0.000785398 -1,
+                          0.270598 -0.653282 -0.707107,
+                          2.39558e-16 -0.707107 -0.707107,
+                          0.258819 -0.965926 -3.36939e-16,
+                          1 9.38648e-17 0,
+                          1 9.38648e-17 0,
+                          1 9.38648e-17 0,
+                          0.270598 0.653282 -0.707107,
+                          -2.16325e-16 1 9.9584e-17,
+                          -1.52965e-16 0.707107 -0.707107,
+                          1 9.38648e-17 0,
+                          1 9.38648e-17 0,
+                          1 9.38648e-17 0,
+                          1 9.38648e-17 0,
+                          1 9.38648e-17 0,
+                          1 9.38648e-17 0,
+                          0.258819 0.965926 3.36939e-16,
+                          -1.53205e-16 0.708217 0.705995,
+                          -2.16325e-16 1 3.44505e-16,
+                          0.270598 0.653282 -0.707107,
+                          0.258819 0.965926 9.2018e-17,
+                          -2.16325e-16 1 9.9584e-17,
+                          1 9.38648e-17 0,
+                          1 9.38648e-17 0,
+                          1 9.38648e-17 0,
+                          -0.000300559 -0.000725613 -1,
+                          -1.52965e-16 0.707107 -0.707107,
+                          1.69902e-19 -0.000785398 -1,
+                          0.270598 0.653282 -0.707107,
+                          -1.52965e-16 0.707107 -0.707107,
+                          -0.000300559 -0.000725613 -1,
+                          -0.271023 -0.654307 -0.705995,
+                          1.69902e-19 -0.000785398 -1,
+                          1.53205e-16 -0.708217 -0.705995,
+                          -0.000300559 -0.000725613 -1,
+                          1.69902e-19 -0.000785398 -1,
+                          -0.271023 -0.654307 -0.705995,
+                          -0.382683 -0.92388 -2.05142e-16,
+                          1.53205e-16 -0.708217 -0.705995,
+                          2.16325e-16 -1 -2.22045e-16,
+                          -0.271023 -0.654307 -0.705995,
+                          1.53205e-16 -0.708217 -0.705995,
+                          -0.382683 -0.92388 -2.05142e-16,
+                          1 9.38648e-17 0,
+                          1 9.38648e-17 0,
+                          1 9.38648e-17 0,
+                          -0.270598 -0.653282 0.707107,
+                          2.16325e-16 -1 -1.11022e-16,
+                          1.52965e-16 -0.707107 0.707107,
+                          -0.382683 -0.92388 -9.41202e-17,
+                          2.16325e-16 -1 -1.11022e-16,
+                          -0.270598 -0.653282 0.707107,
+                          1 9.38648e-17 0,
+                          1 9.38648e-17 0,
+                          1 9.38648e-17 0,
+                          0.000300559 0.000725613 1,
+                          1.52965e-16 -0.707107 0.707107,
+                          -1.69902e-19 0.000785398 1,
+                          -0.270598 -0.653282 0.707107,
+                          1.52965e-16 -0.707107 0.707107,
+                          0.000300559 0.000725613 1,
+                          0.271023 0.654307 0.705995,
+                          -1.69902e-19 0.000785398 1,
+                          -1.53205e-16 0.708217 0.705995,
+                          0.000300559 0.000725613 1,
+                          -1.69902e-19 0.000785398 1,
+                          0.271023 0.654307 0.705995,
+                          0.271023 0.654307 0.705995,
+                          -1.53205e-16 0.708217 0.705995,
+                          0.258819 0.965926 3.36939e-16,
+                          0.271023 -0.654307 0.705995,
+                          0.5 -0.866025 -6.98356e-17,
+                          0.258819 -0.965926 -9.2018e-17,
+                          0.270598 -0.653282 -0.707107,
+                          0.258819 -0.965926 -3.36939e-16,
+                          0.5 -0.866025 -3.14757e-16,
+                          0.500785 -0.500785 0.705995,
+                          0.707107 -0.707107 -3.45486e-17,
+                          0.5 -0.866025 -6.98356e-17,
+                          0.270598 -0.653282 -0.707107,
+                          0.5 -0.866025 -3.14757e-16,
+                          0.707107 -0.707107 -2.7947e-16,
+                          0.271023 -0.654307 0.705995,
+                          0.500785 -0.500785 0.705995,
+                          0.5 -0.866025 -6.98356e-17,
+                          0.654307 -0.271023 0.705995,
+                          0.866025 -0.5 1.14383e-17,
+                          0.707107 -0.707107 -3.45486e-17,
+                          0.5 -0.5 -0.707107,
+                          0.707107 -0.707107 -2.7947e-16,
+                          0.866025 -0.5 -2.33483e-16,
+                          0.500785 -0.500785 0.705995,
+                          0.654307 -0.271023 0.705995,
+                          0.707107 -0.707107 -3.45486e-17,
+                          0.270598 -0.653282 -0.707107,
+                          0.707107 -0.707107 -2.7947e-16,
+                          0.5 -0.5 -0.707107,
+                          0.654307 -0.271023 0.705995,
+                          0.965926 -0.258819 6.49913e-17,
+                          0.866025 -0.5 1.14383e-17,
+                          0.653282 -0.270598 -0.707107,
+                          0.866025 -0.5 -2.33483e-16,
+                          0.965926 -0.258819 -1.7993e-16,
+                          0.5 -0.5 -0.707107,
+                          0.866025 -0.5 -2.33483e-16,
+                          0.653282 -0.270598 -0.707107,
+                          0.708217 3.98072e-17 0.705995,
+                          1 2.77556e-16 1.22461e-16,
+                          0.965926 -0.258819 6.49913e-17,
+                          0.653282 -0.270598 -0.707107,
+                          0.965926 -0.258819 -1.7993e-16,
+                          1 2.77556e-16 -1.22461e-16,
+                          0.654307 -0.271023 0.705995,
+                          0.708217 3.98072e-17 0.705995,
+                          0.965926 -0.258819 6.49913e-17,
+                          0.654307 0.271023 0.705995,
+                          0.965926 0.258819 1.7993e-16,
+                          1 2.77556e-16 1.22461e-16,
+                          0.707107 3.53271e-16 -0.707107,
+                          1 2.77556e-16 -1.22461e-16,
+                          0.965926 0.258819 -6.49913e-17,
+                          0.708217 3.98072e-17 0.705995,
+                          0.654307 0.271023 0.705995,
+                          1 2.77556e-16 1.22461e-16,
+                          0.653282 -0.270598 -0.707107,
+                          1 2.77556e-16 -1.22461e-16,
+                          0.707107 3.53271e-16 -0.707107,
+                          0.654307 0.271023 0.705995,
+                          0.866025 0.5 2.33483e-16,
+                          0.965926 0.258819 1.7993e-16,
+                          0.653282 0.270598 -0.707107,
+                          0.965926 0.258819 -6.49913e-17,
+                          0.866025 0.5 -1.14383e-17,
+                          0.707107 3.53271e-16 -0.707107,
+                          0.965926 0.258819 -6.49913e-17,
+                          0.653282 0.270598 -0.707107,
+                          0.500785 0.500785 0.705995,
+                          0.707107 0.707107 2.7947e-16,
+                          0.866025 0.5 2.33483e-16,
+                          0.653282 0.270598 -0.707107,
+                          0.866025 0.5 -1.14383e-17,
+                          0.707107 0.707107 3.45486e-17,
+                          0.654307 0.271023 0.705995,
+                          0.500785 0.500785 0.705995,
+                          0.866025 0.5 2.33483e-16,
+                          0.271023 0.654307 0.705995,
+                          0.5 0.866025 7.58846e-16,
+                          0.707107 0.707107 2.7947e-16,
+                          0.5 0.5 -0.707107,
+                          0.707107 0.707107 3.45486e-17,
+                          0.5 0.866025 -3.74254e-16,
+                          0.500785 0.500785 0.705995,
+                          0.271023 0.654307 0.705995,
+                          0.707107 0.707107 2.7947e-16,
+                          0.653282 0.270598 -0.707107,
+                          0.707107 0.707107 3.45486e-17,
+                          0.5 0.5 -0.707107,
+                          0.271023 0.654307 0.705995,
+                          0.258819 0.965926 3.36939e-16,
+                          0.5 0.866025 7.58846e-16,
+                          0.270598 0.653282 -0.707107,
+                          0.5 0.866025 -3.74254e-16,
+                          0.258819 0.965926 9.2018e-17,
+                          0.5 0.5 -0.707107,
+                          0.5 0.866025 -3.74254e-16,
+                          0.270598 0.653282 -0.707107,
+                          0.000300559 0.000725613 1,
+                          0.271023 0.654307 0.705995,
+                          0.500785 0.500785 0.705995,
+                          0.00055536 0.00055536 1,
+                          0.500785 0.500785 0.705995,
+                          0.654307 0.271023 0.705995,
+                          0.00055536 0.00055536 1,
+                          0.000300559 0.000725613 1,
+                          0.500785 0.500785 0.705995,
+                          0.000725613 0.000300559 1,
+                          0.654307 0.271023 0.705995,
+                          0.708217 3.98072e-17 0.705995,
+                          0.000725613 0.000300559 1,
+                          0.00055536 0.00055536 1,
+                          0.654307 0.271023 0.705995,
+                          0.000785398 -2.21827e-16 1,
+                          0.708217 3.98072e-17 0.705995,
+                          0.654307 -0.271023 0.705995,
+                          0.000785398 -2.21827e-16 1,
+                          0.000725613 0.000300559 1,
+                          0.708217 3.98072e-17 0.705995,
+                          0.000725613 -0.000300559 1,
+                          0.654307 -0.271023 0.705995,
+                          0.500785 -0.500785 0.705995,
+                          0.000725613 -0.000300559 1,
+                          0.000785398 -2.21827e-16 1,
+                          0.654307 -0.271023 0.705995,
+                          0.00055536 -0.00055536 1,
+                          0.500785 -0.500785 0.705995,
+                          0.271023 -0.654307 0.705995,
+                          0.00055536 -0.00055536 1,
+                          0.000725613 -0.000300559 1,
+                          0.500785 -0.500785 0.705995,
+                          0.000300559 -0.000725613 1,
+                          0.00055536 -0.00055536 1,
+                          0.271023 -0.654307 0.705995,
+                          -0.270598 -0.653282 0.707107,
+                          0.000300559 0.000725613 1,
+                          0.00055536 0.00055536 1,
+                          -0.5 -0.5 0.707107,
+                          0.00055536 0.00055536 1,
+                          0.000725613 0.000300559 1,
+                          -0.5 -0.5 0.707107,
+                          -0.270598 -0.653282 0.707107,
+                          0.00055536 0.00055536 1,
+                          -0.653282 -0.270598 0.707107,
+                          0.000725613 0.000300559 1,
+                          0.000785398 -2.21827e-16 1,
+                          -0.653282 -0.270598 0.707107,
+                          -0.5 -0.5 0.707107,
+                          0.000725613 0.000300559 1,
+                          -0.707107 -3.53271e-16 0.707107,
+                          0.000785398 -2.21827e-16 1,
+                          0.000725613 -0.000300559 1,
+                          -0.707107 -3.53271e-16 0.707107,
+                          -0.653282 -0.270598 0.707107,
+                          0.000785398 -2.21827e-16 1,
+                          -0.653282 0.270598 0.707107,
+                          0.000725613 -0.000300559 1,
+                          0.00055536 -0.00055536 1,
+                          -0.653282 0.270598 0.707107,
+                          -0.707107 -3.53271e-16 0.707107,
+                          0.000725613 -0.000300559 1,
+                          -0.5 0.5 0.707107,
+                          0.00055536 -0.00055536 1,
+                          0.000300559 -0.000725613 1,
+                          -0.5 0.5 0.707107,
+                          -0.653282 0.270598 0.707107,
+                          0.00055536 -0.00055536 1,
+                          -0.270598 0.653282 0.707107,
+                          -0.5 0.5 0.707107,
+                          0.000300559 -0.000725613 1,
+                          -0.382683 -0.92388 -9.41202e-17,
+                          -0.270598 -0.653282 0.707107,
+                          -0.5 -0.5 0.707107,
+                          -0.707107 -0.707107 -4.59869e-17,
+                          -0.5 -0.5 0.707107,
+                          -0.653282 -0.270598 0.707107,
+                          -0.707107 -0.707107 -4.59869e-17,
+                          -0.382683 -0.92388 -9.41202e-17,
+                          -0.5 -0.5 0.707107,
+                          -0.92388 -0.382683 2.60495e-17,
+                          -0.653282 -0.270598 0.707107,
+                          -0.707107 -3.53271e-16 0.707107,
+                          -0.92388 -0.382683 2.60495e-17,
+                          -0.707107 -0.707107 -4.59869e-17,
+                          -0.653282 -0.270598 0.707107,
+                          -1 -2.77556e-16 1.11022e-16,
+                          -0.707107 -3.53271e-16 0.707107,
+                          -0.653282 0.270598 0.707107,
+                          -1 -2.77556e-16 1.11022e-16,
+                          -0.92388 -0.382683 2.60495e-17,
+                          -0.707107 -3.53271e-16 0.707107,
+                          -0.92388 0.382683 1.95995e-16,
+                          -0.653282 0.270598 0.707107,
+                          -0.5 0.5 0.707107,
+                          -0.92388 0.382683 1.95995e-16,
+                          -1 -2.77556e-16 1.11022e-16,
+                          -0.653282 0.270598 0.707107,
+                          -0.707107 0.707107 2.68032e-16,
+                          -0.5 0.5 0.707107,
+                          -0.270598 0.653282 0.707107,
+                          -0.707107 0.707107 2.68032e-16,
+                          -0.92388 0.382683 1.95995e-16,
+                          -0.5 0.5 0.707107,
+                          -0.382683 0.92388 3.16165e-16,
+                          -0.707107 0.707107 2.68032e-16,
+                          -0.270598 0.653282 0.707107,
+                          -0.271023 -0.654307 -0.705995,
+                          -0.382683 -0.92388 -2.05142e-16,
+                          -0.707107 -0.707107 -1.57009e-16,
+                          -0.500785 -0.500785 -0.705995,
+                          -0.707107 -0.707107 -1.57009e-16,
+                          -0.92388 -0.382683 -8.49728e-17,
+                          -0.500785 -0.500785 -0.705995,
+                          -0.271023 -0.654307 -0.705995,
+                          -0.707107 -0.707107 -1.57009e-16,
+                          -0.654307 -0.271023 -0.705995,
+                          -0.92388 -0.382683 -8.49728e-17,
+                          -1 -2.77556e-16 0,
+                          -0.654307 -0.271023 -0.705995,
+                          -0.500785 -0.500785 -0.705995,
+                          -0.92388 -0.382683 -8.49728e-17,
+                          -0.708217 -3.98072e-17 -0.705995,
+                          -1 -2.77556e-16 0,
+                          -0.92388 0.382683 8.49728e-17,
+                          -0.708217 -3.98072e-17 -0.705995,
+                          -0.654307 -0.271023 -0.705995,
+                          -1 -2.77556e-16 0,
+                          -0.654307 0.271023 -0.705995,
+                          -0.92388 0.382683 8.49728e-17,
+                          -0.707107 0.707107 1.57009e-16,
+                          -0.654307 0.271023 -0.705995,
+                          -0.708217 -3.98072e-17 -0.705995,
+                          -0.92388 0.382683 8.49728e-17,
+                          -0.500785 0.500785 -0.705995,
+                          -0.707107 0.707107 1.57009e-16,
+                          -0.382683 0.92388 2.05142e-16,
+                          -0.500785 0.500785 -0.705995,
+                          -0.654307 0.271023 -0.705995,
+                          -0.707107 0.707107 1.57009e-16,
+                          -0.271023 0.654307 -0.705995,
+                          -0.500785 0.500785 -0.705995,
+                          -0.382683 0.92388 2.05142e-16,
+                          -0.000300559 -0.000725613 -1,
+                          -0.271023 -0.654307 -0.705995,
+                          -0.500785 -0.500785 -0.705995,
+                          -0.00055536 -0.00055536 -1,
+                          -0.500785 -0.500785 -0.705995,
+                          -0.654307 -0.271023 -0.705995,
+                          -0.00055536 -0.00055536 -1,
+                          -0.000300559 -0.000725613 -1,
+                          -0.500785 -0.500785 -0.705995,
+                          -0.000725613 -0.000300559 -1,
+                          -0.654307 -0.271023 -0.705995,
+                          -0.708217 -3.98072e-17 -0.705995,
+                          -0.000725613 -0.000300559 -1,
+                          -0.00055536 -0.00055536 -1,
+                          -0.654307 -0.271023 -0.705995,
+                          -0.000785398 2.21827e-16 -1,
+                          -0.708217 -3.98072e-17 -0.705995,
+                          -0.654307 0.271023 -0.705995,
+                          -0.000785398 2.21827e-16 -1,
+                          -0.000725613 -0.000300559 -1,
+                          -0.708217 -3.98072e-17 -0.705995,
+                          -0.000725613 0.000300559 -1,
+                          -0.654307 0.271023 -0.705995,
+                          -0.500785 0.500785 -0.705995,
+                          -0.000725613 0.000300559 -1,
+                          -0.000785398 2.21827e-16 -1,
+                          -0.654307 0.271023 -0.705995,
+                          -0.00055536 0.00055536 -1,
+                          -0.500785 0.500785 -0.705995,
+                          -0.271023 0.654307 -0.705995,
+                          -0.00055536 0.00055536 -1,
+                          -0.000725613 0.000300559 -1,
+                          -0.500785 0.500785 -0.705995,
+                          -0.000300559 0.000725613 -1,
+                          -0.00055536 0.00055536 -1,
+                          -0.271023 0.654307 -0.705995,
+                          0.270598 0.653282 -0.707107,
+                          -0.000300559 -0.000725613 -1,
+                          -0.00055536 -0.00055536 -1,
+                          0.5 0.5 -0.707107,
+                          -0.00055536 -0.00055536 -1,
+                          -0.000725613 -0.000300559 -1,
+                          0.5 0.5 -0.707107,
+                          0.270598 0.653282 -0.707107,
+                          -0.00055536 -0.00055536 -1,
+                          0.653282 0.270598 -0.707107,
+                          -0.000725613 -0.000300559 -1,
+                          -0.000785398 2.21827e-16 -1,
+                          0.653282 0.270598 -0.707107,
+                          0.5 0.5 -0.707107,
+                          -0.000725613 -0.000300559 -1,
+                          0.707107 3.53271e-16 -0.707107,
+                          -0.000785398 2.21827e-16 -1,
+                          -0.000725613 0.000300559 -1,
+                          0.707107 3.53271e-16 -0.707107,
+                          0.653282 0.270598 -0.707107,
+                          -0.000785398 2.21827e-16 -1,
+                          0.653282 -0.270598 -0.707107,
+                          -0.000725613 0.000300559 -1,
+                          -0.00055536 0.00055536 -1,
+                          0.653282 -0.270598 -0.707107,
+                          0.707107 3.53271e-16 -0.707107,
+                          -0.000725613 0.000300559 -1,
+                          0.5 -0.5 -0.707107,
+                          -0.00055536 0.00055536 -1,
+                          -0.000300559 0.000725613 -1,
+                          0.5 -0.5 -0.707107,
+                          0.653282 -0.270598 -0.707107,
+                          -0.00055536 0.00055536 -1,
+                          0.270598 -0.653282 -0.707107,
+                          0.5 -0.5 -0.707107,
+                          -0.000300559 0.000725613 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -98 83 220.5,
+                          -129 111.183 220.5,
+                          -129 117.817 220.5,
+                          -129 114.5 219.5,
+                          -129 117.817 220.5,
+                          -129 111.183 220.5,
+                          -129 146 220.5,
+                          -98 83 220.5,
+                          -129 117.817 220.5,
+                          -129 146 230.5,
+                          -129 146 220.5,
+                          -129 117.817 220.5,
+                          -129 119.786 222.662,
+                          -129 146 230.5,
+                          -129 117.817 220.5,
+                          -157 118.749 221.264,
+                          -129 119.786 222.662,
+                          -129 117.817 220.5,
+                          -157 114.505 219.5,
+                          -129 117.817 220.5,
+                          -129 114.5 219.5,
+                          -157 114.505 219.5,
+                          -157 118.749 221.264,
+                          -129 117.817 220.5,
+                          -115 83 220.5,
+                          -129 83 220.5,
+                          -129 111.183 220.5,
+                          -129 109.214 222.662,
+                          -129 111.183 220.5,
+                          -129 83 220.5,
+                          -98 83 220.5,
+                          -115 83 220.5,
+                          -129 111.183 220.5,
+                          -157 110.257 221.257,
+                          -129 111.183 220.5,
+                          -129 109.214 222.662,
+                          -157 114.505 219.5,
+                          -129 114.5 219.5,
+                          -129 111.183 220.5,
+                          -157 110.257 221.257,
+                          -157 114.505 219.5,
+                          -129 111.183 220.5,
+                          -129 83 230.5,
+                          -129 83 220.5,
+                          -115 83 220.5,
+                          -129 111.183 230.5,
+                          -129 83 220.5,
+                          -129 83 230.5,
+                          -129 109.214 228.338,
+                          -129 83 220.5,
+                          -129 111.183 230.5,
+                          -129 108.5 225.5,
+                          -129 109.214 222.662,
+                          -129 83 220.5,
+                          -129 109.214 228.338,
+                          -129 108.5 225.5,
+                          -129 83 220.5,
+                          -115 83 230.5,
+                          -115 83 220.5,
+                          -98 83 220.5,
+                          -129 83 230.5,
+                          -115 83 220.5,
+                          -115 83 230.5,
+                          -115 146 220.5,
+                          -98 146 220.5,
+                          -98 83 220.5,
+                          -98 83 230.5,
+                          -98 83 220.5,
+                          -98 146 220.5,
+                          -129 146 220.5,
+                          -115 146 220.5,
+                          -98 83 220.5,
+                          -115 83 230.5,
+                          -98 83 220.5,
+                          -98 83 230.5,
+                          -98 146 230.5,
+                          -98 146 220.5,
+                          -115 146 220.5,
+                          -98 83 230.5,
+                          -98 146 220.5,
+                          -98 146 230.5,
+                          -115 146 230.5,
+                          -115 146 220.5,
+                          -129 146 220.5,
+                          -98 146 230.5,
+                          -115 146 220.5,
+                          -115 146 230.5,
+                          -115 146 230.5,
+                          -129 146 220.5,
+                          -129 146 230.5,
+                          -115 146 230.5,
+                          -129 146 230.5,
+                          -129 117.817 230.5,
+                          -129 119.786 228.338,
+                          -129 117.817 230.5,
+                          -129 146 230.5,
+                          -98 146 230.5,
+                          -115 146 230.5,
+                          -129 117.817 230.5,
+                          -129 111.183 230.5,
+                          -98 146 230.5,
+                          -129 117.817 230.5,
+                          -129 114.5 231.5,
+                          -129 111.183 230.5,
+                          -129 117.817 230.5,
+                          -157 118.743 229.743,
+                          -129 117.817 230.5,
+                          -129 119.786 228.338,
+                          -157 114.495 231.5,
+                          -129 114.5 231.5,
+                          -129 117.817 230.5,
+                          -157 118.743 229.743,
+                          -157 114.495 231.5,
+                          -129 117.817 230.5,
+                          -129 120.5 225.5,
+                          -129 119.786 228.338,
+                          -129 146 230.5,
+                          -129 119.786 222.662,
+                          -129 120.5 225.5,
+                          -129 146 230.5,
+                          -115 83 230.5,
+                          -98 83 230.5,
+                          -98 146 230.5,
+                          -129 83 230.5,
+                          -115 83 230.5,
+                          -98 146 230.5,
+                          -129 111.183 230.5,
+                          -129 83 230.5,
+                          -98 146 230.5,
+                          -157 110.251 229.736,
+                          -129 109.214 228.338,
+                          -129 111.183 230.5,
+                          -157 114.495 231.5,
+                          -129 111.183 230.5,
+                          -129 114.5 231.5,
+                          -157 114.495 231.5,
+                          -157 110.251 229.736,
+                          -129 111.183 230.5,
+                          -157 110.257 221.257,
+                          -129 109.214 222.662,
+                          -129 108.5 225.5,
+                          -157 108.5 225.5,
+                          -129 108.5 225.5,
+                          -129 109.214 228.338,
+                          -157 110.257 221.257,
+                          -129 108.5 225.5,
+                          -157 108.5 225.5,
+                          -157 110.251 229.736,
+                          -157 108.5 225.5,
+                          -129 109.214 228.338,
+                          -157 118.743 229.743,
+                          -129 119.786 228.338,
+                          -129 120.5 225.5,
+                          -157 120.5 225.5,
+                          -129 120.5 225.5,
+                          -129 119.786 222.662,
+                          -157 120.5 225.5,
+                          -157 118.743 229.743,
+                          -129 120.5 225.5,
+                          -157 118.749 221.264,
+                          -157 120.5 225.5,
+                          -129 119.786 222.662,
+                          -168.385 107.986 229.736,
+                          -157 108.5 225.5,
+                          -157 110.251 229.736,
+                          -164.247 107.546 225.5,
+                          -157 110.257 221.257,
+                          -157 108.5 225.5,
+                          -168.385 107.986 229.736,
+                          -164.247 107.546 225.5,
+                          -157 108.5 225.5,
+                          -170.009 111.908 231.5,
+                          -157 110.251 229.736,
+                          -157 114.495 231.5,
+                          -170.009 111.908 231.5,
+                          -168.385 107.986 229.736,
+                          -157 110.251 229.736,
+                          -171.635 115.832 229.743,
+                          -157 114.495 231.5,
+                          -157 118.743 229.743,
+                          -171.635 115.832 229.743,
+                          -170.009 111.908 231.5,
+                          -157 114.495 231.5,
+                          -172.307 117.455 225.5,
+                          -157 118.743 229.743,
+                          -157 120.5 225.5,
+                          -172.307 117.455 225.5,
+                          -171.635 115.832 229.743,
+                          -157 118.743 229.743,
+                          -171.637 115.838 221.264,
+                          -157 120.5 225.5,
+                          -157 118.749 221.264,
+                          -171.637 115.838 221.264,
+                          -172.307 117.455 225.5,
+                          -157 120.5 225.5,
+                          -170.013 111.916 219.5,
+                          -157 118.749 221.264,
+                          -157 114.505 219.5,
+                          -170.013 111.916 219.5,
+                          -171.637 115.838 221.264,
+                          -157 118.749 221.264,
+                          -168.388 107.992 221.257,
+                          -157 114.505 219.5,
+                          -157 110.257 221.257,
+                          -168.388 107.992 221.257,
+                          -170.013 111.916 219.5,
+                          -157 114.505 219.5,
+                          -168.388 107.992 221.257,
+                          -157 110.257 221.257,
+                          -164.247 107.546 225.5,
+                          -157 42.2499 221.265,
+                          -157 50.7434 221.258,
+                          -157 52.5 225.5,
+                          -168.388 53.0078 221.257,
+                          -157 52.5 225.5,
+                          -157 50.7434 221.258,
+                          -157 40.5 225.5,
+                          -157 42.2499 221.265,
+                          -157 52.5 225.5,
+                          -157 50.7501 229.735,
+                          -157 40.5 225.5,
+                          -157 52.5 225.5,
+                          -164.247 53.4541 225.5,
+                          -157 50.7501 229.735,
+                          -157 52.5 225.5,
+                          -168.388 53.0078 221.257,
+                          -164.247 53.4541 225.5,
+                          -157 52.5 225.5,
+                          -157 42.2499 221.265,
+                          -157 46.4953 219.5,
+                          -157 50.7434 221.258,
+                          -170.013 49.0837 219.5,
+                          -157 50.7434 221.258,
+                          -157 46.4953 219.5,
+                          -168.388 53.0078 221.257,
+                          -157 50.7434 221.258,
+                          -170.013 49.0837 219.5,
+                          -171.637 45.1623 221.264,
+                          -157 46.4953 219.5,
+                          -157 42.2499 221.265,
+                          -170.013 49.0837 219.5,
+                          -157 46.4953 219.5,
+                          -171.637 45.1623 221.264,
+                          -172.307 43.5448 225.5,
+                          -157 42.2499 221.265,
+                          -157 40.5 225.5,
+                          -171.637 45.1623 221.264,
+                          -157 42.2499 221.265,
+                          -172.307 43.5448 225.5,
+                          -157 50.7501 229.735,
+                          -157 42.2566 229.742,
+                          -157 40.5 225.5,
+                          -171.635 45.1684 229.743,
+                          -157 40.5 225.5,
+                          -157 42.2566 229.742,
+                          -172.307 43.5448 225.5,
+                          -157 40.5 225.5,
+                          -171.635 45.1684 229.743,
+                          -157 50.7501 229.735,
+                          -157 46.5047 231.5,
+                          -157 42.2566 229.742,
+                          -170.009 49.0924 231.5,
+                          -157 42.2566 229.742,
+                          -157 46.5047 231.5,
+                          -171.635 45.1684 229.743,
+                          -157 42.2566 229.742,
+                          -170.009 49.0924 231.5,
+                          -168.385 53.0139 229.736,
+                          -157 46.5047 231.5,
+                          -157 50.7501 229.735,
+                          -170.009 49.0924 231.5,
+                          -157 46.5047 231.5,
+                          -168.385 53.0139 229.736,
+                          -168.385 53.0139 229.736,
+                          -157 50.7501 229.735,
+                          -164.247 53.4541 225.5,
+                          -168.385 107.986 229.736,
+                          -171 104.749 225.5,
+                          -164.247 107.546 225.5,
+                          -168.388 107.992 221.257,
+                          -164.247 107.546 225.5,
+                          -171 104.749 225.5,
+                          -178.037 101.537 229.736,
+                          -176.799 100.299 225.5,
+                          -171 104.749 225.5,
+                          -168.388 107.992 221.257,
+                          -171 104.749 225.5,
+                          -176.799 100.299 225.5,
+                          -168.385 107.986 229.736,
+                          -178.037 101.537 229.736,
+                          -171 104.749 225.5,
+                          -184.486 91.8851 229.736,
+                          -181.249 94.5 225.5,
+                          -176.799 100.299 225.5,
+                          -178.042 101.542 221.257,
+                          -176.799 100.299 225.5,
+                          -181.249 94.5 225.5,
+                          -178.037 101.537 229.736,
+                          -184.486 91.8851 229.736,
+                          -176.799 100.299 225.5,
+                          -168.388 107.992 221.257,
+                          -176.799 100.299 225.5,
+                          -178.042 101.542 221.257,
+                          -184.486 91.8851 229.736,
+                          -184.046 87.7469 225.5,
+                          -181.249 94.5 225.5,
+                          -184.492 91.8876 221.257,
+                          -181.249 94.5 225.5,
+                          -184.046 87.7469 225.5,
+                          -178.042 101.542 221.257,
+                          -181.249 94.5 225.5,
+                          -184.492 91.8876 221.257,
+                          -186.751 80.5 229.736,
+                          -185 80.5 225.5,
+                          -184.046 87.7469 225.5,
+                          -184.492 91.8876 221.257,
+                          -184.046 87.7469 225.5,
+                          -185 80.5 225.5,
+                          -184.486 91.8851 229.736,
+                          -186.751 80.5 229.736,
+                          -184.046 87.7469 225.5,
+                          -184.486 69.1149 229.736,
+                          -184.046 73.2531 225.5,
+                          -185 80.5 225.5,
+                          -186.757 80.5 221.257,
+                          -185 80.5 225.5,
+                          -184.046 73.2531 225.5,
+                          -186.751 80.5 229.736,
+                          -184.486 69.1149 229.736,
+                          -185 80.5 225.5,
+                          -184.492 91.8876 221.257,
+                          -185 80.5 225.5,
+                          -186.757 80.5 221.257,
+                          -184.486 69.1149 229.736,
+                          -181.249 66.5 225.5,
+                          -184.046 73.2531 225.5,
+                          -184.492 69.1124 221.257,
+                          -184.046 73.2531 225.5,
+                          -181.249 66.5 225.5,
+                          -186.757 80.5 221.257,
+                          -184.046 73.2531 225.5,
+                          -184.492 69.1124 221.257,
+                          -178.037 59.4631 229.736,
+                          -176.799 60.701 225.5,
+                          -181.249 66.5 225.5,
+                          -184.492 69.1124 221.257,
+                          -181.249 66.5 225.5,
+                          -176.799 60.701 225.5,
+                          -184.486 69.1149 229.736,
+                          -178.037 59.4631 229.736,
+                          -181.249 66.5 225.5,
+                          -168.385 53.0139 229.736,
+                          -171 56.2513 225.5,
+                          -176.799 60.701 225.5,
+                          -178.042 59.4584 221.257,
+                          -176.799 60.701 225.5,
+                          -171 56.2513 225.5,
+                          -178.037 59.4631 229.736,
+                          -168.385 53.0139 229.736,
+                          -176.799 60.701 225.5,
+                          -184.492 69.1124 221.257,
+                          -176.799 60.701 225.5,
+                          -178.042 59.4584 221.257,
+                          -168.385 53.0139 229.736,
+                          -164.247 53.4541 225.5,
+                          -171 56.2513 225.5,
+                          -168.388 53.0078 221.257,
+                          -171 56.2513 225.5,
+                          -164.247 53.4541 225.5,
+                          -178.042 59.4584 221.257,
+                          -171 56.2513 225.5,
+                          -168.388 53.0078 221.257,
+                          -170.009 49.0924 231.5,
+                          -168.385 53.0139 229.736,
+                          -178.037 59.4631 229.736,
+                          -181.038 56.4617 231.5,
+                          -178.037 59.4631 229.736,
+                          -184.486 69.1149 229.736,
+                          -181.038 56.4617 231.5,
+                          -170.009 49.0924 231.5,
+                          -178.037 59.4631 229.736,
+                          -188.408 67.4906 231.5,
+                          -184.486 69.1149 229.736,
+                          -186.751 80.5 229.736,
+                          -188.408 67.4906 231.5,
+                          -181.038 56.4617 231.5,
+                          -184.486 69.1149 229.736,
+                          -190.995 80.5 231.5,
+                          -186.751 80.5 229.736,
+                          -184.486 91.8851 229.736,
+                          -190.995 80.5 231.5,
+                          -188.408 67.4906 231.5,
+                          -186.751 80.5 229.736,
+                          -188.408 93.5094 231.5,
+                          -184.486 91.8851 229.736,
+                          -178.037 101.537 229.736,
+                          -188.408 93.5094 231.5,
+                          -190.995 80.5 231.5,
+                          -184.486 91.8851 229.736,
+                          -181.038 104.538 231.5,
+                          -178.037 101.537 229.736,
+                          -168.385 107.986 229.736,
+                          -181.038 104.538 231.5,
+                          -188.408 93.5094 231.5,
+                          -178.037 101.537 229.736,
+                          -170.009 111.908 231.5,
+                          -181.038 104.538 231.5,
+                          -168.385 107.986 229.736,
+                          -171.635 45.1684 229.743,
+                          -170.009 49.0924 231.5,
+                          -181.038 56.4617 231.5,
+                          -184.042 53.4584 229.743,
+                          -181.038 56.4617 231.5,
+                          -188.408 67.4906 231.5,
+                          -184.042 53.4584 229.743,
+                          -171.635 45.1684 229.743,
+                          -181.038 56.4617 231.5,
+                          -192.332 65.8652 229.743,
+                          -188.408 67.4906 231.5,
+                          -190.995 80.5 231.5,
+                          -192.332 65.8652 229.743,
+                          -184.042 53.4584 229.743,
+                          -188.408 67.4906 231.5,
+                          -195.243 80.5 229.743,
+                          -190.995 80.5 231.5,
+                          -188.408 93.5094 231.5,
+                          -195.243 80.5 229.743,
+                          -192.332 65.8652 229.743,
+                          -190.995 80.5 231.5,
+                          -192.332 95.1348 229.743,
+                          -188.408 93.5094 231.5,
+                          -181.038 104.538 231.5,
+                          -192.332 95.1348 229.743,
+                          -195.243 80.5 229.743,
+                          -188.408 93.5094 231.5,
+                          -184.042 107.542 229.743,
+                          -181.038 104.538 231.5,
+                          -170.009 111.908 231.5,
+                          -184.042 107.542 229.743,
+                          -192.332 95.1348 229.743,
+                          -181.038 104.538 231.5,
+                          -171.635 115.832 229.743,
+                          -184.042 107.542 229.743,
+                          -170.009 111.908 231.5,
+                          -172.307 43.5448 225.5,
+                          -171.635 45.1684 229.743,
+                          -184.042 53.4584 229.743,
+                          -185.284 52.2157 225.5,
+                          -184.042 53.4584 229.743,
+                          -192.332 65.8652 229.743,
+                          -185.284 52.2157 225.5,
+                          -172.307 43.5448 225.5,
+                          -184.042 53.4584 229.743,
+                          -193.955 65.1927 225.5,
+                          -192.332 65.8652 229.743,
+                          -195.243 80.5 229.743,
+                          -193.955 65.1927 225.5,
+                          -185.284 52.2157 225.5,
+                          -192.332 65.8652 229.743,
+                          -197 80.5 225.5,
+                          -195.243 80.5 229.743,
+                          -192.332 95.1348 229.743,
+                          -197 80.5 225.5,
+                          -193.955 65.1927 225.5,
+                          -195.243 80.5 229.743,
+                          -193.955 95.8073 225.5,
+                          -192.332 95.1348 229.743,
+                          -184.042 107.542 229.743,
+                          -193.955 95.8073 225.5,
+                          -197 80.5 225.5,
+                          -192.332 95.1348 229.743,
+                          -185.284 108.784 225.5,
+                          -184.042 107.542 229.743,
+                          -171.635 115.832 229.743,
+                          -185.284 108.784 225.5,
+                          -193.955 95.8073 225.5,
+                          -184.042 107.542 229.743,
+                          -172.307 117.455 225.5,
+                          -185.284 108.784 225.5,
+                          -171.635 115.832 229.743,
+                          -171.637 45.1623 221.264,
+                          -172.307 43.5448 225.5,
+                          -185.284 52.2157 225.5,
+                          -184.046 53.4537 221.264,
+                          -185.284 52.2157 225.5,
+                          -193.955 65.1927 225.5,
+                          -184.046 53.4537 221.264,
+                          -171.637 45.1623 221.264,
+                          -185.284 52.2157 225.5,
+                          -192.338 65.8626 221.264,
+                          -193.955 65.1927 225.5,
+                          -197 80.5 225.5,
+                          -192.338 65.8626 221.264,
+                          -184.046 53.4537 221.264,
+                          -193.955 65.1927 225.5,
+                          -195.249 80.5 221.264,
+                          -197 80.5 225.5,
+                          -193.955 95.8073 225.5,
+                          -195.249 80.5 221.264,
+                          -192.338 65.8626 221.264,
+                          -197 80.5 225.5,
+                          -192.338 95.1374 221.264,
+                          -193.955 95.8073 225.5,
+                          -185.284 108.784 225.5,
+                          -192.338 95.1374 221.264,
+                          -195.249 80.5 221.264,
+                          -193.955 95.8073 225.5,
+                          -184.046 107.546 221.264,
+                          -185.284 108.784 225.5,
+                          -172.307 117.455 225.5,
+                          -184.046 107.546 221.264,
+                          -192.338 95.1374 221.264,
+                          -185.284 108.784 225.5,
+                          -171.637 115.838 221.264,
+                          -184.046 107.546 221.264,
+                          -172.307 117.455 225.5,
+                          -170.013 49.0837 219.5,
+                          -171.637 45.1623 221.264,
+                          -184.046 53.4537 221.264,
+                          -181.045 56.455 219.5,
+                          -184.046 53.4537 221.264,
+                          -192.338 65.8626 221.264,
+                          -181.045 56.455 219.5,
+                          -170.013 49.0837 219.5,
+                          -184.046 53.4537 221.264,
+                          -188.416 67.487 219.5,
+                          -192.338 65.8626 221.264,
+                          -195.249 80.5 221.264,
+                          -188.416 67.487 219.5,
+                          -181.045 56.455 219.5,
+                          -192.338 65.8626 221.264,
+                          -191.005 80.5 219.5,
+                          -195.249 80.5 221.264,
+                          -192.338 95.1374 221.264,
+                          -191.005 80.5 219.5,
+                          -188.416 67.487 219.5,
+                          -195.249 80.5 221.264,
+                          -188.416 93.513 219.5,
+                          -192.338 95.1374 221.264,
+                          -184.046 107.546 221.264,
+                          -188.416 93.513 219.5,
+                          -191.005 80.5 219.5,
+                          -192.338 95.1374 221.264,
+                          -181.045 104.545 219.5,
+                          -184.046 107.546 221.264,
+                          -171.637 115.838 221.264,
+                          -181.045 104.545 219.5,
+                          -188.416 93.513 219.5,
+                          -184.046 107.546 221.264,
+                          -170.013 111.916 219.5,
+                          -181.045 104.545 219.5,
+                          -171.637 115.838 221.264,
+                          -168.388 53.0078 221.257,
+                          -170.013 49.0837 219.5,
+                          -181.045 56.455 219.5,
+                          -178.042 59.4584 221.257,
+                          -181.045 56.455 219.5,
+                          -188.416 67.487 219.5,
+                          -178.042 59.4584 221.257,
+                          -168.388 53.0078 221.257,
+                          -181.045 56.455 219.5,
+                          -184.492 69.1124 221.257,
+                          -188.416 67.487 219.5,
+                          -191.005 80.5 219.5,
+                          -184.492 69.1124 221.257,
+                          -178.042 59.4584 221.257,
+                          -188.416 67.487 219.5,
+                          -186.757 80.5 221.257,
+                          -191.005 80.5 219.5,
+                          -188.416 93.513 219.5,
+                          -186.757 80.5 221.257,
+                          -184.492 69.1124 221.257,
+                          -191.005 80.5 219.5,
+                          -184.492 91.8876 221.257,
+                          -188.416 93.513 219.5,
+                          -181.045 104.545 219.5,
+                          -184.492 91.8876 221.257,
+                          -186.757 80.5 221.257,
+                          -188.416 93.513 219.5,
+                          -178.042 101.542 221.257,
+                          -181.045 104.545 219.5,
+                          -170.013 111.916 219.5,
+                          -178.042 101.542 221.257,
+                          -184.492 91.8876 221.257,
+                          -181.045 104.545 219.5,
+                          -168.388 107.992 221.257,
+                          -178.042 101.542 221.257,
+                          -170.013 111.916 219.5 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1.53205e-16 0.708217 -0.705995,
+                          -1.9059e-16 0.881032 -0.473056,
+                          -1.19578e-16 0.552771 -0.833333,
+                          -1.69902e-19 0.000785398 -1,
+                          -1.19578e-16 0.552771 -0.833333,
+                          0 4.05736e-16 -1,
+                          -1.69902e-19 0.000785398 -1,
+                          -1.53205e-16 0.708217 -0.705995,
+                          -1.19578e-16 0.552771 -0.833333,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1.52965e-16 -0.707107 -0.707107,
+                          1.19578e-16 -0.552771 -0.833333,
+                          1.9059e-16 -0.881032 -0.473056,
+                          -1.69902e-19 0.000785398 -1,
+                          0 4.05736e-16 -1,
+                          1.19578e-16 -0.552771 -0.833333,
+                          1.52965e-16 -0.707107 -0.707107,
+                          -1.69902e-19 0.000785398 -1,
+                          1.19578e-16 -0.552771 -0.833333,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          -2.16325e-16 1 2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          -1.52965e-16 0.707107 0.707107,
+                          -1.19578e-16 0.552771 0.833333,
+                          -1.9059e-16 0.881032 0.473056,
+                          1.69902e-19 -0.000785398 1,
+                          0 -6.12303e-17 1,
+                          -1.19578e-16 0.552771 0.833333,
+                          -1.52965e-16 0.707107 0.707107,
+                          1.69902e-19 -0.000785398 1,
+                          -1.19578e-16 0.552771 0.833333,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          1.53205e-16 -0.708217 0.705995,
+                          1.9059e-16 -0.881032 0.473056,
+                          1.19578e-16 -0.552771 0.833333,
+                          1.69902e-19 -0.000785398 1,
+                          1.19578e-16 -0.552771 0.833333,
+                          0 -6.12303e-17 1,
+                          1.69902e-19 -0.000785398 1,
+                          1.53205e-16 -0.708217 0.705995,
+                          1.19578e-16 -0.552771 0.833333,
+                          1.52965e-16 -0.707107 -0.707107,
+                          1.9059e-16 -0.881032 -0.473056,
+                          2.16325e-16 -1 -4.66966e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          2.16325e-16 -1 -2.22045e-16,
+                          1.9059e-16 -0.881032 0.473056,
+                          1.52965e-16 -0.707107 -0.707107,
+                          2.16325e-16 -1 -4.66966e-16,
+                          2.16325e-16 -1 -4.66966e-16,
+                          1.53205e-16 -0.708217 0.705995,
+                          2.16325e-16 -1 -2.22045e-16,
+                          1.9059e-16 -0.881032 0.473056,
+                          -1.52965e-16 0.707107 0.707107,
+                          -1.9059e-16 0.881032 0.473056,
+                          -2.16325e-16 1 3.44505e-16,
+                          -2.16325e-16 1 3.44505e-16,
+                          -2.16325e-16 1 3.44505e-16,
+                          -1.9059e-16 0.881032 -0.473056,
+                          -2.16325e-16 1 3.44505e-16,
+                          -1.52965e-16 0.707107 0.707107,
+                          -2.16325e-16 1 3.44505e-16,
+                          -1.53205e-16 0.708217 -0.705995,
+                          -2.16325e-16 1 3.44505e-16,
+                          -1.9059e-16 0.881032 -0.473056,
+                          0.271023 -0.654307 0.705995,
+                          3.38786e-16 -1 -9.9584e-17,
+                          2.39934e-16 -0.708217 0.705995,
+                          0.258819 -0.965926 -3.36939e-16,
+                          2.39558e-16 -0.707107 -0.707107,
+                          3.38786e-16 -1 -3.44505e-16,
+                          0.271023 -0.654307 0.705995,
+                          0.258819 -0.965926 -9.2018e-17,
+                          3.38786e-16 -1 -9.9584e-17,
+                          0.000300559 -0.000725613 1,
+                          2.39934e-16 -0.708217 0.705995,
+                          2.66082e-19 -0.000785398 1,
+                          0.000300559 -0.000725613 1,
+                          0.271023 -0.654307 0.705995,
+                          2.39934e-16 -0.708217 0.705995,
+                          -0.270598 0.653282 0.707107,
+                          2.66082e-19 -0.000785398 1,
+                          -2.39558e-16 0.707107 0.707107,
+                          -0.270598 0.653282 0.707107,
+                          0.000300559 -0.000725613 1,
+                          2.66082e-19 -0.000785398 1,
+                          -0.382683 0.92388 3.16165e-16,
+                          -2.39558e-16 0.707107 0.707107,
+                          -3.38786e-16 1 3.33067e-16,
+                          -0.382683 0.92388 3.16165e-16,
+                          -0.270598 0.653282 0.707107,
+                          -2.39558e-16 0.707107 0.707107,
+                          -0.271023 0.654307 -0.705995,
+                          -3.38786e-16 1 2.22045e-16,
+                          -2.39934e-16 0.708217 -0.705995,
+                          -0.271023 0.654307 -0.705995,
+                          -0.382683 0.92388 2.05142e-16,
+                          -3.38786e-16 1 2.22045e-16,
+                          -0.000300559 0.000725613 -1,
+                          -2.39934e-16 0.708217 -0.705995,
+                          -2.66082e-19 0.000785398 -1,
+                          -0.000300559 0.000725613 -1,
+                          -0.271023 0.654307 -0.705995,
+                          -2.39934e-16 0.708217 -0.705995,
+                          0.270598 -0.653282 -0.707107,
+                          -2.66082e-19 0.000785398 -1,
+                          2.39558e-16 -0.707107 -0.707107,
+                          0.270598 -0.653282 -0.707107,
+                          -0.000300559 0.000725613 -1,
+                          -2.66082e-19 0.000785398 -1,
+                          0.270598 -0.653282 -0.707107,
+                          2.39558e-16 -0.707107 -0.707107,
+                          0.258819 -0.965926 -3.36939e-16,
+                          1 9.38648e-17 0,
+                          1 9.38648e-17 0,
+                          1 9.38648e-17 0,
+                          0.270598 0.653282 -0.707107,
+                          -2.16325e-16 1 9.9584e-17,
+                          -1.52965e-16 0.707107 -0.707107,
+                          1 9.38648e-17 0,
+                          1 9.38648e-17 0,
+                          1 9.38648e-17 0,
+                          1 9.38648e-17 0,
+                          1 9.38648e-17 0,
+                          1 9.38648e-17 0,
+                          0.258819 0.965926 3.36939e-16,
+                          -1.53205e-16 0.708217 0.705995,
+                          -2.16325e-16 1 3.44505e-16,
+                          0.270598 0.653282 -0.707107,
+                          0.258819 0.965926 9.2018e-17,
+                          -2.16325e-16 1 9.9584e-17,
+                          1 9.38648e-17 0,
+                          1 9.38648e-17 0,
+                          1 9.38648e-17 0,
+                          -0.000300559 -0.000725613 -1,
+                          -1.52965e-16 0.707107 -0.707107,
+                          1.69902e-19 -0.000785398 -1,
+                          0.270598 0.653282 -0.707107,
+                          -1.52965e-16 0.707107 -0.707107,
+                          -0.000300559 -0.000725613 -1,
+                          -0.271023 -0.654307 -0.705995,
+                          1.69902e-19 -0.000785398 -1,
+                          1.53205e-16 -0.708217 -0.705995,
+                          -0.000300559 -0.000725613 -1,
+                          1.69902e-19 -0.000785398 -1,
+                          -0.271023 -0.654307 -0.705995,
+                          -0.382683 -0.92388 -2.05142e-16,
+                          1.53205e-16 -0.708217 -0.705995,
+                          2.16325e-16 -1 -2.22045e-16,
+                          -0.271023 -0.654307 -0.705995,
+                          1.53205e-16 -0.708217 -0.705995,
+                          -0.382683 -0.92388 -2.05142e-16,
+                          1 9.38648e-17 0,
+                          1 9.38648e-17 0,
+                          1 9.38648e-17 0,
+                          -0.270598 -0.653282 0.707107,
+                          2.16325e-16 -1 -1.11022e-16,
+                          1.52965e-16 -0.707107 0.707107,
+                          -0.382683 -0.92388 -9.41202e-17,
+                          2.16325e-16 -1 -1.11022e-16,
+                          -0.270598 -0.653282 0.707107,
+                          1 9.38648e-17 0,
+                          1 9.38648e-17 0,
+                          1 9.38648e-17 0,
+                          0.000300559 0.000725613 1,
+                          1.52965e-16 -0.707107 0.707107,
+                          -1.69902e-19 0.000785398 1,
+                          -0.270598 -0.653282 0.707107,
+                          1.52965e-16 -0.707107 0.707107,
+                          0.000300559 0.000725613 1,
+                          0.271023 0.654307 0.705995,
+                          -1.69902e-19 0.000785398 1,
+                          -1.53205e-16 0.708217 0.705995,
+                          0.000300559 0.000725613 1,
+                          -1.69902e-19 0.000785398 1,
+                          0.271023 0.654307 0.705995,
+                          0.271023 0.654307 0.705995,
+                          -1.53205e-16 0.708217 0.705995,
+                          0.258819 0.965926 3.36939e-16,
+                          0.271023 -0.654307 0.705995,
+                          0.5 -0.866025 -6.98356e-17,
+                          0.258819 -0.965926 -9.2018e-17,
+                          0.270598 -0.653282 -0.707107,
+                          0.258819 -0.965926 -3.36939e-16,
+                          0.5 -0.866025 -3.14757e-16,
+                          0.500785 -0.500785 0.705995,
+                          0.707107 -0.707107 -3.45486e-17,
+                          0.5 -0.866025 -6.98356e-17,
+                          0.270598 -0.653282 -0.707107,
+                          0.5 -0.866025 -3.14757e-16,
+                          0.707107 -0.707107 -2.7947e-16,
+                          0.271023 -0.654307 0.705995,
+                          0.500785 -0.500785 0.705995,
+                          0.5 -0.866025 -6.98356e-17,
+                          0.654307 -0.271023 0.705995,
+                          0.866025 -0.5 1.14383e-17,
+                          0.707107 -0.707107 -3.45486e-17,
+                          0.5 -0.5 -0.707107,
+                          0.707107 -0.707107 -2.7947e-16,
+                          0.866025 -0.5 -2.33483e-16,
+                          0.500785 -0.500785 0.705995,
+                          0.654307 -0.271023 0.705995,
+                          0.707107 -0.707107 -3.45486e-17,
+                          0.270598 -0.653282 -0.707107,
+                          0.707107 -0.707107 -2.7947e-16,
+                          0.5 -0.5 -0.707107,
+                          0.654307 -0.271023 0.705995,
+                          0.965926 -0.258819 6.49913e-17,
+                          0.866025 -0.5 1.14383e-17,
+                          0.653282 -0.270598 -0.707107,
+                          0.866025 -0.5 -2.33483e-16,
+                          0.965926 -0.258819 -1.7993e-16,
+                          0.5 -0.5 -0.707107,
+                          0.866025 -0.5 -2.33483e-16,
+                          0.653282 -0.270598 -0.707107,
+                          0.708217 3.98072e-17 0.705995,
+                          1 2.77556e-16 1.22461e-16,
+                          0.965926 -0.258819 6.49913e-17,
+                          0.653282 -0.270598 -0.707107,
+                          0.965926 -0.258819 -1.7993e-16,
+                          1 2.77556e-16 -1.22461e-16,
+                          0.654307 -0.271023 0.705995,
+                          0.708217 3.98072e-17 0.705995,
+                          0.965926 -0.258819 6.49913e-17,
+                          0.654307 0.271023 0.705995,
+                          0.965926 0.258819 1.7993e-16,
+                          1 2.77556e-16 1.22461e-16,
+                          0.707107 3.53271e-16 -0.707107,
+                          1 2.77556e-16 -1.22461e-16,
+                          0.965926 0.258819 -6.49913e-17,
+                          0.708217 3.98072e-17 0.705995,
+                          0.654307 0.271023 0.705995,
+                          1 2.77556e-16 1.22461e-16,
+                          0.653282 -0.270598 -0.707107,
+                          1 2.77556e-16 -1.22461e-16,
+                          0.707107 3.53271e-16 -0.707107,
+                          0.654307 0.271023 0.705995,
+                          0.866025 0.5 2.33483e-16,
+                          0.965926 0.258819 1.7993e-16,
+                          0.653282 0.270598 -0.707107,
+                          0.965926 0.258819 -6.49913e-17,
+                          0.866025 0.5 -1.14383e-17,
+                          0.707107 3.53271e-16 -0.707107,
+                          0.965926 0.258819 -6.49913e-17,
+                          0.653282 0.270598 -0.707107,
+                          0.500785 0.500785 0.705995,
+                          0.707107 0.707107 2.7947e-16,
+                          0.866025 0.5 2.33483e-16,
+                          0.653282 0.270598 -0.707107,
+                          0.866025 0.5 -1.14383e-17,
+                          0.707107 0.707107 3.45486e-17,
+                          0.654307 0.271023 0.705995,
+                          0.500785 0.500785 0.705995,
+                          0.866025 0.5 2.33483e-16,
+                          0.271023 0.654307 0.705995,
+                          0.5 0.866025 7.58846e-16,
+                          0.707107 0.707107 2.7947e-16,
+                          0.5 0.5 -0.707107,
+                          0.707107 0.707107 3.45486e-17,
+                          0.5 0.866025 -3.74254e-16,
+                          0.500785 0.500785 0.705995,
+                          0.271023 0.654307 0.705995,
+                          0.707107 0.707107 2.7947e-16,
+                          0.653282 0.270598 -0.707107,
+                          0.707107 0.707107 3.45486e-17,
+                          0.5 0.5 -0.707107,
+                          0.271023 0.654307 0.705995,
+                          0.258819 0.965926 3.36939e-16,
+                          0.5 0.866025 7.58846e-16,
+                          0.270598 0.653282 -0.707107,
+                          0.5 0.866025 -3.74254e-16,
+                          0.258819 0.965926 9.2018e-17,
+                          0.5 0.5 -0.707107,
+                          0.5 0.866025 -3.74254e-16,
+                          0.270598 0.653282 -0.707107,
+                          0.000300559 0.000725613 1,
+                          0.271023 0.654307 0.705995,
+                          0.500785 0.500785 0.705995,
+                          0.00055536 0.00055536 1,
+                          0.500785 0.500785 0.705995,
+                          0.654307 0.271023 0.705995,
+                          0.00055536 0.00055536 1,
+                          0.000300559 0.000725613 1,
+                          0.500785 0.500785 0.705995,
+                          0.000725613 0.000300559 1,
+                          0.654307 0.271023 0.705995,
+                          0.708217 3.98072e-17 0.705995,
+                          0.000725613 0.000300559 1,
+                          0.00055536 0.00055536 1,
+                          0.654307 0.271023 0.705995,
+                          0.000785398 -2.21827e-16 1,
+                          0.708217 3.98072e-17 0.705995,
+                          0.654307 -0.271023 0.705995,
+                          0.000785398 -2.21827e-16 1,
+                          0.000725613 0.000300559 1,
+                          0.708217 3.98072e-17 0.705995,
+                          0.000725613 -0.000300559 1,
+                          0.654307 -0.271023 0.705995,
+                          0.500785 -0.500785 0.705995,
+                          0.000725613 -0.000300559 1,
+                          0.000785398 -2.21827e-16 1,
+                          0.654307 -0.271023 0.705995,
+                          0.00055536 -0.00055536 1,
+                          0.500785 -0.500785 0.705995,
+                          0.271023 -0.654307 0.705995,
+                          0.00055536 -0.00055536 1,
+                          0.000725613 -0.000300559 1,
+                          0.500785 -0.500785 0.705995,
+                          0.000300559 -0.000725613 1,
+                          0.00055536 -0.00055536 1,
+                          0.271023 -0.654307 0.705995,
+                          -0.270598 -0.653282 0.707107,
+                          0.000300559 0.000725613 1,
+                          0.00055536 0.00055536 1,
+                          -0.5 -0.5 0.707107,
+                          0.00055536 0.00055536 1,
+                          0.000725613 0.000300559 1,
+                          -0.5 -0.5 0.707107,
+                          -0.270598 -0.653282 0.707107,
+                          0.00055536 0.00055536 1,
+                          -0.653282 -0.270598 0.707107,
+                          0.000725613 0.000300559 1,
+                          0.000785398 -2.21827e-16 1,
+                          -0.653282 -0.270598 0.707107,
+                          -0.5 -0.5 0.707107,
+                          0.000725613 0.000300559 1,
+                          -0.707107 -3.53271e-16 0.707107,
+                          0.000785398 -2.21827e-16 1,
+                          0.000725613 -0.000300559 1,
+                          -0.707107 -3.53271e-16 0.707107,
+                          -0.653282 -0.270598 0.707107,
+                          0.000785398 -2.21827e-16 1,
+                          -0.653282 0.270598 0.707107,
+                          0.000725613 -0.000300559 1,
+                          0.00055536 -0.00055536 1,
+                          -0.653282 0.270598 0.707107,
+                          -0.707107 -3.53271e-16 0.707107,
+                          0.000725613 -0.000300559 1,
+                          -0.5 0.5 0.707107,
+                          0.00055536 -0.00055536 1,
+                          0.000300559 -0.000725613 1,
+                          -0.5 0.5 0.707107,
+                          -0.653282 0.270598 0.707107,
+                          0.00055536 -0.00055536 1,
+                          -0.270598 0.653282 0.707107,
+                          -0.5 0.5 0.707107,
+                          0.000300559 -0.000725613 1,
+                          -0.382683 -0.92388 -9.41202e-17,
+                          -0.270598 -0.653282 0.707107,
+                          -0.5 -0.5 0.707107,
+                          -0.707107 -0.707107 -4.59869e-17,
+                          -0.5 -0.5 0.707107,
+                          -0.653282 -0.270598 0.707107,
+                          -0.707107 -0.707107 -4.59869e-17,
+                          -0.382683 -0.92388 -9.41202e-17,
+                          -0.5 -0.5 0.707107,
+                          -0.92388 -0.382683 2.60495e-17,
+                          -0.653282 -0.270598 0.707107,
+                          -0.707107 -3.53271e-16 0.707107,
+                          -0.92388 -0.382683 2.60495e-17,
+                          -0.707107 -0.707107 -4.59869e-17,
+                          -0.653282 -0.270598 0.707107,
+                          -1 -2.77556e-16 1.11022e-16,
+                          -0.707107 -3.53271e-16 0.707107,
+                          -0.653282 0.270598 0.707107,
+                          -1 -2.77556e-16 1.11022e-16,
+                          -0.92388 -0.382683 2.60495e-17,
+                          -0.707107 -3.53271e-16 0.707107,
+                          -0.92388 0.382683 1.95995e-16,
+                          -0.653282 0.270598 0.707107,
+                          -0.5 0.5 0.707107,
+                          -0.92388 0.382683 1.95995e-16,
+                          -1 -2.77556e-16 1.11022e-16,
+                          -0.653282 0.270598 0.707107,
+                          -0.707107 0.707107 2.68032e-16,
+                          -0.5 0.5 0.707107,
+                          -0.270598 0.653282 0.707107,
+                          -0.707107 0.707107 2.68032e-16,
+                          -0.92388 0.382683 1.95995e-16,
+                          -0.5 0.5 0.707107,
+                          -0.382683 0.92388 3.16165e-16,
+                          -0.707107 0.707107 2.68032e-16,
+                          -0.270598 0.653282 0.707107,
+                          -0.271023 -0.654307 -0.705995,
+                          -0.382683 -0.92388 -2.05142e-16,
+                          -0.707107 -0.707107 -1.57009e-16,
+                          -0.500785 -0.500785 -0.705995,
+                          -0.707107 -0.707107 -1.57009e-16,
+                          -0.92388 -0.382683 -8.49728e-17,
+                          -0.500785 -0.500785 -0.705995,
+                          -0.271023 -0.654307 -0.705995,
+                          -0.707107 -0.707107 -1.57009e-16,
+                          -0.654307 -0.271023 -0.705995,
+                          -0.92388 -0.382683 -8.49728e-17,
+                          -1 -2.77556e-16 0,
+                          -0.654307 -0.271023 -0.705995,
+                          -0.500785 -0.500785 -0.705995,
+                          -0.92388 -0.382683 -8.49728e-17,
+                          -0.708217 -3.98072e-17 -0.705995,
+                          -1 -2.77556e-16 0,
+                          -0.92388 0.382683 8.49728e-17,
+                          -0.708217 -3.98072e-17 -0.705995,
+                          -0.654307 -0.271023 -0.705995,
+                          -1 -2.77556e-16 0,
+                          -0.654307 0.271023 -0.705995,
+                          -0.92388 0.382683 8.49728e-17,
+                          -0.707107 0.707107 1.57009e-16,
+                          -0.654307 0.271023 -0.705995,
+                          -0.708217 -3.98072e-17 -0.705995,
+                          -0.92388 0.382683 8.49728e-17,
+                          -0.500785 0.500785 -0.705995,
+                          -0.707107 0.707107 1.57009e-16,
+                          -0.382683 0.92388 2.05142e-16,
+                          -0.500785 0.500785 -0.705995,
+                          -0.654307 0.271023 -0.705995,
+                          -0.707107 0.707107 1.57009e-16,
+                          -0.271023 0.654307 -0.705995,
+                          -0.500785 0.500785 -0.705995,
+                          -0.382683 0.92388 2.05142e-16,
+                          -0.000300559 -0.000725613 -1,
+                          -0.271023 -0.654307 -0.705995,
+                          -0.500785 -0.500785 -0.705995,
+                          -0.00055536 -0.00055536 -1,
+                          -0.500785 -0.500785 -0.705995,
+                          -0.654307 -0.271023 -0.705995,
+                          -0.00055536 -0.00055536 -1,
+                          -0.000300559 -0.000725613 -1,
+                          -0.500785 -0.500785 -0.705995,
+                          -0.000725613 -0.000300559 -1,
+                          -0.654307 -0.271023 -0.705995,
+                          -0.708217 -3.98072e-17 -0.705995,
+                          -0.000725613 -0.000300559 -1,
+                          -0.00055536 -0.00055536 -1,
+                          -0.654307 -0.271023 -0.705995,
+                          -0.000785398 2.21827e-16 -1,
+                          -0.708217 -3.98072e-17 -0.705995,
+                          -0.654307 0.271023 -0.705995,
+                          -0.000785398 2.21827e-16 -1,
+                          -0.000725613 -0.000300559 -1,
+                          -0.708217 -3.98072e-17 -0.705995,
+                          -0.000725613 0.000300559 -1,
+                          -0.654307 0.271023 -0.705995,
+                          -0.500785 0.500785 -0.705995,
+                          -0.000725613 0.000300559 -1,
+                          -0.000785398 2.21827e-16 -1,
+                          -0.654307 0.271023 -0.705995,
+                          -0.00055536 0.00055536 -1,
+                          -0.500785 0.500785 -0.705995,
+                          -0.271023 0.654307 -0.705995,
+                          -0.00055536 0.00055536 -1,
+                          -0.000725613 0.000300559 -1,
+                          -0.500785 0.500785 -0.705995,
+                          -0.000300559 0.000725613 -1,
+                          -0.00055536 0.00055536 -1,
+                          -0.271023 0.654307 -0.705995,
+                          0.270598 0.653282 -0.707107,
+                          -0.000300559 -0.000725613 -1,
+                          -0.00055536 -0.00055536 -1,
+                          0.5 0.5 -0.707107,
+                          -0.00055536 -0.00055536 -1,
+                          -0.000725613 -0.000300559 -1,
+                          0.5 0.5 -0.707107,
+                          0.270598 0.653282 -0.707107,
+                          -0.00055536 -0.00055536 -1,
+                          0.653282 0.270598 -0.707107,
+                          -0.000725613 -0.000300559 -1,
+                          -0.000785398 2.21827e-16 -1,
+                          0.653282 0.270598 -0.707107,
+                          0.5 0.5 -0.707107,
+                          -0.000725613 -0.000300559 -1,
+                          0.707107 3.53271e-16 -0.707107,
+                          -0.000785398 2.21827e-16 -1,
+                          -0.000725613 0.000300559 -1,
+                          0.707107 3.53271e-16 -0.707107,
+                          0.653282 0.270598 -0.707107,
+                          -0.000785398 2.21827e-16 -1,
+                          0.653282 -0.270598 -0.707107,
+                          -0.000725613 0.000300559 -1,
+                          -0.00055536 0.00055536 -1,
+                          0.653282 -0.270598 -0.707107,
+                          0.707107 3.53271e-16 -0.707107,
+                          -0.000725613 0.000300559 -1,
+                          0.5 -0.5 -0.707107,
+                          -0.00055536 0.00055536 -1,
+                          -0.000300559 0.000725613 -1,
+                          0.5 -0.5 -0.707107,
+                          0.653282 -0.270598 -0.707107,
+                          -0.00055536 0.00055536 -1,
+                          0.270598 -0.653282 -0.707107,
+                          0.5 -0.5 -0.707107,
+                          -0.000300559 0.000725613 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -98 83 243.5,
+                          -129 111.183 243.5,
+                          -129 117.817 243.5,
+                          -129 114.5 242.5,
+                          -129 117.817 243.5,
+                          -129 111.183 243.5,
+                          -129 146 243.5,
+                          -98 83 243.5,
+                          -129 117.817 243.5,
+                          -129 146 253.5,
+                          -129 146 243.5,
+                          -129 117.817 243.5,
+                          -129 119.786 245.662,
+                          -129 146 253.5,
+                          -129 117.817 243.5,
+                          -157 118.749 244.264,
+                          -129 119.786 245.662,
+                          -129 117.817 243.5,
+                          -157 114.505 242.5,
+                          -129 117.817 243.5,
+                          -129 114.5 242.5,
+                          -157 114.505 242.5,
+                          -157 118.749 244.264,
+                          -129 117.817 243.5,
+                          -115 83 243.5,
+                          -129 83 243.5,
+                          -129 111.183 243.5,
+                          -129 109.214 245.662,
+                          -129 111.183 243.5,
+                          -129 83 243.5,
+                          -98 83 243.5,
+                          -115 83 243.5,
+                          -129 111.183 243.5,
+                          -157 110.257 244.257,
+                          -129 111.183 243.5,
+                          -129 109.214 245.662,
+                          -157 114.505 242.5,
+                          -129 114.5 242.5,
+                          -129 111.183 243.5,
+                          -157 110.257 244.257,
+                          -157 114.505 242.5,
+                          -129 111.183 243.5,
+                          -129 83 253.5,
+                          -129 83 243.5,
+                          -115 83 243.5,
+                          -129 111.183 253.5,
+                          -129 83 243.5,
+                          -129 83 253.5,
+                          -129 109.214 251.338,
+                          -129 83 243.5,
+                          -129 111.183 253.5,
+                          -129 108.5 248.5,
+                          -129 109.214 245.662,
+                          -129 83 243.5,
+                          -129 109.214 251.338,
+                          -129 108.5 248.5,
+                          -129 83 243.5,
+                          -115 83 253.5,
+                          -115 83 243.5,
+                          -98 83 243.5,
+                          -129 83 253.5,
+                          -115 83 243.5,
+                          -115 83 253.5,
+                          -115 146 243.5,
+                          -98 146 243.5,
+                          -98 83 243.5,
+                          -98 83 253.5,
+                          -98 83 243.5,
+                          -98 146 243.5,
+                          -129 146 243.5,
+                          -115 146 243.5,
+                          -98 83 243.5,
+                          -115 83 253.5,
+                          -98 83 243.5,
+                          -98 83 253.5,
+                          -98 146 253.5,
+                          -98 146 243.5,
+                          -115 146 243.5,
+                          -98 83 253.5,
+                          -98 146 243.5,
+                          -98 146 253.5,
+                          -115 146 253.5,
+                          -115 146 243.5,
+                          -129 146 243.5,
+                          -98 146 253.5,
+                          -115 146 243.5,
+                          -115 146 253.5,
+                          -115 146 253.5,
+                          -129 146 243.5,
+                          -129 146 253.5,
+                          -115 146 253.5,
+                          -129 146 253.5,
+                          -129 117.817 253.5,
+                          -129 119.786 251.338,
+                          -129 117.817 253.5,
+                          -129 146 253.5,
+                          -98 146 253.5,
+                          -115 146 253.5,
+                          -129 117.817 253.5,
+                          -129 111.183 253.5,
+                          -98 146 253.5,
+                          -129 117.817 253.5,
+                          -129 114.5 254.5,
+                          -129 111.183 253.5,
+                          -129 117.817 253.5,
+                          -157 118.743 252.743,
+                          -129 117.817 253.5,
+                          -129 119.786 251.338,
+                          -157 114.495 254.5,
+                          -129 114.5 254.5,
+                          -129 117.817 253.5,
+                          -157 118.743 252.743,
+                          -157 114.495 254.5,
+                          -129 117.817 253.5,
+                          -129 120.5 248.5,
+                          -129 119.786 251.338,
+                          -129 146 253.5,
+                          -129 119.786 245.662,
+                          -129 120.5 248.5,
+                          -129 146 253.5,
+                          -115 83 253.5,
+                          -98 83 253.5,
+                          -98 146 253.5,
+                          -129 83 253.5,
+                          -115 83 253.5,
+                          -98 146 253.5,
+                          -129 111.183 253.5,
+                          -129 83 253.5,
+                          -98 146 253.5,
+                          -157 110.251 252.736,
+                          -129 109.214 251.338,
+                          -129 111.183 253.5,
+                          -157 114.495 254.5,
+                          -129 111.183 253.5,
+                          -129 114.5 254.5,
+                          -157 114.495 254.5,
+                          -157 110.251 252.736,
+                          -129 111.183 253.5,
+                          -157 110.257 244.257,
+                          -129 109.214 245.662,
+                          -129 108.5 248.5,
+                          -157 108.5 248.5,
+                          -129 108.5 248.5,
+                          -129 109.214 251.338,
+                          -157 110.257 244.257,
+                          -129 108.5 248.5,
+                          -157 108.5 248.5,
+                          -157 110.251 252.736,
+                          -157 108.5 248.5,
+                          -129 109.214 251.338,
+                          -157 118.743 252.743,
+                          -129 119.786 251.338,
+                          -129 120.5 248.5,
+                          -157 120.5 248.5,
+                          -129 120.5 248.5,
+                          -129 119.786 245.662,
+                          -157 120.5 248.5,
+                          -157 118.743 252.743,
+                          -129 120.5 248.5,
+                          -157 118.749 244.264,
+                          -157 120.5 248.5,
+                          -129 119.786 245.662,
+                          -168.385 107.986 252.736,
+                          -157 108.5 248.5,
+                          -157 110.251 252.736,
+                          -164.247 107.546 248.5,
+                          -157 110.257 244.257,
+                          -157 108.5 248.5,
+                          -168.385 107.986 252.736,
+                          -164.247 107.546 248.5,
+                          -157 108.5 248.5,
+                          -170.009 111.908 254.5,
+                          -157 110.251 252.736,
+                          -157 114.495 254.5,
+                          -170.009 111.908 254.5,
+                          -168.385 107.986 252.736,
+                          -157 110.251 252.736,
+                          -171.635 115.832 252.743,
+                          -157 114.495 254.5,
+                          -157 118.743 252.743,
+                          -171.635 115.832 252.743,
+                          -170.009 111.908 254.5,
+                          -157 114.495 254.5,
+                          -172.307 117.455 248.5,
+                          -157 118.743 252.743,
+                          -157 120.5 248.5,
+                          -172.307 117.455 248.5,
+                          -171.635 115.832 252.743,
+                          -157 118.743 252.743,
+                          -171.637 115.838 244.264,
+                          -157 120.5 248.5,
+                          -157 118.749 244.264,
+                          -171.637 115.838 244.264,
+                          -172.307 117.455 248.5,
+                          -157 120.5 248.5,
+                          -170.013 111.916 242.5,
+                          -157 118.749 244.264,
+                          -157 114.505 242.5,
+                          -170.013 111.916 242.5,
+                          -171.637 115.838 244.264,
+                          -157 118.749 244.264,
+                          -168.388 107.992 244.257,
+                          -157 114.505 242.5,
+                          -157 110.257 244.257,
+                          -168.388 107.992 244.257,
+                          -170.013 111.916 242.5,
+                          -157 114.505 242.5,
+                          -168.388 107.992 244.257,
+                          -157 110.257 244.257,
+                          -164.247 107.546 248.5,
+                          -157 42.2499 244.265,
+                          -157 50.7434 244.258,
+                          -157 52.5 248.5,
+                          -168.388 53.0078 244.257,
+                          -157 52.5 248.5,
+                          -157 50.7434 244.258,
+                          -157 40.5 248.5,
+                          -157 42.2499 244.265,
+                          -157 52.5 248.5,
+                          -157 50.7501 252.735,
+                          -157 40.5 248.5,
+                          -157 52.5 248.5,
+                          -164.247 53.4541 248.5,
+                          -157 50.7501 252.735,
+                          -157 52.5 248.5,
+                          -168.388 53.0078 244.257,
+                          -164.247 53.4541 248.5,
+                          -157 52.5 248.5,
+                          -157 42.2499 244.265,
+                          -157 46.4953 242.5,
+                          -157 50.7434 244.258,
+                          -170.013 49.0837 242.5,
+                          -157 50.7434 244.258,
+                          -157 46.4953 242.5,
+                          -168.388 53.0078 244.257,
+                          -157 50.7434 244.258,
+                          -170.013 49.0837 242.5,
+                          -171.637 45.1623 244.264,
+                          -157 46.4953 242.5,
+                          -157 42.2499 244.265,
+                          -170.013 49.0837 242.5,
+                          -157 46.4953 242.5,
+                          -171.637 45.1623 244.264,
+                          -172.307 43.5448 248.5,
+                          -157 42.2499 244.265,
+                          -157 40.5 248.5,
+                          -171.637 45.1623 244.264,
+                          -157 42.2499 244.265,
+                          -172.307 43.5448 248.5,
+                          -157 50.7501 252.735,
+                          -157 42.2566 252.742,
+                          -157 40.5 248.5,
+                          -171.635 45.1684 252.743,
+                          -157 40.5 248.5,
+                          -157 42.2566 252.742,
+                          -172.307 43.5448 248.5,
+                          -157 40.5 248.5,
+                          -171.635 45.1684 252.743,
+                          -157 50.7501 252.735,
+                          -157 46.5047 254.5,
+                          -157 42.2566 252.742,
+                          -170.009 49.0924 254.5,
+                          -157 42.2566 252.742,
+                          -157 46.5047 254.5,
+                          -171.635 45.1684 252.743,
+                          -157 42.2566 252.742,
+                          -170.009 49.0924 254.5,
+                          -168.385 53.0139 252.736,
+                          -157 46.5047 254.5,
+                          -157 50.7501 252.735,
+                          -170.009 49.0924 254.5,
+                          -157 46.5047 254.5,
+                          -168.385 53.0139 252.736,
+                          -168.385 53.0139 252.736,
+                          -157 50.7501 252.735,
+                          -164.247 53.4541 248.5,
+                          -168.385 107.986 252.736,
+                          -171 104.749 248.5,
+                          -164.247 107.546 248.5,
+                          -168.388 107.992 244.257,
+                          -164.247 107.546 248.5,
+                          -171 104.749 248.5,
+                          -178.037 101.537 252.736,
+                          -176.799 100.299 248.5,
+                          -171 104.749 248.5,
+                          -168.388 107.992 244.257,
+                          -171 104.749 248.5,
+                          -176.799 100.299 248.5,
+                          -168.385 107.986 252.736,
+                          -178.037 101.537 252.736,
+                          -171 104.749 248.5,
+                          -184.486 91.8851 252.736,
+                          -181.249 94.5 248.5,
+                          -176.799 100.299 248.5,
+                          -178.042 101.542 244.257,
+                          -176.799 100.299 248.5,
+                          -181.249 94.5 248.5,
+                          -178.037 101.537 252.736,
+                          -184.486 91.8851 252.736,
+                          -176.799 100.299 248.5,
+                          -168.388 107.992 244.257,
+                          -176.799 100.299 248.5,
+                          -178.042 101.542 244.257,
+                          -184.486 91.8851 252.736,
+                          -184.046 87.7469 248.5,
+                          -181.249 94.5 248.5,
+                          -184.492 91.8876 244.257,
+                          -181.249 94.5 248.5,
+                          -184.046 87.7469 248.5,
+                          -178.042 101.542 244.257,
+                          -181.249 94.5 248.5,
+                          -184.492 91.8876 244.257,
+                          -186.751 80.5 252.736,
+                          -185 80.5 248.5,
+                          -184.046 87.7469 248.5,
+                          -184.492 91.8876 244.257,
+                          -184.046 87.7469 248.5,
+                          -185 80.5 248.5,
+                          -184.486 91.8851 252.736,
+                          -186.751 80.5 252.736,
+                          -184.046 87.7469 248.5,
+                          -184.486 69.1149 252.736,
+                          -184.046 73.2531 248.5,
+                          -185 80.5 248.5,
+                          -186.757 80.5 244.257,
+                          -185 80.5 248.5,
+                          -184.046 73.2531 248.5,
+                          -186.751 80.5 252.736,
+                          -184.486 69.1149 252.736,
+                          -185 80.5 248.5,
+                          -184.492 91.8876 244.257,
+                          -185 80.5 248.5,
+                          -186.757 80.5 244.257,
+                          -184.486 69.1149 252.736,
+                          -181.249 66.5 248.5,
+                          -184.046 73.2531 248.5,
+                          -184.492 69.1124 244.257,
+                          -184.046 73.2531 248.5,
+                          -181.249 66.5 248.5,
+                          -186.757 80.5 244.257,
+                          -184.046 73.2531 248.5,
+                          -184.492 69.1124 244.257,
+                          -178.037 59.4631 252.736,
+                          -176.799 60.701 248.5,
+                          -181.249 66.5 248.5,
+                          -184.492 69.1124 244.257,
+                          -181.249 66.5 248.5,
+                          -176.799 60.701 248.5,
+                          -184.486 69.1149 252.736,
+                          -178.037 59.4631 252.736,
+                          -181.249 66.5 248.5,
+                          -168.385 53.0139 252.736,
+                          -171 56.2513 248.5,
+                          -176.799 60.701 248.5,
+                          -178.042 59.4584 244.257,
+                          -176.799 60.701 248.5,
+                          -171 56.2513 248.5,
+                          -178.037 59.4631 252.736,
+                          -168.385 53.0139 252.736,
+                          -176.799 60.701 248.5,
+                          -184.492 69.1124 244.257,
+                          -176.799 60.701 248.5,
+                          -178.042 59.4584 244.257,
+                          -168.385 53.0139 252.736,
+                          -164.247 53.4541 248.5,
+                          -171 56.2513 248.5,
+                          -168.388 53.0078 244.257,
+                          -171 56.2513 248.5,
+                          -164.247 53.4541 248.5,
+                          -178.042 59.4584 244.257,
+                          -171 56.2513 248.5,
+                          -168.388 53.0078 244.257,
+                          -170.009 49.0924 254.5,
+                          -168.385 53.0139 252.736,
+                          -178.037 59.4631 252.736,
+                          -181.038 56.4617 254.5,
+                          -178.037 59.4631 252.736,
+                          -184.486 69.1149 252.736,
+                          -181.038 56.4617 254.5,
+                          -170.009 49.0924 254.5,
+                          -178.037 59.4631 252.736,
+                          -188.408 67.4906 254.5,
+                          -184.486 69.1149 252.736,
+                          -186.751 80.5 252.736,
+                          -188.408 67.4906 254.5,
+                          -181.038 56.4617 254.5,
+                          -184.486 69.1149 252.736,
+                          -190.995 80.5 254.5,
+                          -186.751 80.5 252.736,
+                          -184.486 91.8851 252.736,
+                          -190.995 80.5 254.5,
+                          -188.408 67.4906 254.5,
+                          -186.751 80.5 252.736,
+                          -188.408 93.5094 254.5,
+                          -184.486 91.8851 252.736,
+                          -178.037 101.537 252.736,
+                          -188.408 93.5094 254.5,
+                          -190.995 80.5 254.5,
+                          -184.486 91.8851 252.736,
+                          -181.038 104.538 254.5,
+                          -178.037 101.537 252.736,
+                          -168.385 107.986 252.736,
+                          -181.038 104.538 254.5,
+                          -188.408 93.5094 254.5,
+                          -178.037 101.537 252.736,
+                          -170.009 111.908 254.5,
+                          -181.038 104.538 254.5,
+                          -168.385 107.986 252.736,
+                          -171.635 45.1684 252.743,
+                          -170.009 49.0924 254.5,
+                          -181.038 56.4617 254.5,
+                          -184.042 53.4584 252.743,
+                          -181.038 56.4617 254.5,
+                          -188.408 67.4906 254.5,
+                          -184.042 53.4584 252.743,
+                          -171.635 45.1684 252.743,
+                          -181.038 56.4617 254.5,
+                          -192.332 65.8652 252.743,
+                          -188.408 67.4906 254.5,
+                          -190.995 80.5 254.5,
+                          -192.332 65.8652 252.743,
+                          -184.042 53.4584 252.743,
+                          -188.408 67.4906 254.5,
+                          -195.243 80.5 252.743,
+                          -190.995 80.5 254.5,
+                          -188.408 93.5094 254.5,
+                          -195.243 80.5 252.743,
+                          -192.332 65.8652 252.743,
+                          -190.995 80.5 254.5,
+                          -192.332 95.1348 252.743,
+                          -188.408 93.5094 254.5,
+                          -181.038 104.538 254.5,
+                          -192.332 95.1348 252.743,
+                          -195.243 80.5 252.743,
+                          -188.408 93.5094 254.5,
+                          -184.042 107.542 252.743,
+                          -181.038 104.538 254.5,
+                          -170.009 111.908 254.5,
+                          -184.042 107.542 252.743,
+                          -192.332 95.1348 252.743,
+                          -181.038 104.538 254.5,
+                          -171.635 115.832 252.743,
+                          -184.042 107.542 252.743,
+                          -170.009 111.908 254.5,
+                          -172.307 43.5448 248.5,
+                          -171.635 45.1684 252.743,
+                          -184.042 53.4584 252.743,
+                          -185.284 52.2157 248.5,
+                          -184.042 53.4584 252.743,
+                          -192.332 65.8652 252.743,
+                          -185.284 52.2157 248.5,
+                          -172.307 43.5448 248.5,
+                          -184.042 53.4584 252.743,
+                          -193.955 65.1927 248.5,
+                          -192.332 65.8652 252.743,
+                          -195.243 80.5 252.743,
+                          -193.955 65.1927 248.5,
+                          -185.284 52.2157 248.5,
+                          -192.332 65.8652 252.743,
+                          -197 80.5 248.5,
+                          -195.243 80.5 252.743,
+                          -192.332 95.1348 252.743,
+                          -197 80.5 248.5,
+                          -193.955 65.1927 248.5,
+                          -195.243 80.5 252.743,
+                          -193.955 95.8073 248.5,
+                          -192.332 95.1348 252.743,
+                          -184.042 107.542 252.743,
+                          -193.955 95.8073 248.5,
+                          -197 80.5 248.5,
+                          -192.332 95.1348 252.743,
+                          -185.284 108.784 248.5,
+                          -184.042 107.542 252.743,
+                          -171.635 115.832 252.743,
+                          -185.284 108.784 248.5,
+                          -193.955 95.8073 248.5,
+                          -184.042 107.542 252.743,
+                          -172.307 117.455 248.5,
+                          -185.284 108.784 248.5,
+                          -171.635 115.832 252.743,
+                          -171.637 45.1623 244.264,
+                          -172.307 43.5448 248.5,
+                          -185.284 52.2157 248.5,
+                          -184.046 53.4537 244.264,
+                          -185.284 52.2157 248.5,
+                          -193.955 65.1927 248.5,
+                          -184.046 53.4537 244.264,
+                          -171.637 45.1623 244.264,
+                          -185.284 52.2157 248.5,
+                          -192.338 65.8626 244.264,
+                          -193.955 65.1927 248.5,
+                          -197 80.5 248.5,
+                          -192.338 65.8626 244.264,
+                          -184.046 53.4537 244.264,
+                          -193.955 65.1927 248.5,
+                          -195.249 80.5 244.264,
+                          -197 80.5 248.5,
+                          -193.955 95.8073 248.5,
+                          -195.249 80.5 244.264,
+                          -192.338 65.8626 244.264,
+                          -197 80.5 248.5,
+                          -192.338 95.1374 244.264,
+                          -193.955 95.8073 248.5,
+                          -185.284 108.784 248.5,
+                          -192.338 95.1374 244.264,
+                          -195.249 80.5 244.264,
+                          -193.955 95.8073 248.5,
+                          -184.046 107.546 244.264,
+                          -185.284 108.784 248.5,
+                          -172.307 117.455 248.5,
+                          -184.046 107.546 244.264,
+                          -192.338 95.1374 244.264,
+                          -185.284 108.784 248.5,
+                          -171.637 115.838 244.264,
+                          -184.046 107.546 244.264,
+                          -172.307 117.455 248.5,
+                          -170.013 49.0837 242.5,
+                          -171.637 45.1623 244.264,
+                          -184.046 53.4537 244.264,
+                          -181.045 56.455 242.5,
+                          -184.046 53.4537 244.264,
+                          -192.338 65.8626 244.264,
+                          -181.045 56.455 242.5,
+                          -170.013 49.0837 242.5,
+                          -184.046 53.4537 244.264,
+                          -188.416 67.487 242.5,
+                          -192.338 65.8626 244.264,
+                          -195.249 80.5 244.264,
+                          -188.416 67.487 242.5,
+                          -181.045 56.455 242.5,
+                          -192.338 65.8626 244.264,
+                          -191.005 80.5 242.5,
+                          -195.249 80.5 244.264,
+                          -192.338 95.1374 244.264,
+                          -191.005 80.5 242.5,
+                          -188.416 67.487 242.5,
+                          -195.249 80.5 244.264,
+                          -188.416 93.513 242.5,
+                          -192.338 95.1374 244.264,
+                          -184.046 107.546 244.264,
+                          -188.416 93.513 242.5,
+                          -191.005 80.5 242.5,
+                          -192.338 95.1374 244.264,
+                          -181.045 104.545 242.5,
+                          -184.046 107.546 244.264,
+                          -171.637 115.838 244.264,
+                          -181.045 104.545 242.5,
+                          -188.416 93.513 242.5,
+                          -184.046 107.546 244.264,
+                          -170.013 111.916 242.5,
+                          -181.045 104.545 242.5,
+                          -171.637 115.838 244.264,
+                          -168.388 53.0078 244.257,
+                          -170.013 49.0837 242.5,
+                          -181.045 56.455 242.5,
+                          -178.042 59.4584 244.257,
+                          -181.045 56.455 242.5,
+                          -188.416 67.487 242.5,
+                          -178.042 59.4584 244.257,
+                          -168.388 53.0078 244.257,
+                          -181.045 56.455 242.5,
+                          -184.492 69.1124 244.257,
+                          -188.416 67.487 242.5,
+                          -191.005 80.5 242.5,
+                          -184.492 69.1124 244.257,
+                          -178.042 59.4584 244.257,
+                          -188.416 67.487 242.5,
+                          -186.757 80.5 244.257,
+                          -191.005 80.5 242.5,
+                          -188.416 93.513 242.5,
+                          -186.757 80.5 244.257,
+                          -184.492 69.1124 244.257,
+                          -191.005 80.5 242.5,
+                          -184.492 91.8876 244.257,
+                          -188.416 93.513 242.5,
+                          -181.045 104.545 242.5,
+                          -184.492 91.8876 244.257,
+                          -186.757 80.5 244.257,
+                          -188.416 93.513 242.5,
+                          -178.042 101.542 244.257,
+                          -181.045 104.545 242.5,
+                          -170.013 111.916 242.5,
+                          -178.042 101.542 244.257,
+                          -184.492 91.8876 244.257,
+                          -181.045 104.545 242.5,
+                          -168.388 107.992 244.257,
+                          -178.042 101.542 244.257,
+                          -170.013 111.916 242.5 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+    Separator {
+        Normal {
+            vector      [ 1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1.52965e-16 -0.707107 0.707107,
+                          1.52965e-16 -0.707107 0.707107,
+                          2.16325e-16 -1 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          0 -1.11022e-16 1,
+                          0 -1.11022e-16 1,
+                          1.52965e-16 -0.707107 0.707107,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1.52965e-16 -0.707107 0.707107,
+                          0 -1.11022e-16 1,
+                          1.52965e-16 -0.707107 0.707107,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          2.16325e-16 -1 0,
+                          2.16325e-16 -1 0,
+                          1.52965e-16 -0.707107 -0.707107,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          2.16325e-16 -1 0,
+                          1.52965e-16 -0.707107 0.707107,
+                          2.16325e-16 -1 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1.52965e-16 -0.707107 -0.707107,
+                          1.52965e-16 -0.707107 -0.707107,
+                          0 -1.11022e-16 -1,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          2.16325e-16 -1 0,
+                          1.52965e-16 -0.707107 -0.707107,
+                          1.52965e-16 -0.707107 -0.707107,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          0 -1.11022e-16 -1,
+                          0 -1.11022e-16 -1,
+                          -1.52965e-16 0.707107 -0.707107,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1.52965e-16 -0.707107 -0.707107,
+                          0 -1.11022e-16 -1,
+                          0 -1.11022e-16 -1,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          -1.52965e-16 0.707107 -0.707107,
+                          -1.52965e-16 0.707107 -0.707107,
+                          -2.16325e-16 1 1.11022e-16,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          0 -1.11022e-16 -1,
+                          -1.52965e-16 0.707107 -0.707107,
+                          -1.52965e-16 0.707107 -0.707107,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          -2.16325e-16 1 1.11022e-16,
+                          -2.16325e-16 1 1.11022e-16,
+                          -1.52965e-16 0.707107 0.707107,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          -2.16325e-16 1 1.11022e-16,
+                          -1.52965e-16 0.707107 -0.707107,
+                          -2.16325e-16 1 1.11022e-16,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          -1.52965e-16 0.707107 0.707107,
+                          -1.52965e-16 0.707107 0.707107,
+                          0 -1.11022e-16 1,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          -1.52965e-16 0.707107 0.707107,
+                          -2.16325e-16 1 1.11022e-16,
+                          -1.52965e-16 0.707107 0.707107,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          0 -1.11022e-16 1,
+                          -1.52965e-16 0.707107 0.707107,
+                          0 -1.11022e-16 1,
+                          -1.52965e-16 0.707107 -0.707107,
+                          -1.52965e-16 0.707107 -0.707107,
+                          -8.27842e-17 0.382683 -0.92388,
+                          -1.99859e-16 0.92388 -0.382683,
+                          -1.99859e-16 0.92388 -0.382683,
+                          -1.52965e-16 0.707107 -0.707107,
+                          -1.99859e-16 0.92388 -0.382683,
+                          -1.52965e-16 0.707107 -0.707107,
+                          -1.52965e-16 0.707107 -0.707107,
+                          -8.27842e-17 0.382683 -0.92388,
+                          -8.27842e-17 0.382683 -0.92388,
+                          0 1.11022e-16 -1,
+                          -8.27842e-17 0.382683 -0.92388,
+                          -1.52965e-16 0.707107 -0.707107,
+                          -8.27842e-17 0.382683 -0.92388,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          0 1.11022e-16 -1,
+                          0 1.11022e-16 -1,
+                          8.27842e-17 -0.382683 -0.92388,
+                          -8.27842e-17 0.382683 -0.92388,
+                          0 1.11022e-16 -1,
+                          0 1.11022e-16 -1,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          8.27842e-17 -0.382683 -0.92388,
+                          8.27842e-17 -0.382683 -0.92388,
+                          1.52965e-16 -0.707107 -0.707107,
+                          0 1.11022e-16 -1,
+                          8.27842e-17 -0.382683 -0.92388,
+                          8.27842e-17 -0.382683 -0.92388,
+                          1.52965e-16 -0.707107 -0.707107,
+                          1.52965e-16 -0.707107 -0.707107,
+                          1.99859e-16 -0.92388 -0.382683,
+                          8.27842e-17 -0.382683 -0.92388,
+                          1.52965e-16 -0.707107 -0.707107,
+                          1.52965e-16 -0.707107 -0.707107,
+                          1.99859e-16 -0.92388 -0.382683,
+                          1.99859e-16 -0.92388 -0.382683,
+                          2.16325e-16 -1 -1.11022e-16,
+                          1.52965e-16 -0.707107 -0.707107,
+                          1.99859e-16 -0.92388 -0.382683,
+                          1.99859e-16 -0.92388 -0.382683,
+                          2.16325e-16 -1 -1.11022e-16,
+                          2.16325e-16 -1 -1.11022e-16,
+                          1.99859e-16 -0.92388 0.382683,
+                          1.99859e-16 -0.92388 -0.382683,
+                          2.16325e-16 -1 -1.11022e-16,
+                          2.16325e-16 -1 -1.11022e-16,
+                          1.99859e-16 -0.92388 0.382683,
+                          1.99859e-16 -0.92388 0.382683,
+                          1.52965e-16 -0.707107 0.707107,
+                          2.16325e-16 -1 -1.11022e-16,
+                          1.99859e-16 -0.92388 0.382683,
+                          1.99859e-16 -0.92388 0.382683,
+                          1.52965e-16 -0.707107 0.707107,
+                          1.52965e-16 -0.707107 0.707107,
+                          8.27842e-17 -0.382683 0.92388,
+                          1.99859e-16 -0.92388 0.382683,
+                          1.52965e-16 -0.707107 0.707107,
+                          1.52965e-16 -0.707107 0.707107,
+                          8.27842e-17 -0.382683 0.92388,
+                          8.27842e-17 -0.382683 0.92388,
+                          0 9.4369e-16 1,
+                          1.52965e-16 -0.707107 0.707107,
+                          8.27842e-17 -0.382683 0.92388,
+                          8.27842e-17 -0.382683 0.92388,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          0 9.4369e-16 1,
+                          0 9.4369e-16 1,
+                          -8.27842e-17 0.382683 0.92388,
+                          8.27842e-17 -0.382683 0.92388,
+                          0 9.4369e-16 1,
+                          0 9.4369e-16 1,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          -8.27842e-17 0.382683 0.92388,
+                          -8.27842e-17 0.382683 0.92388,
+                          -1.52965e-16 0.707107 0.707107,
+                          0 9.4369e-16 1,
+                          -8.27842e-17 0.382683 0.92388,
+                          -8.27842e-17 0.382683 0.92388,
+                          -1.52965e-16 0.707107 0.707107,
+                          -1.52965e-16 0.707107 0.707107,
+                          -1.99859e-16 0.92388 0.382683,
+                          -8.27842e-17 0.382683 0.92388,
+                          -1.52965e-16 0.707107 0.707107,
+                          -1.52965e-16 0.707107 0.707107,
+                          -1.99859e-16 0.92388 0.382683,
+                          -1.99859e-16 0.92388 0.382683,
+                          -2.16325e-16 1 0,
+                          -1.52965e-16 0.707107 0.707107,
+                          -1.99859e-16 0.92388 0.382683,
+                          -1.99859e-16 0.92388 0.382683,
+                          -2.16325e-16 1 0,
+                          -2.16325e-16 1 0,
+                          -1.99859e-16 0.92388 -0.382683,
+                          -1.99859e-16 0.92388 0.382683,
+                          -2.16325e-16 1 0,
+                          -2.16325e-16 1 0,
+                          -2.16325e-16 1 0,
+                          -1.99859e-16 0.92388 -0.382683,
+                          -1.99859e-16 0.92388 -0.382683,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -3.38408e-17 0.156434 -0.987688,
+                          -3.38408e-17 0.156434 -0.987688,
+                          -1.52965e-16 0.707107 -0.707107,
+                          -1.52965e-16 0.707107 -0.707107,
+                          -3.38408e-17 0.156434 -0.987688,
+                          -1.52965e-16 0.707107 -0.707107,
+                          -2.13662e-16 0.987688 -0.156434,
+                          -1.52965e-16 0.707107 -0.707107,
+                          -1.52965e-16 0.707107 -0.707107,
+                          9.82097e-17 -0.45399 -0.891007,
+                          9.82097e-17 -0.45399 -0.891007,
+                          -3.38408e-17 0.156434 -0.987688,
+                          -3.38408e-17 0.156434 -0.987688,
+                          9.82097e-17 -0.45399 -0.891007,
+                          -3.38408e-17 0.156434 -0.987688,
+                          1.92747e-16 -0.891007 -0.45399,
+                          1.92747e-16 -0.891007 -0.45399,
+                          9.82097e-17 -0.45399 -0.891007,
+                          9.82097e-17 -0.45399 -0.891007,
+                          1.92747e-16 -0.891007 -0.45399,
+                          9.82097e-17 -0.45399 -0.891007,
+                          2.13662e-16 -0.987688 0.156434,
+                          2.13662e-16 -0.987688 0.156434,
+                          1.92747e-16 -0.891007 -0.45399,
+                          1.92747e-16 -0.891007 -0.45399,
+                          2.13662e-16 -0.987688 0.156434,
+                          1.92747e-16 -0.891007 -0.45399,
+                          1.52965e-16 -0.707107 0.707107,
+                          1.52965e-16 -0.707107 0.707107,
+                          2.13662e-16 -0.987688 0.156434,
+                          2.13662e-16 -0.987688 0.156434,
+                          1.52965e-16 -0.707107 0.707107,
+                          2.13662e-16 -0.987688 0.156434,
+                          3.38408e-17 -0.156434 0.987688,
+                          1.52965e-16 -0.707107 0.707107,
+                          1.52965e-16 -0.707107 0.707107,
+                          3.38408e-17 -0.156434 0.987688,
+                          1.52965e-16 -0.707107 0.707107,
+                          3.38408e-17 -0.156434 0.987688,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          -2.13662e-16 0.987688 -0.156434,
+                          -2.13662e-16 0.987688 -0.156434,
+                          -1.52965e-16 0.707107 -0.707107,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          -1.52965e-16 0.707107 -0.707107,
+                          -1.52965e-16 0.707107 -0.707107,
+                          -2.16325e-16 1 0,
+                          0 1.11022e-16 -1,
+                          0 1.11022e-16 -1,
+                          -1.52965e-16 0.707107 -0.707107,
+                          -1.52965e-16 0.707107 -0.707107,
+                          0 1.11022e-16 -1,
+                          -1.52965e-16 0.707107 -0.707107,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          -2.16325e-16 1 0,
+                          -2.16325e-16 1 0,
+                          -1.52965e-16 0.707107 0.707107,
+                          -2.16325e-16 1 0,
+                          -1.52965e-16 0.707107 -0.707107,
+                          -2.16325e-16 1 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          -1.52965e-16 0.707107 0.707107,
+                          -1.52965e-16 0.707107 0.707107,
+                          0 1.11022e-16 1,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          -2.16325e-16 1 0,
+                          -1.52965e-16 0.707107 0.707107,
+                          -1.52965e-16 0.707107 0.707107,
+                          0 1.11022e-16 1,
+                          0 1.11022e-16 1,
+                          1.52965e-16 -0.707107 0.707107,
+                          -1.52965e-16 0.707107 0.707107,
+                          0 1.11022e-16 1,
+                          0 1.11022e-16 1,
+                          1.52965e-16 -0.707107 0.707107,
+                          1.52965e-16 -0.707107 0.707107,
+                          2.16325e-16 -1 -1.11022e-16,
+                          0 1.11022e-16 1,
+                          1.52965e-16 -0.707107 0.707107,
+                          1.52965e-16 -0.707107 0.707107,
+                          2.16325e-16 -1 -1.11022e-16,
+                          2.16325e-16 -1 -1.11022e-16,
+                          1.52965e-16 -0.707107 -0.707107,
+                          2.16325e-16 -1 -1.11022e-16,
+                          1.52965e-16 -0.707107 0.707107,
+                          2.16325e-16 -1 -1.11022e-16,
+                          1.52965e-16 -0.707107 -0.707107,
+                          1.52965e-16 -0.707107 -0.707107,
+                          0 1.11022e-16 -1,
+                          1.52965e-16 -0.707107 -0.707107,
+                          2.16325e-16 -1 -1.11022e-16,
+                          1.52965e-16 -0.707107 -0.707107,
+                          0 1.11022e-16 -1,
+                          1.52965e-16 -0.707107 -0.707107,
+                          0 1.11022e-16 -1,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          3.38408e-17 -0.156434 0.987688,
+                          3.38408e-17 -0.156434 0.987688,
+                          -9.82097e-17 0.45399 0.891007,
+                          -9.82097e-17 0.45399 0.891007,
+                          -9.82097e-17 0.45399 0.891007,
+                          -1.92747e-16 0.891007 0.45399,
+                          3.38408e-17 -0.156434 0.987688,
+                          -9.82097e-17 0.45399 0.891007,
+                          -9.82097e-17 0.45399 0.891007,
+                          -1.92747e-16 0.891007 0.45399,
+                          -1.92747e-16 0.891007 0.45399,
+                          -2.13662e-16 0.987688 -0.156434,
+                          -9.82097e-17 0.45399 0.891007,
+                          -1.92747e-16 0.891007 0.45399,
+                          -1.92747e-16 0.891007 0.45399,
+                          -1.92747e-16 0.891007 0.45399,
+                          -2.13662e-16 0.987688 -0.156434,
+                          -2.13662e-16 0.987688 -0.156434,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1.52965e-16 0.707107 -0.707107,
+                          -1.52965e-16 0.707107 -0.707107,
+                          -2.13662e-16 0.987688 -0.156434,
+                          -3.38408e-17 0.156434 -0.987688,
+                          -3.38408e-17 0.156434 -0.987688,
+                          -1.52965e-16 0.707107 -0.707107,
+                          -1.52965e-16 0.707107 -0.707107,
+                          -3.38408e-17 0.156434 -0.987688,
+                          -1.52965e-16 0.707107 -0.707107,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -2.13662e-16 0.987688 -0.156434,
+                          -2.13662e-16 0.987688 -0.156434,
+                          -1.92747e-16 0.891007 0.45399,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -2.13662e-16 0.987688 -0.156434,
+                          -1.52965e-16 0.707107 -0.707107,
+                          -2.13662e-16 0.987688 -0.156434,
+                          -1.92747e-16 0.891007 0.45399,
+                          -1.92747e-16 0.891007 0.45399,
+                          -9.82097e-17 0.45399 0.891007,
+                          -2.13662e-16 0.987688 -0.156434,
+                          -1.92747e-16 0.891007 0.45399,
+                          -1.92747e-16 0.891007 0.45399,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -9.82097e-17 0.45399 0.891007,
+                          -9.82097e-17 0.45399 0.891007,
+                          3.38408e-17 -0.156434 0.987688,
+                          -1.92747e-16 0.891007 0.45399,
+                          -9.82097e-17 0.45399 0.891007,
+                          -9.82097e-17 0.45399 0.891007,
+                          3.38408e-17 -0.156434 0.987688,
+                          3.38408e-17 -0.156434 0.987688,
+                          1.52965e-16 -0.707107 0.707107,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -9.82097e-17 0.45399 0.891007,
+                          3.38408e-17 -0.156434 0.987688,
+                          3.38408e-17 -0.156434 0.987688,
+                          1.52965e-16 -0.707107 0.707107,
+                          1.52965e-16 -0.707107 0.707107,
+                          2.13662e-16 -0.987688 0.156434,
+                          3.38408e-17 -0.156434 0.987688,
+                          1.52965e-16 -0.707107 0.707107,
+                          1.52965e-16 -0.707107 0.707107,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          -1 -2.16325e-16 0,
+                          2.13662e-16 -0.987688 0.156434,
+                          2.13662e-16 -0.987688 0.156434,
+                          1.92747e-16 -0.891007 -0.45399,
+                          2.13662e-16 -0.987688 0.156434,
+                          1.52965e-16 -0.707107 0.707107,
+                          2.13662e-16 -0.987688 0.156434,
+                          1.92747e-16 -0.891007 -0.45399,
+                          1.92747e-16 -0.891007 -0.45399,
+                          9.82097e-17 -0.45399 -0.891007,
+                          1.92747e-16 -0.891007 -0.45399,
+                          2.13662e-16 -0.987688 0.156434,
+                          1.92747e-16 -0.891007 -0.45399,
+                          9.82097e-17 -0.45399 -0.891007,
+                          9.82097e-17 -0.45399 -0.891007,
+                          -3.38408e-17 0.156434 -0.987688,
+                          9.82097e-17 -0.45399 -0.891007,
+                          1.92747e-16 -0.891007 -0.45399,
+                          9.82097e-17 -0.45399 -0.891007,
+                          -3.38408e-17 0.156434 -0.987688,
+                          9.82097e-17 -0.45399 -0.891007,
+                          -3.38408e-17 0.156434 -0.987688,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0,
+                          1 2.16325e-16 0 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -116 110.549 441.217,
+                          -116 109.5 446,
+                          -116 106.425 438.575,
+                          -140 106.425 438.575,
+                          -116 106.425 438.575,
+                          -116 109.5 446,
+                          -116 107.839 437.161,
+                          -116 106.425 438.575,
+                          -116 99 435.5,
+                          -140 99 435.5,
+                          -116 99 435.5,
+                          -116 106.425 438.575,
+                          -116 110.549 441.217,
+                          -116 106.425 438.575,
+                          -116 107.839 437.161,
+                          -140 106.425 438.575,
+                          -140 99 435.5,
+                          -116 106.425 438.575,
+                          -116 111.5 446,
+                          -116 106.425 453.425,
+                          -116 109.5 446,
+                          -140 109.5 446,
+                          -116 109.5 446,
+                          -116 106.425 453.425,
+                          -116 110.549 441.217,
+                          -116 111.5 446,
+                          -116 109.5 446,
+                          -140 109.5 446,
+                          -140 106.425 438.575,
+                          -116 109.5 446,
+                          -116 99.0005 458.5,
+                          -116 99 456.5,
+                          -116 106.425 453.425,
+                          -140 106.425 453.425,
+                          -116 106.425 453.425,
+                          -116 99 456.5,
+                          -116 110.548 450.784,
+                          -116 99.0005 458.5,
+                          -116 106.425 453.425,
+                          -116 111.5 446,
+                          -116 110.548 450.784,
+                          -116 106.425 453.425,
+                          -140 109.5 446,
+                          -116 106.425 453.425,
+                          -140 106.425 453.425,
+                          -116 90.1612 454.839,
+                          -116 91.5754 453.425,
+                          -116 99 456.5,
+                          -140 99 456.5,
+                          -116 99 456.5,
+                          -116 91.5754 453.425,
+                          -116 94.2169 457.549,
+                          -116 90.1612 454.839,
+                          -116 99 456.5,
+                          -116 99.0005 458.5,
+                          -116 94.2169 457.549,
+                          -116 99 456.5,
+                          -140 106.425 453.425,
+                          -116 99 456.5,
+                          -140 99 456.5,
+                          -116 87.4514 450.783,
+                          -116 88.5001 446,
+                          -116 91.5754 453.425,
+                          -140 91.5754 453.425,
+                          -116 91.5754 453.425,
+                          -116 88.5001 446,
+                          -116 90.1612 454.839,
+                          -116 87.4514 450.783,
+                          -116 91.5754 453.425,
+                          -140 99 456.5,
+                          -116 91.5754 453.425,
+                          -140 91.5754 453.425,
+                          -116 86.5001 446,
+                          -116 91.5754 438.575,
+                          -116 88.5001 446,
+                          -140 88.5001 446,
+                          -116 88.5001 446,
+                          -116 91.5754 438.575,
+                          -116 87.4514 450.783,
+                          -116 86.5001 446,
+                          -116 88.5001 446,
+                          -140 88.5001 446,
+                          -140 91.5754 453.425,
+                          -116 88.5001 446,
+                          -116 98.9995 433.5,
+                          -116 99 435.5,
+                          -116 91.5754 438.575,
+                          -140 91.5754 438.575,
+                          -116 91.5754 438.575,
+                          -116 99 435.5,
+                          -116 87.4517 441.216,
+                          -116 98.9995 433.5,
+                          -116 91.5754 438.575,
+                          -116 86.5001 446,
+                          -116 87.4517 441.216,
+                          -116 91.5754 438.575,
+                          -140 91.5754 438.575,
+                          -140 88.5001 446,
+                          -116 91.5754 438.575,
+                          -116 103.783 434.451,
+                          -116 107.839 437.161,
+                          -116 99 435.5,
+                          -116 98.9995 433.5,
+                          -116 103.783 434.451,
+                          -116 99 435.5,
+                          -140 99 435.5,
+                          -140 91.5754 438.575,
+                          -116 99 435.5,
+                          -118 107.839 437.161,
+                          -116 107.839 437.161,
+                          -116 103.783 434.451,
+                          -118 110.549 441.217,
+                          -116 110.549 441.217,
+                          -116 107.839 437.161,
+                          -118 110.549 441.217,
+                          -116 107.839 437.161,
+                          -118 107.839 437.161,
+                          -118 103.783 434.451,
+                          -116 103.783 434.451,
+                          -116 98.9995 433.5,
+                          -118 103.783 434.451,
+                          -118 107.839 437.161,
+                          -116 103.783 434.451,
+                          -116 87.4517 441.216,
+                          -116 94.2162 434.452,
+                          -116 98.9995 433.5,
+                          -118 98.9995 433.5,
+                          -116 98.9995 433.5,
+                          -116 94.2162 434.452,
+                          -118 103.783 434.451,
+                          -116 98.9995 433.5,
+                          -118 98.9995 433.5,
+                          -116 87.4517 441.216,
+                          -116 90.1612 437.161,
+                          -116 94.2162 434.452,
+                          -118 94.2162 434.452,
+                          -116 94.2162 434.452,
+                          -116 90.1612 437.161,
+                          -118 98.9995 433.5,
+                          -116 94.2162 434.452,
+                          -118 94.2162 434.452,
+                          -118 90.1612 437.161,
+                          -116 90.1612 437.161,
+                          -116 87.4517 441.216,
+                          -118 94.2162 434.452,
+                          -116 90.1612 437.161,
+                          -118 90.1612 437.161,
+                          -118 87.4517 441.216,
+                          -116 87.4517 441.216,
+                          -116 86.5001 446,
+                          -118 90.1612 437.161,
+                          -116 87.4517 441.216,
+                          -118 87.4517 441.216,
+                          -118 86.5001 446,
+                          -116 86.5001 446,
+                          -116 87.4514 450.783,
+                          -118 87.4517 441.216,
+                          -116 86.5001 446,
+                          -118 86.5001 446,
+                          -118 87.4514 450.783,
+                          -116 87.4514 450.783,
+                          -116 90.1612 454.839,
+                          -118 86.5001 446,
+                          -116 87.4514 450.783,
+                          -118 87.4514 450.783,
+                          -118 90.1612 454.839,
+                          -116 90.1612 454.839,
+                          -116 94.2169 457.549,
+                          -118 87.4514 450.783,
+                          -116 90.1612 454.839,
+                          -118 90.1612 454.839,
+                          -118 94.2169 457.549,
+                          -116 94.2169 457.549,
+                          -116 99.0005 458.5,
+                          -118 90.1612 454.839,
+                          -116 94.2169 457.549,
+                          -118 94.2169 457.549,
+                          -116 110.548 450.784,
+                          -116 103.784 457.548,
+                          -116 99.0005 458.5,
+                          -118 99.0005 458.5,
+                          -116 99.0005 458.5,
+                          -116 103.784 457.548,
+                          -118 94.2169 457.549,
+                          -116 99.0005 458.5,
+                          -118 99.0005 458.5,
+                          -116 110.548 450.784,
+                          -116 107.839 454.839,
+                          -116 103.784 457.548,
+                          -118 103.784 457.548,
+                          -116 103.784 457.548,
+                          -116 107.839 454.839,
+                          -118 99.0005 458.5,
+                          -116 103.784 457.548,
+                          -118 103.784 457.548,
+                          -118 107.839 454.839,
+                          -116 107.839 454.839,
+                          -116 110.548 450.784,
+                          -118 103.784 457.548,
+                          -116 107.839 454.839,
+                          -118 107.839 454.839,
+                          -118 110.548 450.784,
+                          -116 110.548 450.784,
+                          -116 111.5 446,
+                          -118 107.839 454.839,
+                          -116 110.548 450.784,
+                          -118 110.548 450.784,
+                          -118 111.5 446,
+                          -116 111.5 446,
+                          -116 110.549 441.217,
+                          -118 110.548 450.784,
+                          -116 111.5 446,
+                          -118 111.5 446,
+                          -118 111.5 446,
+                          -116 110.549 441.217,
+                          -118 110.549 441.217,
+                          -140 90.1612 454.839,
+                          -140 91.5754 453.425,
+                          -140 88.5001 446,
+                          -140 90.1612 454.839,
+                          -140 99.0005 458.5,
+                          -140 91.5754 453.425,
+                          -140 99 456.5,
+                          -140 91.5754 453.425,
+                          -140 99.0005 458.5,
+                          -140 86.5001 446,
+                          -140 88.5001 446,
+                          -140 91.5754 438.575,
+                          -140 86.5001 446,
+                          -140 90.1612 454.839,
+                          -140 88.5001 446,
+                          -140 98.9995 433.5,
+                          -140 91.5754 438.575,
+                          -140 99 435.5,
+                          -140 90.1612 437.161,
+                          -140 86.5001 446,
+                          -140 91.5754 438.575,
+                          -140 98.9995 433.5,
+                          -140 90.1612 437.161,
+                          -140 91.5754 438.575,
+                          -140 98.9995 433.5,
+                          -140 99 435.5,
+                          -140 106.425 438.575,
+                          -140 98.9995 433.5,
+                          -140 106.425 438.575,
+                          -140 107.839 437.161,
+                          -140 109.5 446,
+                          -140 107.839 437.161,
+                          -140 106.425 438.575,
+                          -140 109.5 446,
+                          -140 111.5 446,
+                          -140 107.839 437.161,
+                          -140 108.899 436.1,
+                          -140 107.839 437.161,
+                          -140 111.5 446,
+                          -140 101.19 432.172,
+                          -140 98.9995 433.5,
+                          -140 107.839 437.161,
+                          -140 101.19 432.172,
+                          -140 107.839 437.161,
+                          -140 108.899 436.1,
+                          -140 106.425 453.425,
+                          -140 107.839 454.839,
+                          -140 111.5 446,
+                          -140 112.828 443.81,
+                          -140 111.5 446,
+                          -140 107.839 454.839,
+                          -140 109.5 446,
+                          -140 106.425 453.425,
+                          -140 111.5 446,
+                          -140 112.828 443.81,
+                          -140 108.899 436.1,
+                          -140 111.5 446,
+                          -140 106.425 453.425,
+                          -140 99.0005 458.5,
+                          -140 107.839 454.839,
+                          -140 105.356 458.474,
+                          -140 107.839 454.839,
+                          -140 99.0005 458.5,
+                          -140 111.474 452.356,
+                          -140 112.828 443.81,
+                          -140 107.839 454.839,
+                          -140 105.356 458.474,
+                          -140 111.474 452.356,
+                          -140 107.839 454.839,
+                          -140 96.8104 459.828,
+                          -140 99.0005 458.5,
+                          -140 90.1612 454.839,
+                          -140 106.425 453.425,
+                          -140 99 456.5,
+                          -140 99.0005 458.5,
+                          -140 96.8104 459.828,
+                          -140 105.356 458.474,
+                          -140 99.0005 458.5,
+                          -140 89.1005 455.9,
+                          -140 90.1612 454.839,
+                          -140 86.5001 446,
+                          -140 96.8104 459.828,
+                          -140 90.1612 454.839,
+                          -140 89.1005 455.9,
+                          -140 85.1723 448.19,
+                          -140 86.5001 446,
+                          -140 90.1612 437.161,
+                          -140 89.1005 455.9,
+                          -140 86.5001 446,
+                          -140 85.1723 448.19,
+                          -140 92.644 433.526,
+                          -140 90.1612 437.161,
+                          -140 98.9995 433.5,
+                          -140 86.5261 439.644,
+                          -140 90.1612 437.161,
+                          -140 92.644 433.526,
+                          -140 85.1723 448.19,
+                          -140 90.1612 437.161,
+                          -140 86.5261 439.644,
+                          -140 92.644 433.526,
+                          -140 98.9995 433.5,
+                          -140 101.19 432.172,
+                          -135 101.19 432.172,
+                          -140 101.19 432.172,
+                          -140 108.899 436.1,
+                          -135 108.899 436.1,
+                          -135 101.19 432.172,
+                          -140 108.899 436.1,
+                          -140 112.828 443.81,
+                          -135 108.899 436.1,
+                          -140 108.899 436.1,
+                          -135 92.644 433.526,
+                          -140 92.644 433.526,
+                          -140 101.19 432.172,
+                          -135 101.19 432.172,
+                          -135 92.644 433.526,
+                          -140 101.19 432.172,
+                          -135 86.5261 439.644,
+                          -140 86.5261 439.644,
+                          -140 92.644 433.526,
+                          -135 92.644 433.526,
+                          -135 86.5261 439.644,
+                          -140 92.644 433.526,
+                          -135 85.1723 448.19,
+                          -140 85.1723 448.19,
+                          -140 86.5261 439.644,
+                          -135 86.5261 439.644,
+                          -135 85.1723 448.19,
+                          -140 86.5261 439.644,
+                          -135 89.1005 455.9,
+                          -140 89.1005 455.9,
+                          -140 85.1723 448.19,
+                          -135 85.1723 448.19,
+                          -135 89.1005 455.9,
+                          -140 85.1723 448.19,
+                          -135 96.8104 459.828,
+                          -140 89.1005 455.9,
+                          -135 89.1005 455.9,
+                          -140 96.8104 459.828,
+                          -140 89.1005 455.9,
+                          -135 96.8104 459.828,
+                          -135 90.8683 454.132,
+                          -135 89.1005 455.9,
+                          -135 85.1723 448.19,
+                          -135 90.8683 454.132,
+                          -135 99 457.5,
+                          -135 89.1005 455.9,
+                          -135 96.8104 459.828,
+                          -135 89.1005 455.9,
+                          -135 99 457.5,
+                          -135 90.8683 437.868,
+                          -135 85.1723 448.19,
+                          -135 86.5261 439.644,
+                          -135 87.5001 446,
+                          -135 90.8683 454.132,
+                          -135 85.1723 448.19,
+                          -135 90.8683 437.868,
+                          -135 87.5001 446,
+                          -135 85.1723 448.19,
+                          -135 101.19 432.172,
+                          -135 86.5261 439.644,
+                          -135 92.644 433.526,
+                          -135 90.8683 437.868,
+                          -135 86.5261 439.644,
+                          -135 101.19 432.172,
+                          -135 99 434.5,
+                          -135 101.19 432.172,
+                          -135 108.899 436.1,
+                          -135 99 434.5,
+                          -135 90.8683 437.868,
+                          -135 101.19 432.172,
+                          -135 99 434.5,
+                          -135 108.899 436.1,
+                          -135 107.132 437.868,
+                          -135 112.828 443.81,
+                          -135 107.132 437.868,
+                          -135 108.899 436.1,
+                          -140 112.828 443.81,
+                          -135 112.828 443.81,
+                          -135 108.899 436.1,
+                          -135 112.828 443.81,
+                          -135 110.5 446,
+                          -135 107.132 437.868,
+                          -120 107.132 437.868,
+                          -135 107.132 437.868,
+                          -135 110.5 446,
+                          -120 99 434.5,
+                          -135 99 434.5,
+                          -135 107.132 437.868,
+                          -120 107.132 437.868,
+                          -120 99 434.5,
+                          -135 107.132 437.868,
+                          -135 112.828 443.81,
+                          -135 107.132 454.132,
+                          -135 110.5 446,
+                          -120 110.5 446,
+                          -135 110.5 446,
+                          -135 107.132 454.132,
+                          -120 110.5 446,
+                          -120 107.132 437.868,
+                          -135 110.5 446,
+                          -135 96.8104 459.828,
+                          -135 99 457.5,
+                          -135 107.132 454.132,
+                          -120 107.132 454.132,
+                          -135 107.132 454.132,
+                          -135 99 457.5,
+                          -135 111.474 452.356,
+                          -135 96.8104 459.828,
+                          -135 107.132 454.132,
+                          -135 112.828 443.81,
+                          -135 111.474 452.356,
+                          -135 107.132 454.132,
+                          -120 110.5 446,
+                          -135 107.132 454.132,
+                          -120 107.132 454.132,
+                          -120 99 457.5,
+                          -135 99 457.5,
+                          -135 90.8683 454.132,
+                          -120 107.132 454.132,
+                          -135 99 457.5,
+                          -120 99 457.5,
+                          -120 90.8683 454.132,
+                          -135 90.8683 454.132,
+                          -135 87.5001 446,
+                          -120 99 457.5,
+                          -135 90.8683 454.132,
+                          -120 90.8683 454.132,
+                          -120 87.5001 446,
+                          -135 87.5001 446,
+                          -135 90.8683 437.868,
+                          -120 87.5001 446,
+                          -120 90.8683 454.132,
+                          -135 87.5001 446,
+                          -120 90.8683 437.868,
+                          -135 90.8683 437.868,
+                          -135 99 434.5,
+                          -120 90.8683 437.868,
+                          -120 87.5001 446,
+                          -135 90.8683 437.868,
+                          -120 99 434.5,
+                          -120 90.8683 437.868,
+                          -135 99 434.5,
+                          -135 111.474 452.356,
+                          -135 105.356 458.474,
+                          -135 96.8104 459.828,
+                          -140 96.8104 459.828,
+                          -135 96.8104 459.828,
+                          -135 105.356 458.474,
+                          -140 105.356 458.474,
+                          -135 105.356 458.474,
+                          -135 111.474 452.356,
+                          -140 96.8104 459.828,
+                          -135 105.356 458.474,
+                          -140 105.356 458.474,
+                          -140 111.474 452.356,
+                          -135 111.474 452.356,
+                          -135 112.828 443.81,
+                          -140 105.356 458.474,
+                          -135 111.474 452.356,
+                          -140 111.474 452.356,
+                          -140 111.474 452.356,
+                          -135 112.828 443.81,
+                          -140 112.828 443.81,
+                          -120 85.565 459.435,
+                          -120 90.8683 454.132,
+                          -120 87.5001 446,
+                          -120 85.565 459.435,
+                          -120 96.0275 464.766,
+                          -120 90.8683 454.132,
+                          -120 99 457.5,
+                          -120 90.8683 454.132,
+                          -120 96.0275 464.766,
+                          -120 80.234 448.972,
+                          -120 87.5001 446,
+                          -120 90.8683 437.868,
+                          -120 80.234 448.972,
+                          -120 85.565 459.435,
+                          -120 87.5001 446,
+                          -120 101.972 427.234,
+                          -120 90.8683 437.868,
+                          -120 99 434.5,
+                          -120 90.3738 429.071,
+                          -120 80.234 448.972,
+                          -120 90.8683 437.868,
+                          -120 101.972 427.234,
+                          -120 90.3738 429.071,
+                          -120 90.8683 437.868,
+                          -120 101.972 427.234,
+                          -120 99 434.5,
+                          -120 107.132 437.868,
+                          -120 101.972 427.234,
+                          -120 107.132 437.868,
+                          -120 112.435 432.565,
+                          -120 110.5 446,
+                          -120 112.435 432.565,
+                          -120 107.132 437.868,
+                          -120 110.5 446,
+                          -120 117.766 443.028,
+                          -120 112.435 432.565,
+                          -118 112.435 432.565,
+                          -120 112.435 432.565,
+                          -120 117.766 443.028,
+                          -118 101.972 427.234,
+                          -120 101.972 427.234,
+                          -120 112.435 432.565,
+                          -118 112.435 432.565,
+                          -118 101.972 427.234,
+                          -120 112.435 432.565,
+                          -120 107.626 462.929,
+                          -120 115.929 454.626,
+                          -120 117.766 443.028,
+                          -118 117.766 443.028,
+                          -120 117.766 443.028,
+                          -120 115.929 454.626,
+                          -120 107.132 454.132,
+                          -120 107.626 462.929,
+                          -120 117.766 443.028,
+                          -120 110.5 446,
+                          -120 107.132 454.132,
+                          -120 117.766 443.028,
+                          -118 117.766 443.028,
+                          -118 112.435 432.565,
+                          -120 117.766 443.028,
+                          -118 115.929 454.626,
+                          -120 115.929 454.626,
+                          -120 107.626 462.929,
+                          -118 117.766 443.028,
+                          -120 115.929 454.626,
+                          -118 115.929 454.626,
+                          -120 107.132 454.132,
+                          -120 96.0275 464.766,
+                          -120 107.626 462.929,
+                          -118 107.626 462.929,
+                          -120 107.626 462.929,
+                          -120 96.0275 464.766,
+                          -118 115.929 454.626,
+                          -120 107.626 462.929,
+                          -118 107.626 462.929,
+                          -118 96.0275 464.766,
+                          -120 96.0275 464.766,
+                          -120 85.565 459.435,
+                          -120 107.132 454.132,
+                          -120 99 457.5,
+                          -120 96.0275 464.766,
+                          -118 107.626 462.929,
+                          -120 96.0275 464.766,
+                          -118 96.0275 464.766,
+                          -118 85.565 459.435,
+                          -120 85.565 459.435,
+                          -120 80.234 448.972,
+                          -118 96.0275 464.766,
+                          -120 85.565 459.435,
+                          -118 85.565 459.435,
+                          -120 90.3738 429.071,
+                          -120 82.0711 437.374,
+                          -120 80.234 448.972,
+                          -118 80.234 448.972,
+                          -120 80.234 448.972,
+                          -120 82.0711 437.374,
+                          -118 80.234 448.972,
+                          -118 85.565 459.435,
+                          -120 80.234 448.972,
+                          -118 82.0711 437.374,
+                          -120 82.0711 437.374,
+                          -120 90.3738 429.071,
+                          -118 82.0711 437.374,
+                          -118 80.234 448.972,
+                          -120 82.0711 437.374,
+                          -118 90.3738 429.071,
+                          -120 90.3738 429.071,
+                          -120 101.972 427.234,
+                          -118 90.3738 429.071,
+                          -118 82.0711 437.374,
+                          -120 90.3738 429.071,
+                          -118 101.972 427.234,
+                          -118 90.3738 429.071,
+                          -120 101.972 427.234,
+                          -118 90.1612 454.839,
+                          -118 85.565 459.435,
+                          -118 80.234 448.972,
+                          -118 94.2169 457.549,
+                          -118 99.0005 458.5,
+                          -118 85.565 459.435,
+                          -118 96.0275 464.766,
+                          -118 85.565 459.435,
+                          -118 99.0005 458.5,
+                          -118 90.1612 454.839,
+                          -118 94.2169 457.549,
+                          -118 85.565 459.435,
+                          -118 87.4517 441.216,
+                          -118 80.234 448.972,
+                          -118 82.0711 437.374,
+                          -118 87.4514 450.783,
+                          -118 90.1612 454.839,
+                          -118 80.234 448.972,
+                          -118 86.5001 446,
+                          -118 87.4514 450.783,
+                          -118 80.234 448.972,
+                          -118 87.4517 441.216,
+                          -118 86.5001 446,
+                          -118 80.234 448.972,
+                          -118 101.972 427.234,
+                          -118 82.0711 437.374,
+                          -118 90.3738 429.071,
+                          -118 90.1612 437.161,
+                          -118 82.0711 437.374,
+                          -118 101.972 427.234,
+                          -118 90.1612 437.161,
+                          -118 87.4517 441.216,
+                          -118 82.0711 437.374,
+                          -118 98.9995 433.5,
+                          -118 101.972 427.234,
+                          -118 112.435 432.565,
+                          -118 94.2162 434.452,
+                          -118 90.1612 437.161,
+                          -118 101.972 427.234,
+                          -118 98.9995 433.5,
+                          -118 94.2162 434.452,
+                          -118 101.972 427.234,
+                          -118 103.783 434.451,
+                          -118 112.435 432.565,
+                          -118 107.839 437.161,
+                          -118 117.766 443.028,
+                          -118 107.839 437.161,
+                          -118 112.435 432.565,
+                          -118 103.783 434.451,
+                          -118 98.9995 433.5,
+                          -118 112.435 432.565,
+                          -118 117.766 443.028,
+                          -118 110.549 441.217,
+                          -118 107.839 437.161,
+                          -118 117.766 443.028,
+                          -118 111.5 446,
+                          -118 110.549 441.217,
+                          -118 117.766 443.028,
+                          -118 110.548 450.784,
+                          -118 111.5 446,
+                          -118 115.929 454.626,
+                          -118 107.839 454.839,
+                          -118 110.548 450.784,
+                          -118 117.766 443.028,
+                          -118 115.929 454.626,
+                          -118 110.548 450.784,
+                          -118 96.0275 464.766,
+                          -118 103.784 457.548,
+                          -118 107.839 454.839,
+                          -118 115.929 454.626,
+                          -118 96.0275 464.766,
+                          -118 107.839 454.839,
+                          -118 96.0275 464.766,
+                          -118 99.0005 458.5,
+                          -118 103.784 457.548,
+                          -118 115.929 454.626,
+                          -118 107.626 462.929,
+                          -118 96.0275 464.766 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1.39941e-14 0.707107 0.707107,
+                          1.39941e-14 0.707107 0.707107,
+                          1.65354e-14 -8.88178e-16 1,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          3.25529e-15 1 9.99201e-16,
+                          3.25529e-15 1 9.99201e-16,
+                          1.39941e-14 0.707107 0.707107,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1.39941e-14 0.707107 0.707107,
+                          3.25529e-15 1 9.99201e-16,
+                          1.39941e-14 0.707107 0.707107,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1.65354e-14 -8.88178e-16 1,
+                          1.65354e-14 -8.88178e-16 1,
+                          9.39044e-15 -0.707107 0.707107,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1.65354e-14 -8.88178e-16 1,
+                          1.39941e-14 0.707107 0.707107,
+                          1.65354e-14 -8.88178e-16 1,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          9.39044e-15 -0.707107 0.707107,
+                          9.39044e-15 -0.707107 0.707107,
+                          -3.25529e-15 -1 -7.77156e-16,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1.65354e-14 -8.88178e-16 1,
+                          9.39044e-15 -0.707107 0.707107,
+                          9.39044e-15 -0.707107 0.707107,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          -3.25529e-15 -1 -7.77156e-16,
+                          -3.25529e-15 -1 -7.77156e-16,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          9.39044e-15 -0.707107 0.707107,
+                          -3.25529e-15 -1 -7.77156e-16,
+                          -3.25529e-15 -1 -7.77156e-16,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          -1.65354e-14 9.99201e-16 -1,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          -3.25529e-15 -1 -7.77156e-16,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          -1.65354e-14 9.99201e-16 -1,
+                          -1.65354e-14 9.99201e-16 -1,
+                          -9.39044e-15 0.707107 -0.707107,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          -1.65354e-14 9.99201e-16 -1,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          -1.65354e-14 9.99201e-16 -1,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          -9.39044e-15 0.707107 -0.707107,
+                          -9.39044e-15 0.707107 -0.707107,
+                          3.25529e-15 1 9.99201e-16,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          -9.39044e-15 0.707107 -0.707107,
+                          -1.65354e-14 9.99201e-16 -1,
+                          -9.39044e-15 0.707107 -0.707107,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          3.25529e-15 1 9.99201e-16,
+                          -9.39044e-15 0.707107 -0.707107,
+                          3.25529e-15 1 9.99201e-16,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          -9.33531e-15 -0.92388 -0.382683,
+                          -1.65224e-14 -0.382683 -0.92388,
+                          -1.65224e-14 -0.382683 -0.92388,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          -1.65224e-14 -0.382683 -0.92388,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          -9.33531e-15 -0.92388 -0.382683,
+                          -9.33531e-15 -0.92388 -0.382683,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          -9.33531e-15 -0.92388 -0.382683,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          -9.33531e-15 -0.92388 -0.382683,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          3.32032e-15 -0.92388 0.382683,
+                          -9.33531e-15 -0.92388 -0.382683,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          3.32032e-15 -0.92388 0.382683,
+                          3.32032e-15 -0.92388 0.382683,
+                          9.39044e-15 -0.707107 0.707107,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          3.32032e-15 -0.92388 0.382683,
+                          3.32032e-15 -0.92388 0.382683,
+                          9.39044e-15 -0.707107 0.707107,
+                          9.39044e-15 -0.707107 0.707107,
+                          1.4031e-14 -0.382683 0.92388,
+                          3.32032e-15 -0.92388 0.382683,
+                          9.39044e-15 -0.707107 0.707107,
+                          9.39044e-15 -0.707107 0.707107,
+                          1.4031e-14 -0.382683 0.92388,
+                          1.4031e-14 -0.382683 0.92388,
+                          1.65354e-14 -9.99201e-16 1,
+                          9.39044e-15 -0.707107 0.707107,
+                          1.4031e-14 -0.382683 0.92388,
+                          1.4031e-14 -0.382683 0.92388,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65224e-14 0.382683 0.92388,
+                          1.4031e-14 -0.382683 0.92388,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65224e-14 0.382683 0.92388,
+                          1.65224e-14 0.382683 0.92388,
+                          1.39941e-14 0.707107 0.707107,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65224e-14 0.382683 0.92388,
+                          1.65224e-14 0.382683 0.92388,
+                          1.39941e-14 0.707107 0.707107,
+                          1.39941e-14 0.707107 0.707107,
+                          9.33531e-15 0.92388 0.382683,
+                          1.65224e-14 0.382683 0.92388,
+                          1.39941e-14 0.707107 0.707107,
+                          1.39941e-14 0.707107 0.707107,
+                          9.33531e-15 0.92388 0.382683,
+                          9.33531e-15 0.92388 0.382683,
+                          3.25529e-15 1 -5.55112e-17,
+                          1.39941e-14 0.707107 0.707107,
+                          9.33531e-15 0.92388 0.382683,
+                          9.33531e-15 0.92388 0.382683,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          3.25529e-15 1 -5.55112e-17,
+                          3.25529e-15 1 -5.55112e-17,
+                          -3.32032e-15 0.92388 -0.382683,
+                          9.33531e-15 0.92388 0.382683,
+                          3.25529e-15 1 -5.55112e-17,
+                          3.25529e-15 1 -5.55112e-17,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          -3.32032e-15 0.92388 -0.382683,
+                          -3.32032e-15 0.92388 -0.382683,
+                          -9.39044e-15 0.707107 -0.707107,
+                          3.25529e-15 1 -5.55112e-17,
+                          -3.32032e-15 0.92388 -0.382683,
+                          -3.32032e-15 0.92388 -0.382683,
+                          -9.39044e-15 0.707107 -0.707107,
+                          -9.39044e-15 0.707107 -0.707107,
+                          -1.4031e-14 0.382683 -0.92388,
+                          -3.32032e-15 0.92388 -0.382683,
+                          -9.39044e-15 0.707107 -0.707107,
+                          -9.39044e-15 0.707107 -0.707107,
+                          -1.4031e-14 0.382683 -0.92388,
+                          -1.4031e-14 0.382683 -0.92388,
+                          -1.65354e-14 8.88178e-16 -1,
+                          -9.39044e-15 0.707107 -0.707107,
+                          -1.4031e-14 0.382683 -0.92388,
+                          -1.4031e-14 0.382683 -0.92388,
+                          -1.65354e-14 8.88178e-16 -1,
+                          -1.65354e-14 8.88178e-16 -1,
+                          -1.65224e-14 -0.382683 -0.92388,
+                          -1.4031e-14 0.382683 -0.92388,
+                          -1.65354e-14 8.88178e-16 -1,
+                          -1.65354e-14 8.88178e-16 -1,
+                          -1.65354e-14 8.88178e-16 -1,
+                          -1.65224e-14 -0.382683 -0.92388,
+                          -1.65224e-14 -0.382683 -0.92388,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -5.80192e-15 -0.987688 -0.156434,
+                          -5.80192e-15 -0.987688 -0.156434,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          -5.80192e-15 -0.987688 -0.156434,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          -1.6841e-14 -0.156434 -0.987688,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          4.60642e-15 -0.891007 0.45399,
+                          4.60642e-15 -0.891007 0.45399,
+                          -5.80192e-15 -0.987688 -0.156434,
+                          -5.80192e-15 -0.987688 -0.156434,
+                          4.60642e-15 -0.891007 0.45399,
+                          -5.80192e-15 -0.987688 -0.156434,
+                          1.32553e-14 -0.45399 0.891007,
+                          1.32553e-14 -0.45399 0.891007,
+                          4.60642e-15 -0.891007 0.45399,
+                          4.60642e-15 -0.891007 0.45399,
+                          1.32553e-14 -0.45399 0.891007,
+                          4.60642e-15 -0.891007 0.45399,
+                          1.6841e-14 0.156434 0.987688,
+                          1.6841e-14 0.156434 0.987688,
+                          1.32553e-14 -0.45399 0.891007,
+                          1.32553e-14 -0.45399 0.891007,
+                          1.6841e-14 0.156434 0.987688,
+                          1.32553e-14 -0.45399 0.891007,
+                          1.39941e-14 0.707107 0.707107,
+                          1.39941e-14 0.707107 0.707107,
+                          1.6841e-14 0.156434 0.987688,
+                          1.6841e-14 0.156434 0.987688,
+                          1.39941e-14 0.707107 0.707107,
+                          1.6841e-14 0.156434 0.987688,
+                          5.80192e-15 0.987688 0.156434,
+                          1.39941e-14 0.707107 0.707107,
+                          1.39941e-14 0.707107 0.707107,
+                          5.80192e-15 0.987688 0.156434,
+                          1.39941e-14 0.707107 0.707107,
+                          5.80192e-15 0.987688 0.156434,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          -1.6841e-14 -0.156434 -0.987688,
+                          -1.6841e-14 -0.156434 -0.987688,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          -1.65354e-14 8.88178e-16 -1,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          -1.65354e-14 8.88178e-16 -1,
+                          -1.65354e-14 8.88178e-16 -1,
+                          -9.39044e-15 0.707107 -0.707107,
+                          -1.65354e-14 8.88178e-16 -1,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          -1.65354e-14 8.88178e-16 -1,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          -9.39044e-15 0.707107 -0.707107,
+                          -9.39044e-15 0.707107 -0.707107,
+                          3.25529e-15 1 7.77156e-16,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          -1.65354e-14 8.88178e-16 -1,
+                          -9.39044e-15 0.707107 -0.707107,
+                          -9.39044e-15 0.707107 -0.707107,
+                          3.25529e-15 1 7.77156e-16,
+                          3.25529e-15 1 7.77156e-16,
+                          1.39941e-14 0.707107 0.707107,
+                          -9.39044e-15 0.707107 -0.707107,
+                          3.25529e-15 1 7.77156e-16,
+                          3.25529e-15 1 7.77156e-16,
+                          1.39941e-14 0.707107 0.707107,
+                          1.39941e-14 0.707107 0.707107,
+                          1.65354e-14 -9.99201e-16 1,
+                          3.25529e-15 1 7.77156e-16,
+                          1.39941e-14 0.707107 0.707107,
+                          1.39941e-14 0.707107 0.707107,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.65354e-14 -9.99201e-16 1,
+                          9.39044e-15 -0.707107 0.707107,
+                          1.65354e-14 -9.99201e-16 1,
+                          1.39941e-14 0.707107 0.707107,
+                          1.65354e-14 -9.99201e-16 1,
+                          9.39044e-15 -0.707107 0.707107,
+                          9.39044e-15 -0.707107 0.707107,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          9.39044e-15 -0.707107 0.707107,
+                          1.65354e-14 -9.99201e-16 1,
+                          9.39044e-15 -0.707107 0.707107,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          9.39044e-15 -0.707107 0.707107,
+                          -3.25529e-15 -1 -9.99201e-16,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          5.80192e-15 0.987688 0.156434,
+                          5.80192e-15 0.987688 0.156434,
+                          -4.60642e-15 0.891007 -0.45399,
+                          -4.60642e-15 0.891007 -0.45399,
+                          -4.60642e-15 0.891007 -0.45399,
+                          -1.32553e-14 0.45399 -0.891007,
+                          5.80192e-15 0.987688 0.156434,
+                          -4.60642e-15 0.891007 -0.45399,
+                          -4.60642e-15 0.891007 -0.45399,
+                          -1.32553e-14 0.45399 -0.891007,
+                          -1.32553e-14 0.45399 -0.891007,
+                          -1.6841e-14 -0.156434 -0.987688,
+                          -4.60642e-15 0.891007 -0.45399,
+                          -1.32553e-14 0.45399 -0.891007,
+                          -1.32553e-14 0.45399 -0.891007,
+                          -1.32553e-14 0.45399 -0.891007,
+                          -1.6841e-14 -0.156434 -0.987688,
+                          -1.6841e-14 -0.156434 -0.987688,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          -1.6841e-14 -0.156434 -0.987688,
+                          -5.80192e-15 -0.987688 -0.156434,
+                          -5.80192e-15 -0.987688 -0.156434,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          -5.80192e-15 -0.987688 -0.156434,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1.6841e-14 -0.156434 -0.987688,
+                          -1.6841e-14 -0.156434 -0.987688,
+                          -1.32553e-14 0.45399 -0.891007,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1.6841e-14 -0.156434 -0.987688,
+                          -1.39941e-14 -0.707107 -0.707107,
+                          -1.6841e-14 -0.156434 -0.987688,
+                          -1.32553e-14 0.45399 -0.891007,
+                          -1.32553e-14 0.45399 -0.891007,
+                          -4.60642e-15 0.891007 -0.45399,
+                          -1.6841e-14 -0.156434 -0.987688,
+                          -1.32553e-14 0.45399 -0.891007,
+                          -1.32553e-14 0.45399 -0.891007,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -4.60642e-15 0.891007 -0.45399,
+                          -4.60642e-15 0.891007 -0.45399,
+                          5.80192e-15 0.987688 0.156434,
+                          -1.32553e-14 0.45399 -0.891007,
+                          -4.60642e-15 0.891007 -0.45399,
+                          -4.60642e-15 0.891007 -0.45399,
+                          5.80192e-15 0.987688 0.156434,
+                          5.80192e-15 0.987688 0.156434,
+                          1.39941e-14 0.707107 0.707107,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -4.60642e-15 0.891007 -0.45399,
+                          5.80192e-15 0.987688 0.156434,
+                          5.80192e-15 0.987688 0.156434,
+                          1.39941e-14 0.707107 0.707107,
+                          1.39941e-14 0.707107 0.707107,
+                          1.6841e-14 0.156434 0.987688,
+                          5.80192e-15 0.987688 0.156434,
+                          1.39941e-14 0.707107 0.707107,
+                          1.39941e-14 0.707107 0.707107,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          -1 3.25529e-15 1.65354e-14,
+                          1.6841e-14 0.156434 0.987688,
+                          1.6841e-14 0.156434 0.987688,
+                          1.32553e-14 -0.45399 0.891007,
+                          1.6841e-14 0.156434 0.987688,
+                          1.39941e-14 0.707107 0.707107,
+                          1.6841e-14 0.156434 0.987688,
+                          1.32553e-14 -0.45399 0.891007,
+                          1.32553e-14 -0.45399 0.891007,
+                          4.60642e-15 -0.891007 0.45399,
+                          1.32553e-14 -0.45399 0.891007,
+                          1.6841e-14 0.156434 0.987688,
+                          1.32553e-14 -0.45399 0.891007,
+                          4.60642e-15 -0.891007 0.45399,
+                          4.60642e-15 -0.891007 0.45399,
+                          -5.80192e-15 -0.987688 -0.156434,
+                          4.60642e-15 -0.891007 0.45399,
+                          1.32553e-14 -0.45399 0.891007,
+                          4.60642e-15 -0.891007 0.45399,
+                          -5.80192e-15 -0.987688 -0.156434,
+                          4.60642e-15 -0.891007 0.45399,
+                          -5.80192e-15 -0.987688 -0.156434,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14,
+                          1 -3.25529e-15 -1.65354e-14 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -116 -103.783 434.451,
+                          -116 -99 435.5,
+                          -116 -106.425 438.575,
+                          -140 -106.425 438.575,
+                          -116 -106.425 438.575,
+                          -116 -99 435.5,
+                          -116 -107.839 437.161,
+                          -116 -106.425 438.575,
+                          -116 -109.5 446,
+                          -140 -109.5 446,
+                          -116 -109.5 446,
+                          -116 -106.425 438.575,
+                          -116 -103.783 434.451,
+                          -116 -106.425 438.575,
+                          -116 -107.839 437.161,
+                          -140 -106.425 438.575,
+                          -140 -109.5 446,
+                          -116 -106.425 438.575,
+                          -116 -98.9995 433.5,
+                          -116 -91.5754 438.575,
+                          -116 -99 435.5,
+                          -140 -99 435.5,
+                          -116 -99 435.5,
+                          -116 -91.5754 438.575,
+                          -116 -103.783 434.451,
+                          -116 -98.9995 433.5,
+                          -116 -99 435.5,
+                          -140 -99 435.5,
+                          -140 -106.425 438.575,
+                          -116 -99 435.5,
+                          -116 -86.5001 446,
+                          -116 -88.5001 446,
+                          -116 -91.5754 438.575,
+                          -140 -91.5754 438.575,
+                          -116 -91.5754 438.575,
+                          -116 -88.5001 446,
+                          -116 -94.2162 434.452,
+                          -116 -86.5001 446,
+                          -116 -91.5754 438.575,
+                          -116 -98.9995 433.5,
+                          -116 -94.2162 434.452,
+                          -116 -91.5754 438.575,
+                          -140 -99 435.5,
+                          -116 -91.5754 438.575,
+                          -140 -91.5754 438.575,
+                          -116 -90.1612 454.839,
+                          -116 -91.5754 453.425,
+                          -116 -88.5001 446,
+                          -140 -88.5001 446,
+                          -116 -88.5001 446,
+                          -116 -91.5754 453.425,
+                          -116 -87.4514 450.783,
+                          -116 -90.1612 454.839,
+                          -116 -88.5001 446,
+                          -116 -86.5001 446,
+                          -116 -87.4514 450.783,
+                          -116 -88.5001 446,
+                          -140 -91.5754 438.575,
+                          -116 -88.5001 446,
+                          -140 -88.5001 446,
+                          -116 -94.2169 457.549,
+                          -116 -99 456.5,
+                          -116 -91.5754 453.425,
+                          -140 -91.5754 453.425,
+                          -116 -91.5754 453.425,
+                          -116 -99 456.5,
+                          -116 -90.1612 454.839,
+                          -116 -94.2169 457.549,
+                          -116 -91.5754 453.425,
+                          -140 -88.5001 446,
+                          -116 -91.5754 453.425,
+                          -140 -91.5754 453.425,
+                          -116 -99.0005 458.5,
+                          -116 -106.425 453.425,
+                          -116 -99 456.5,
+                          -140 -99 456.5,
+                          -116 -99 456.5,
+                          -116 -106.425 453.425,
+                          -116 -94.2169 457.549,
+                          -116 -99.0005 458.5,
+                          -116 -99 456.5,
+                          -140 -99 456.5,
+                          -140 -91.5754 453.425,
+                          -116 -99 456.5,
+                          -116 -111.5 446,
+                          -116 -109.5 446,
+                          -116 -106.425 453.425,
+                          -140 -106.425 453.425,
+                          -116 -106.425 453.425,
+                          -116 -109.5 446,
+                          -116 -103.784 457.548,
+                          -116 -111.5 446,
+                          -116 -106.425 453.425,
+                          -116 -99.0005 458.5,
+                          -116 -103.784 457.548,
+                          -116 -106.425 453.425,
+                          -140 -106.425 453.425,
+                          -140 -99 456.5,
+                          -116 -106.425 453.425,
+                          -116 -110.549 441.217,
+                          -116 -107.839 437.161,
+                          -116 -109.5 446,
+                          -116 -111.5 446,
+                          -116 -110.549 441.217,
+                          -116 -109.5 446,
+                          -140 -109.5 446,
+                          -140 -106.425 453.425,
+                          -116 -109.5 446,
+                          -118 -107.839 437.161,
+                          -116 -107.839 437.161,
+                          -116 -110.549 441.217,
+                          -118 -103.783 434.451,
+                          -116 -103.783 434.451,
+                          -116 -107.839 437.161,
+                          -118 -103.783 434.451,
+                          -116 -107.839 437.161,
+                          -118 -107.839 437.161,
+                          -118 -110.549 441.217,
+                          -116 -110.549 441.217,
+                          -116 -111.5 446,
+                          -118 -110.549 441.217,
+                          -118 -107.839 437.161,
+                          -116 -110.549 441.217,
+                          -116 -103.784 457.548,
+                          -116 -110.548 450.784,
+                          -116 -111.5 446,
+                          -118 -111.5 446,
+                          -116 -111.5 446,
+                          -116 -110.548 450.784,
+                          -118 -110.549 441.217,
+                          -116 -111.5 446,
+                          -118 -111.5 446,
+                          -116 -103.784 457.548,
+                          -116 -107.839 454.839,
+                          -116 -110.548 450.784,
+                          -118 -110.548 450.784,
+                          -116 -110.548 450.784,
+                          -116 -107.839 454.839,
+                          -118 -111.5 446,
+                          -116 -110.548 450.784,
+                          -118 -110.548 450.784,
+                          -118 -107.839 454.839,
+                          -116 -107.839 454.839,
+                          -116 -103.784 457.548,
+                          -118 -110.548 450.784,
+                          -116 -107.839 454.839,
+                          -118 -107.839 454.839,
+                          -118 -103.784 457.548,
+                          -116 -103.784 457.548,
+                          -116 -99.0005 458.5,
+                          -118 -107.839 454.839,
+                          -116 -103.784 457.548,
+                          -118 -103.784 457.548,
+                          -118 -99.0005 458.5,
+                          -116 -99.0005 458.5,
+                          -116 -94.2169 457.549,
+                          -118 -103.784 457.548,
+                          -116 -99.0005 458.5,
+                          -118 -99.0005 458.5,
+                          -118 -94.2169 457.549,
+                          -116 -94.2169 457.549,
+                          -116 -90.1612 454.839,
+                          -118 -99.0005 458.5,
+                          -116 -94.2169 457.549,
+                          -118 -94.2169 457.549,
+                          -118 -90.1612 454.839,
+                          -116 -90.1612 454.839,
+                          -116 -87.4514 450.783,
+                          -118 -94.2169 457.549,
+                          -116 -90.1612 454.839,
+                          -118 -90.1612 454.839,
+                          -118 -87.4514 450.783,
+                          -116 -87.4514 450.783,
+                          -116 -86.5001 446,
+                          -118 -90.1612 454.839,
+                          -116 -87.4514 450.783,
+                          -118 -87.4514 450.783,
+                          -116 -94.2162 434.452,
+                          -116 -87.4517 441.216,
+                          -116 -86.5001 446,
+                          -118 -86.5001 446,
+                          -116 -86.5001 446,
+                          -116 -87.4517 441.216,
+                          -118 -87.4514 450.783,
+                          -116 -86.5001 446,
+                          -118 -86.5001 446,
+                          -116 -94.2162 434.452,
+                          -116 -90.1612 437.161,
+                          -116 -87.4517 441.216,
+                          -118 -87.4517 441.216,
+                          -116 -87.4517 441.216,
+                          -116 -90.1612 437.161,
+                          -118 -86.5001 446,
+                          -116 -87.4517 441.216,
+                          -118 -87.4517 441.216,
+                          -118 -90.1612 437.161,
+                          -116 -90.1612 437.161,
+                          -116 -94.2162 434.452,
+                          -118 -87.4517 441.216,
+                          -116 -90.1612 437.161,
+                          -118 -90.1612 437.161,
+                          -118 -94.2162 434.452,
+                          -116 -94.2162 434.452,
+                          -116 -98.9995 433.5,
+                          -118 -90.1612 437.161,
+                          -116 -94.2162 434.452,
+                          -118 -94.2162 434.452,
+                          -118 -98.9995 433.5,
+                          -116 -98.9995 433.5,
+                          -116 -103.783 434.451,
+                          -118 -94.2162 434.452,
+                          -116 -98.9995 433.5,
+                          -118 -98.9995 433.5,
+                          -118 -98.9995 433.5,
+                          -116 -103.783 434.451,
+                          -118 -103.783 434.451,
+                          -140 -90.1612 454.839,
+                          -140 -91.5754 453.425,
+                          -140 -99 456.5,
+                          -140 -90.1612 454.839,
+                          -140 -86.5001 446,
+                          -140 -91.5754 453.425,
+                          -140 -88.5001 446,
+                          -140 -91.5754 453.425,
+                          -140 -86.5001 446,
+                          -140 -99.0005 458.5,
+                          -140 -99 456.5,
+                          -140 -106.425 453.425,
+                          -140 -99.0005 458.5,
+                          -140 -90.1612 454.839,
+                          -140 -99 456.5,
+                          -140 -111.5 446,
+                          -140 -106.425 453.425,
+                          -140 -109.5 446,
+                          -140 -107.839 454.839,
+                          -140 -99.0005 458.5,
+                          -140 -106.425 453.425,
+                          -140 -111.5 446,
+                          -140 -107.839 454.839,
+                          -140 -106.425 453.425,
+                          -140 -111.5 446,
+                          -140 -109.5 446,
+                          -140 -106.425 438.575,
+                          -140 -111.5 446,
+                          -140 -106.425 438.575,
+                          -140 -107.839 437.161,
+                          -140 -99 435.5,
+                          -140 -107.839 437.161,
+                          -140 -106.425 438.575,
+                          -140 -99 435.5,
+                          -140 -98.9995 433.5,
+                          -140 -107.839 437.161,
+                          -140 -108.899 436.1,
+                          -140 -107.839 437.161,
+                          -140 -98.9995 433.5,
+                          -140 -112.828 443.81,
+                          -140 -111.5 446,
+                          -140 -107.839 437.161,
+                          -140 -112.828 443.81,
+                          -140 -107.839 437.161,
+                          -140 -108.899 436.1,
+                          -140 -91.5754 438.575,
+                          -140 -90.1612 437.161,
+                          -140 -98.9995 433.5,
+                          -140 -101.19 432.172,
+                          -140 -98.9995 433.5,
+                          -140 -90.1612 437.161,
+                          -140 -99 435.5,
+                          -140 -91.5754 438.575,
+                          -140 -98.9995 433.5,
+                          -140 -101.19 432.172,
+                          -140 -108.899 436.1,
+                          -140 -98.9995 433.5,
+                          -140 -91.5754 438.575,
+                          -140 -86.5001 446,
+                          -140 -90.1612 437.161,
+                          -140 -86.5261 439.644,
+                          -140 -90.1612 437.161,
+                          -140 -86.5001 446,
+                          -140 -92.644 433.526,
+                          -140 -101.19 432.172,
+                          -140 -90.1612 437.161,
+                          -140 -86.5261 439.644,
+                          -140 -92.644 433.526,
+                          -140 -90.1612 437.161,
+                          -140 -85.1723 448.19,
+                          -140 -86.5001 446,
+                          -140 -90.1612 454.839,
+                          -140 -91.5754 438.575,
+                          -140 -88.5001 446,
+                          -140 -86.5001 446,
+                          -140 -85.1723 448.19,
+                          -140 -86.5261 439.644,
+                          -140 -86.5001 446,
+                          -140 -89.1005 455.9,
+                          -140 -90.1612 454.839,
+                          -140 -99.0005 458.5,
+                          -140 -85.1723 448.19,
+                          -140 -90.1612 454.839,
+                          -140 -89.1005 455.9,
+                          -140 -96.8104 459.828,
+                          -140 -99.0005 458.5,
+                          -140 -107.839 454.839,
+                          -140 -89.1005 455.9,
+                          -140 -99.0005 458.5,
+                          -140 -96.8104 459.828,
+                          -140 -111.474 452.356,
+                          -140 -107.839 454.839,
+                          -140 -111.5 446,
+                          -140 -105.356 458.474,
+                          -140 -107.839 454.839,
+                          -140 -111.474 452.356,
+                          -140 -96.8104 459.828,
+                          -140 -107.839 454.839,
+                          -140 -105.356 458.474,
+                          -140 -111.474 452.356,
+                          -140 -111.5 446,
+                          -140 -112.828 443.81,
+                          -135 -112.828 443.81,
+                          -140 -112.828 443.81,
+                          -140 -108.899 436.1,
+                          -135 -108.899 436.1,
+                          -135 -112.828 443.81,
+                          -140 -108.899 436.1,
+                          -140 -101.19 432.172,
+                          -135 -108.899 436.1,
+                          -140 -108.899 436.1,
+                          -135 -111.474 452.356,
+                          -140 -111.474 452.356,
+                          -140 -112.828 443.81,
+                          -135 -112.828 443.81,
+                          -135 -111.474 452.356,
+                          -140 -112.828 443.81,
+                          -135 -105.356 458.474,
+                          -140 -105.356 458.474,
+                          -140 -111.474 452.356,
+                          -135 -111.474 452.356,
+                          -135 -105.356 458.474,
+                          -140 -111.474 452.356,
+                          -135 -96.8104 459.828,
+                          -140 -96.8104 459.828,
+                          -140 -105.356 458.474,
+                          -135 -105.356 458.474,
+                          -135 -96.8104 459.828,
+                          -140 -105.356 458.474,
+                          -135 -89.1005 455.9,
+                          -140 -89.1005 455.9,
+                          -140 -96.8104 459.828,
+                          -135 -96.8104 459.828,
+                          -135 -89.1005 455.9,
+                          -140 -96.8104 459.828,
+                          -135 -85.1723 448.19,
+                          -140 -89.1005 455.9,
+                          -135 -89.1005 455.9,
+                          -140 -85.1723 448.19,
+                          -140 -89.1005 455.9,
+                          -135 -85.1723 448.19,
+                          -135 -90.8683 454.132,
+                          -135 -89.1005 455.9,
+                          -135 -96.8104 459.828,
+                          -135 -90.8683 454.132,
+                          -135 -87.5001 446,
+                          -135 -89.1005 455.9,
+                          -135 -85.1723 448.19,
+                          -135 -89.1005 455.9,
+                          -135 -87.5001 446,
+                          -135 -107.132 454.132,
+                          -135 -96.8104 459.828,
+                          -135 -105.356 458.474,
+                          -135 -99 457.5,
+                          -135 -90.8683 454.132,
+                          -135 -96.8104 459.828,
+                          -135 -107.132 454.132,
+                          -135 -99 457.5,
+                          -135 -96.8104 459.828,
+                          -135 -112.828 443.81,
+                          -135 -105.356 458.474,
+                          -135 -111.474 452.356,
+                          -135 -107.132 454.132,
+                          -135 -105.356 458.474,
+                          -135 -112.828 443.81,
+                          -135 -110.5 446,
+                          -135 -112.828 443.81,
+                          -135 -108.899 436.1,
+                          -135 -110.5 446,
+                          -135 -107.132 454.132,
+                          -135 -112.828 443.81,
+                          -135 -110.5 446,
+                          -135 -108.899 436.1,
+                          -135 -107.132 437.868,
+                          -135 -101.19 432.172,
+                          -135 -107.132 437.868,
+                          -135 -108.899 436.1,
+                          -140 -101.19 432.172,
+                          -135 -101.19 432.172,
+                          -135 -108.899 436.1,
+                          -135 -101.19 432.172,
+                          -135 -99 434.5,
+                          -135 -107.132 437.868,
+                          -120 -107.132 437.868,
+                          -135 -107.132 437.868,
+                          -135 -99 434.5,
+                          -120 -110.5 446,
+                          -135 -110.5 446,
+                          -135 -107.132 437.868,
+                          -120 -107.132 437.868,
+                          -120 -110.5 446,
+                          -135 -107.132 437.868,
+                          -135 -101.19 432.172,
+                          -135 -90.8683 437.868,
+                          -135 -99 434.5,
+                          -120 -99 434.5,
+                          -135 -99 434.5,
+                          -135 -90.8683 437.868,
+                          -120 -99 434.5,
+                          -120 -107.132 437.868,
+                          -135 -99 434.5,
+                          -135 -85.1723 448.19,
+                          -135 -87.5001 446,
+                          -135 -90.8683 437.868,
+                          -120 -90.8683 437.868,
+                          -135 -90.8683 437.868,
+                          -135 -87.5001 446,
+                          -135 -92.644 433.526,
+                          -135 -85.1723 448.19,
+                          -135 -90.8683 437.868,
+                          -135 -101.19 432.172,
+                          -135 -92.644 433.526,
+                          -135 -90.8683 437.868,
+                          -120 -99 434.5,
+                          -135 -90.8683 437.868,
+                          -120 -90.8683 437.868,
+                          -120 -87.5001 446,
+                          -135 -87.5001 446,
+                          -135 -90.8683 454.132,
+                          -120 -90.8683 437.868,
+                          -135 -87.5001 446,
+                          -120 -87.5001 446,
+                          -120 -90.8683 454.132,
+                          -135 -90.8683 454.132,
+                          -135 -99 457.5,
+                          -120 -87.5001 446,
+                          -135 -90.8683 454.132,
+                          -120 -90.8683 454.132,
+                          -120 -99 457.5,
+                          -135 -99 457.5,
+                          -135 -107.132 454.132,
+                          -120 -99 457.5,
+                          -120 -90.8683 454.132,
+                          -135 -99 457.5,
+                          -120 -107.132 454.132,
+                          -135 -107.132 454.132,
+                          -135 -110.5 446,
+                          -120 -107.132 454.132,
+                          -120 -99 457.5,
+                          -135 -107.132 454.132,
+                          -120 -110.5 446,
+                          -120 -107.132 454.132,
+                          -135 -110.5 446,
+                          -135 -92.644 433.526,
+                          -135 -86.5261 439.644,
+                          -135 -85.1723 448.19,
+                          -140 -85.1723 448.19,
+                          -135 -85.1723 448.19,
+                          -135 -86.5261 439.644,
+                          -140 -86.5261 439.644,
+                          -135 -86.5261 439.644,
+                          -135 -92.644 433.526,
+                          -140 -85.1723 448.19,
+                          -135 -86.5261 439.644,
+                          -140 -86.5261 439.644,
+                          -140 -92.644 433.526,
+                          -135 -92.644 433.526,
+                          -135 -101.19 432.172,
+                          -140 -86.5261 439.644,
+                          -135 -92.644 433.526,
+                          -140 -92.644 433.526,
+                          -140 -92.644 433.526,
+                          -135 -101.19 432.172,
+                          -140 -101.19 432.172,
+                          -120 -85.565 459.435,
+                          -120 -90.8683 454.132,
+                          -120 -99 457.5,
+                          -120 -85.565 459.435,
+                          -120 -80.234 448.972,
+                          -120 -90.8683 454.132,
+                          -120 -87.5001 446,
+                          -120 -90.8683 454.132,
+                          -120 -80.234 448.972,
+                          -120 -96.0275 464.766,
+                          -120 -99 457.5,
+                          -120 -107.132 454.132,
+                          -120 -96.0275 464.766,
+                          -120 -85.565 459.435,
+                          -120 -99 457.5,
+                          -120 -117.766 443.028,
+                          -120 -107.132 454.132,
+                          -120 -110.5 446,
+                          -120 -115.929 454.626,
+                          -120 -96.0275 464.766,
+                          -120 -107.132 454.132,
+                          -120 -117.766 443.028,
+                          -120 -115.929 454.626,
+                          -120 -107.132 454.132,
+                          -120 -117.766 443.028,
+                          -120 -110.5 446,
+                          -120 -107.132 437.868,
+                          -120 -117.766 443.028,
+                          -120 -107.132 437.868,
+                          -120 -112.435 432.565,
+                          -120 -99 434.5,
+                          -120 -112.435 432.565,
+                          -120 -107.132 437.868,
+                          -120 -99 434.5,
+                          -120 -101.972 427.234,
+                          -120 -112.435 432.565,
+                          -118 -112.435 432.565,
+                          -120 -112.435 432.565,
+                          -120 -101.972 427.234,
+                          -118 -117.766 443.028,
+                          -120 -117.766 443.028,
+                          -120 -112.435 432.565,
+                          -118 -112.435 432.565,
+                          -118 -117.766 443.028,
+                          -120 -112.435 432.565,
+                          -120 -82.0711 437.374,
+                          -120 -90.3738 429.071,
+                          -120 -101.972 427.234,
+                          -118 -101.972 427.234,
+                          -120 -101.972 427.234,
+                          -120 -90.3738 429.071,
+                          -120 -90.8683 437.868,
+                          -120 -82.0711 437.374,
+                          -120 -101.972 427.234,
+                          -120 -99 434.5,
+                          -120 -90.8683 437.868,
+                          -120 -101.972 427.234,
+                          -118 -101.972 427.234,
+                          -118 -112.435 432.565,
+                          -120 -101.972 427.234,
+                          -118 -90.3738 429.071,
+                          -120 -90.3738 429.071,
+                          -120 -82.0711 437.374,
+                          -118 -101.972 427.234,
+                          -120 -90.3738 429.071,
+                          -118 -90.3738 429.071,
+                          -120 -90.8683 437.868,
+                          -120 -80.234 448.972,
+                          -120 -82.0711 437.374,
+                          -118 -82.0711 437.374,
+                          -120 -82.0711 437.374,
+                          -120 -80.234 448.972,
+                          -118 -90.3738 429.071,
+                          -120 -82.0711 437.374,
+                          -118 -82.0711 437.374,
+                          -118 -80.234 448.972,
+                          -120 -80.234 448.972,
+                          -120 -85.565 459.435,
+                          -120 -90.8683 437.868,
+                          -120 -87.5001 446,
+                          -120 -80.234 448.972,
+                          -118 -82.0711 437.374,
+                          -120 -80.234 448.972,
+                          -118 -80.234 448.972,
+                          -118 -85.565 459.435,
+                          -120 -85.565 459.435,
+                          -120 -96.0275 464.766,
+                          -118 -80.234 448.972,
+                          -120 -85.565 459.435,
+                          -118 -85.565 459.435,
+                          -120 -115.929 454.626,
+                          -120 -107.626 462.929,
+                          -120 -96.0275 464.766,
+                          -118 -96.0275 464.766,
+                          -120 -96.0275 464.766,
+                          -120 -107.626 462.929,
+                          -118 -96.0275 464.766,
+                          -118 -85.565 459.435,
+                          -120 -96.0275 464.766,
+                          -118 -107.626 462.929,
+                          -120 -107.626 462.929,
+                          -120 -115.929 454.626,
+                          -118 -107.626 462.929,
+                          -118 -96.0275 464.766,
+                          -120 -107.626 462.929,
+                          -118 -115.929 454.626,
+                          -120 -115.929 454.626,
+                          -120 -117.766 443.028,
+                          -118 -115.929 454.626,
+                          -118 -107.626 462.929,
+                          -120 -115.929 454.626,
+                          -118 -117.766 443.028,
+                          -118 -115.929 454.626,
+                          -120 -117.766 443.028,
+                          -118 -90.1612 454.839,
+                          -118 -85.565 459.435,
+                          -118 -96.0275 464.766,
+                          -118 -87.4514 450.783,
+                          -118 -86.5001 446,
+                          -118 -85.565 459.435,
+                          -118 -80.234 448.972,
+                          -118 -85.565 459.435,
+                          -118 -86.5001 446,
+                          -118 -90.1612 454.839,
+                          -118 -87.4514 450.783,
+                          -118 -85.565 459.435,
+                          -118 -103.784 457.548,
+                          -118 -96.0275 464.766,
+                          -118 -107.626 462.929,
+                          -118 -94.2169 457.549,
+                          -118 -90.1612 454.839,
+                          -118 -96.0275 464.766,
+                          -118 -99.0005 458.5,
+                          -118 -94.2169 457.549,
+                          -118 -96.0275 464.766,
+                          -118 -103.784 457.548,
+                          -118 -99.0005 458.5,
+                          -118 -96.0275 464.766,
+                          -118 -117.766 443.028,
+                          -118 -107.626 462.929,
+                          -118 -115.929 454.626,
+                          -118 -107.839 454.839,
+                          -118 -107.626 462.929,
+                          -118 -117.766 443.028,
+                          -118 -107.839 454.839,
+                          -118 -103.784 457.548,
+                          -118 -107.626 462.929,
+                          -118 -111.5 446,
+                          -118 -117.766 443.028,
+                          -118 -112.435 432.565,
+                          -118 -110.548 450.784,
+                          -118 -107.839 454.839,
+                          -118 -117.766 443.028,
+                          -118 -111.5 446,
+                          -118 -110.548 450.784,
+                          -118 -117.766 443.028,
+                          -118 -110.549 441.217,
+                          -118 -112.435 432.565,
+                          -118 -107.839 437.161,
+                          -118 -101.972 427.234,
+                          -118 -107.839 437.161,
+                          -118 -112.435 432.565,
+                          -118 -110.549 441.217,
+                          -118 -111.5 446,
+                          -118 -112.435 432.565,
+                          -118 -101.972 427.234,
+                          -118 -103.783 434.451,
+                          -118 -107.839 437.161,
+                          -118 -101.972 427.234,
+                          -118 -98.9995 433.5,
+                          -118 -103.783 434.451,
+                          -118 -101.972 427.234,
+                          -118 -94.2162 434.452,
+                          -118 -98.9995 433.5,
+                          -118 -90.3738 429.071,
+                          -118 -90.1612 437.161,
+                          -118 -94.2162 434.452,
+                          -118 -101.972 427.234,
+                          -118 -90.3738 429.071,
+                          -118 -94.2162 434.452,
+                          -118 -80.234 448.972,
+                          -118 -87.4517 441.216,
+                          -118 -90.1612 437.161,
+                          -118 -90.3738 429.071,
+                          -118 -80.234 448.972,
+                          -118 -90.1612 437.161,
+                          -118 -80.234 448.972,
+                          -118 -86.5001 446,
+                          -118 -87.4517 441.216,
+                          -118 -90.3738 429.071,
+                          -118 -82.0711 437.374,
+                          -118 -80.234 448.972 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.5 0.5 0.5
+    }
+    Separator {
+        Normal {
+            vector      [ 3.87294e-15 5.98549e-16 1,
+                          3.87294e-15 5.98549e-16 1,
+                          3.87294e-15 5.98549e-16 1,
+                          -0.556044 -0.831153 2.65101e-15,
+                          -0.556044 -0.831153 2.65101e-15,
+                          -0.365448 -0.930832 1.9725e-15,
+                          3.87294e-15 5.98549e-16 1,
+                          3.87294e-15 5.98549e-16 1,
+                          3.87294e-15 5.98549e-16 1,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          3.87294e-15 5.98549e-16 1,
+                          3.87294e-15 5.98549e-16 1,
+                          3.87294e-15 5.98549e-16 1,
+                          -0.365448 -0.930832 1.9725e-15,
+                          -0.365448 -0.930832 1.9725e-15,
+                          -0.157897 -0.987456 1.20257e-15,
+                          -0.365448 -0.930832 1.9725e-15,
+                          -0.556044 -0.831153 2.65101e-15,
+                          -0.365448 -0.930832 1.9725e-15,
+                          3.87294e-15 5.98549e-16 1,
+                          3.87294e-15 5.98549e-16 1,
+                          3.87294e-15 5.98549e-16 1,
+                          -0.157897 -0.987456 1.20257e-15,
+                          -0.157897 -0.987456 1.20257e-15,
+                          0.0569565 -0.998377 3.76989e-16,
+                          -0.365448 -0.930832 1.9725e-15,
+                          -0.157897 -0.987456 1.20257e-15,
+                          -0.157897 -0.987456 1.20257e-15,
+                          3.87294e-15 5.98549e-16 1,
+                          3.87294e-15 5.98549e-16 1,
+                          3.87294e-15 5.98549e-16 1,
+                          -1 1.44497e-16 3.87294e-15,
+                          -1 1.44497e-16 3.87294e-15,
+                          -1 1.44497e-16 3.87294e-15,
+                          -0.157897 -0.987456 1.20257e-15,
+                          0.0569565 -0.998377 3.76989e-16,
+                          0.0569565 -0.998377 3.76989e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          -1 1.44497e-16 3.87294e-15,
+                          -1 1.44497e-16 3.87294e-15,
+                          -1 1.44497e-16 3.87294e-15,
+                          0.280995 5.3383e-16 0.959709,
+                          3.81171e-15 5.98549e-16 1,
+                          3.81171e-15 5.98549e-16 1,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          0.546578 4.22251e-16 0.837408,
+                          0.566073 4.11621e-16 0.824355,
+                          3.81171e-15 5.98549e-16 1,
+                          0.280995 5.3383e-16 0.959709,
+                          0.546578 4.22251e-16 0.837408,
+                          3.81171e-15 5.98549e-16 1,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          -0.178731 -0.983029 0.0413357,
+                          -0.153822 -0.987071 0.0450605,
+                          0.000780052 -1 5.95528e-16,
+                          0.00111921 -0.999999 5.94214e-16,
+                          -0.178731 -0.983029 0.0413357,
+                          0.000780052 -1 5.95528e-16,
+                          3.87294e-15 5.98549e-16 1,
+                          3.87294e-15 5.98549e-16 1,
+                          3.87294e-15 5.98549e-16 1,
+                          0.056944 0.998377 -8.18119e-16,
+                          0.056944 0.998377 -8.18119e-16,
+                          -0.112305 0.993674 -1.59813e-16,
+                          -1 1.44497e-16 3.87294e-15,
+                          -1 1.44497e-16 3.87294e-15,
+                          -1 1.44497e-16 3.87294e-15,
+                          -1 1.44497e-16 3.87294e-15,
+                          -1 1.44497e-16 3.87294e-15,
+                          -1 1.44497e-16 3.87294e-15,
+                          3.87294e-15 5.98549e-16 1,
+                          3.87294e-15 5.98549e-16 1,
+                          3.87294e-15 5.98549e-16 1,
+                          -0.112305 0.993674 -1.59813e-16,
+                          -0.112305 0.993674 -1.59813e-16,
+                          -0.278338 0.960483 5.03089e-16,
+                          -0.112305 0.993674 -1.59813e-16,
+                          0.056944 0.998377 -8.18119e-16,
+                          -0.112305 0.993674 -1.59813e-16,
+                          3.87294e-15 5.98549e-16 1,
+                          3.87294e-15 5.98549e-16 1,
+                          3.87294e-15 5.98549e-16 1,
+                          -0.278338 0.960483 5.03089e-16,
+                          -0.278338 0.960483 5.03089e-16,
+                          -0.436391 0.899757 1.15157e-15,
+                          -0.112305 0.993674 -1.59813e-16,
+                          -0.278338 0.960483 5.03089e-16,
+                          -0.278338 0.960483 5.03089e-16,
+                          3.87294e-15 5.98549e-16 1,
+                          3.87294e-15 5.98549e-16 1,
+                          3.87294e-15 5.98549e-16 1,
+                          -0.436391 0.899757 1.15157e-15,
+                          -0.436391 0.899757 1.15157e-15,
+                          -0.581934 0.813236 1.76703e-15,
+                          3.87294e-15 5.98549e-16 1,
+                          3.87294e-15 5.98549e-16 1,
+                          3.87294e-15 5.98549e-16 1,
+                          3.87294e-15 5.98549e-16 1,
+                          3.87294e-15 5.98549e-16 1,
+                          3.87294e-15 5.98549e-16 1,
+                          -0.278338 0.960483 5.03089e-16,
+                          -0.436391 0.899757 1.15157e-15,
+                          -0.436391 0.899757 1.15157e-15,
+                          4.7674e-16 1 -5.98549e-16,
+                          4.7674e-16 1 -5.98549e-16,
+                          4.7674e-16 1 -5.98549e-16,
+                          4.7674e-16 1 -5.98549e-16,
+                          4.7674e-16 1 -5.98549e-16,
+                          4.7674e-16 1 -5.98549e-16,
+                          4.7674e-16 1 -5.98549e-16,
+                          4.7674e-16 1 -5.98549e-16,
+                          4.7674e-16 1 -5.98549e-16,
+                          4.7674e-16 1 -5.98549e-16,
+                          4.7674e-16 1 -5.98549e-16,
+                          4.7674e-16 1 -5.98549e-16,
+                          -0.436391 0.899757 1.15157e-15,
+                          -0.581934 0.813236 1.76703e-15,
+                          -0.581934 0.813236 1.76703e-15,
+                          0.566073 4.11621e-16 0.824355,
+                          3.81171e-15 5.98549e-16 1,
+                          3.81171e-15 5.98549e-16 1,
+                          0.566073 4.11621e-16 0.824355,
+                          0.280995 5.3383e-16 0.959709,
+                          3.81171e-15 5.98549e-16 1,
+                          0.00111921 0.999999 -6.02884e-16,
+                          0.000780052 1 -6.0157e-16,
+                          -0.153822 0.987071 0.0450605,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          0.933291 8.00944e-17 0.359122,
+                          0.933291 8.00944e-17 0.359122,
+                          0.933291 8.00944e-17 0.359122,
+                          0.77293 2.68088e-16 0.634492,
+                          0.933291 8.00944e-17 0.359122,
+                          0.933291 8.00944e-17 0.359122,
+                          0.933291 8.00944e-17 0.359122,
+                          0.933291 8.00944e-17 0.359122,
+                          0.933291 8.00944e-17 0.359122,
+                          0.933291 8.00944e-17 0.359122,
+                          0.933291 8.00944e-17 0.359122,
+                          0.933291 8.00944e-17 0.359122,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          0.566073 4.11621e-16 0.824355,
+                          0.933291 8.00944e-17 0.359122,
+                          0.77293 2.68088e-16 0.634492,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          0.00858026 -0.999963 5.65297e-16,
+                          -0.804806 -0.276181 0.525367,
+                          -0.49076 -0.836693 0.243104,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -0.170351 0.880334 0.442711,
+                          -0.170351 0.880334 0.442711,
+                          -0.170351 0.880334 0.442711,
+                          -0.32386 0.832602 0.44932,
+                          -0.255805 0.915144 0.311569,
+                          -0.174237 0.874416 0.452811,
+                          -0.32386 0.832602 0.44932,
+                          -0.174237 0.874416 0.452811,
+                          -0.223673 0.782355 0.581284,
+                          0.933291 8.00944e-17 0.359122,
+                          0.933291 8.00944e-17 0.359122,
+                          0.933291 8.00944e-17 0.359122,
+                          -0.345177 0.275954 0.897052,
+                          -0.345177 0.275954 0.897052,
+                          -0.345177 0.275954 0.897052,
+                          -0.170351 0.880334 0.442711,
+                          -0.170351 0.880334 0.442711,
+                          -0.170351 0.880334 0.442711,
+                          -0.170351 0.880334 0.442711,
+                          -0.170351 0.880334 0.442711,
+                          -0.170351 0.880334 0.442711,
+                          -0.170351 0.880334 0.442711,
+                          -0.170351 0.880334 0.442711,
+                          -0.170351 0.880334 0.442711,
+                          0.933291 8.00944e-17 0.359122,
+                          0.933291 8.00944e-17 0.359122,
+                          0.933291 8.00944e-17 0.359122,
+                          -0.345177 -0.275954 0.897052,
+                          -0.345177 -0.275954 0.897052,
+                          -0.345177 -0.275954 0.897052,
+                          -0.345177 0.275954 0.897052,
+                          -0.345177 0.275954 0.897052,
+                          -0.345177 0.275954 0.897052,
+                          0.933291 8.00944e-17 0.359122,
+                          0.933291 8.00944e-17 0.359122,
+                          0.933291 8.00944e-17 0.359122,
+                          -0.170351 -0.880334 0.442711,
+                          -0.170351 -0.880334 0.442711,
+                          -0.170351 -0.880334 0.442711,
+                          -0.345177 -0.275954 0.897052,
+                          -0.345177 -0.275954 0.897052,
+                          -0.345177 -0.275954 0.897052,
+                          0.933291 8.00944e-17 0.359122,
+                          0.933291 8.00944e-17 0.359122,
+                          0.933291 8.00944e-17 0.359122,
+                          0.566073 4.11621e-16 0.824355,
+                          0.933291 8.00944e-17 0.359122,
+                          0.933291 8.00944e-17 0.359122,
+                          0.77293 2.68088e-16 0.634492,
+                          0.933291 8.00944e-17 0.359122,
+                          0.566073 4.11621e-16 0.824355,
+                          -0.223673 -0.782355 0.581284,
+                          -0.174237 -0.874416 0.452811,
+                          -0.255805 -0.915144 0.311569,
+                          -0.170351 -0.880334 0.442711,
+                          -0.170351 -0.880334 0.442711,
+                          -0.170351 -0.880334 0.442711,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          -0.804806 -0.276181 0.525367,
+                          -0.621456 -0.202115 0.756929,
+                          -0.524319 -0.728839 0.440322,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          0.986666 -4.51512e-17 0.162759,
+                          0.933291 8.00944e-17 0.359122,
+                          0.933291 8.00944e-17 0.359122,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          0.986666 -4.51512e-17 0.162759,
+                          0.986666 -4.51512e-17 0.162759,
+                          0.933291 8.00944e-17 0.359122,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.986666 -4.51512e-17 0.162759,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          0.986666 -4.51512e-17 0.162759,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.986666 -4.51512e-17 0.162759,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          -1.44497e-16 -1 5.98549e-16,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          -6.99005e-08 1 -1.73121e-06,
+                          -6.99005e-08 1 -1.73121e-06,
+                          0.00678203 0.985769 0.167969,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          1.44497e-16 1 -5.98549e-16,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.00678203 0.985769 0.167969,
+                          0.00678203 0.985769 0.167969,
+                          0.0133632 0.943549 0.330962,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          -6.99005e-08 1 -1.73121e-06,
+                          0.00678203 0.985769 0.167969,
+                          0.00678203 0.985769 0.167969,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.99699 0.0662598 -0.0402552,
+                          0.999186 -2.29758e-16 -0.0403439,
+                          0.999186 -2.29758e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.997108 0.0644586 -0.04026,
+                          0.999186 -2.29758e-16 -0.0403439,
+                          0.99699 0.0662598 -0.0402552,
+                          -0.121314 0.972742 0.197626,
+                          0.0133486 0.943676 0.330601,
+                          -0.0463338 0.935505 0.350263,
+                          0.00678203 0.985769 0.167969,
+                          0.0133632 0.943549 0.330962,
+                          0.0133632 0.943549 0.330962,
+                          -0.0559593 0.981152 0.184955,
+                          0.00696641 0.984979 0.172535,
+                          0.0133486 0.943676 0.330601,
+                          -0.0559593 0.981152 0.184955,
+                          0.0133486 0.943676 0.330601,
+                          -0.121314 0.972742 0.197626,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.0403439 5.92232e-16 0.999186,
+                          0.0403439 5.92232e-16 0.999186,
+                          0.0403439 5.92232e-16 0.999186,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          -0.0403439 -5.92232e-16 -0.999186,
+                          -0.0403439 -5.92232e-16 -0.999186,
+                          -0.0403439 -5.92232e-16 -0.999186,
+                          0.0403439 5.92232e-16 0.999186,
+                          0.0403439 5.92232e-16 0.999186,
+                          0.0403439 5.92232e-16 0.999186,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          -0.0104338 0.965979 -0.258412,
+                          -0.0104338 0.965979 -0.258412,
+                          -0.0104338 0.965979 -0.258412,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          -0.0104336 0.96598 -0.258406,
+                          -0.0104336 0.96598 -0.258406,
+                          0.00630722 0.987704 0.156209,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          -0.0104338 0.965979 -0.258412,
+                          -0.0104338 0.965979 -0.258412,
+                          -0.0104338 0.965979 -0.258412,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.00630722 0.987704 0.156209,
+                          0.00630722 0.987704 0.156209,
+                          0.021956 0.838941 0.543779,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.00630722 0.987704 0.156209,
+                          -0.0104336 0.96598 -0.258406,
+                          0.00630722 0.987704 0.156209,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.0219603 0.838873 0.543884,
+                          0.0219603 0.838873 0.543884,
+                          0.0219603 0.838873 0.543884,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.021956 0.838941 0.543779,
+                          0.00630722 0.987704 0.156209,
+                          0.021956 0.838941 0.543779,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.0218476 0.840678 0.541094,
+                          0.0218476 0.840678 0.541094,
+                          0.0038645 0.995402 0.0957109,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.0219603 0.838873 0.543884,
+                          0.0219603 0.838873 0.543884,
+                          0.0219603 0.838873 0.543884,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.0038645 0.995402 0.0957109,
+                          0.0038645 0.995402 0.0957109,
+                          -0.0149774 0.928536 -0.370941,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.0038645 0.995402 0.0957109,
+                          0.0218476 0.840678 0.541094,
+                          0.0038645 0.995402 0.0957109,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          -0.0151025 0.92729 -0.37404,
+                          -0.0151025 0.92729 -0.37404,
+                          -0.0151025 0.92729 -0.37404,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          -0.0149774 0.928536 -0.370941,
+                          0.0038645 0.995402 0.0957109,
+                          -0.0149774 0.928536 -0.370941,
+                          -0.0403439 -5.92232e-16 -0.999186,
+                          -0.0403439 -5.92232e-16 -0.999186,
+                          -0.0403439 -5.92232e-16 -0.999186,
+                          -0.0151025 0.92729 -0.37404,
+                          -0.0151025 0.92729 -0.37404,
+                          -0.0151025 0.92729 -0.37404,
+                          -0.0151025 -0.92729 -0.37404,
+                          -0.0151025 -0.92729 -0.37404,
+                          -0.0151025 -0.92729 -0.37404,
+                          -0.0403439 -5.92232e-16 -0.999186,
+                          -0.0403439 -5.92232e-16 -0.999186,
+                          -0.0403439 -5.92232e-16 -0.999186,
+                          -0.0149774 -0.928536 -0.370941,
+                          -0.0149774 -0.928536 -0.370941,
+                          0.0038645 -0.995402 0.0957111,
+                          -0.0151025 -0.92729 -0.37404,
+                          -0.0151025 -0.92729 -0.37404,
+                          -0.0151025 -0.92729 -0.37404,
+                          0.0038645 -0.995402 0.0957111,
+                          0.0038645 -0.995402 0.0957111,
+                          0.0218476 -0.840678 0.541094,
+                          0.0038645 -0.995402 0.0957111,
+                          -0.0149774 -0.928536 -0.370941,
+                          0.0038645 -0.995402 0.0957111,
+                          0.0219603 -0.838873 0.543884,
+                          0.0219603 -0.838873 0.543884,
+                          0.0219603 -0.838873 0.543884,
+                          0.0218476 -0.840678 0.541094,
+                          0.0038645 -0.995402 0.0957111,
+                          0.0218476 -0.840678 0.541094,
+                          0.0219595 -0.838885 0.543865,
+                          0.0219595 -0.838885 0.543865,
+                          0.0114506 -0.958876 0.283594,
+                          0.0219603 -0.838873 0.543884,
+                          0.0219603 -0.838873 0.543884,
+                          0.0219603 -0.838873 0.543884,
+                          0.0114506 -0.958876 0.283594,
+                          0.0114506 -0.958876 0.283594,
+                          -3.22476e-06 -1 -7.98669e-05,
+                          0.0114506 -0.958876 0.283594,
+                          0.0219595 -0.838885 0.543865,
+                          0.0114506 -0.958876 0.283594,
+                          3.25611e-08 -1 8.06401e-07,
+                          3.25611e-08 -1 8.06401e-07,
+                          -0.00526181 -0.991458 -0.130318,
+                          -3.22476e-06 -1 -7.98669e-05,
+                          0.0114506 -0.958876 0.283594,
+                          -3.22476e-06 -1 -7.98669e-05,
+                          -0.00526181 -0.991458 -0.130318,
+                          -0.00526181 -0.991458 -0.130318,
+                          -0.0104335 -0.965981 -0.258403,
+                          -0.00526181 -0.991458 -0.130318,
+                          3.25611e-08 -1 8.06401e-07,
+                          -0.00526181 -0.991458 -0.130318,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          0.999186 -1.68527e-16 -0.0403439,
+                          -0.0104338 -0.965979 -0.258412,
+                          -0.0104338 -0.965979 -0.258412,
+                          -0.0104338 -0.965979 -0.258412,
+                          -0.0104335 -0.965981 -0.258403,
+                          -0.00526181 -0.991458 -0.130318,
+                          -0.0104335 -0.965981 -0.258403,
+                          0.0403439 5.92232e-16 0.999186,
+                          0.0403439 5.92232e-16 0.999186,
+                          0.0403439 5.92232e-16 0.999186,
+                          -0.0104338 -0.965979 -0.258412,
+                          -0.0104338 -0.965979 -0.258412,
+                          -0.0104338 -0.965979 -0.258412,
+                          0.0403439 5.92232e-16 0.999186,
+                          0.0403439 5.92232e-16 0.999186,
+                          0.0403439 5.92232e-16 0.999186,
+                          0.997082 -0.0648573 -0.0402589,
+                          0.999186 -1.07297e-16 -0.0403439,
+                          0.999186 -1.07297e-16 -0.0403439,
+                          -0.0403439 -5.92232e-16 -0.999186,
+                          -0.0403439 -5.92232e-16 -0.999186,
+                          -0.0403439 -5.92232e-16 -0.999186,
+                          0.997082 -0.0648573 -0.0402589,
+                          0.99699 -0.0662598 -0.0402552,
+                          0.999186 -1.07297e-16 -0.0403439,
+                          -0.0403439 -5.92232e-16 -0.999186,
+                          -0.0403439 -5.92232e-16 -0.999186,
+                          -0.0403439 -5.92232e-16 -0.999186,
+                          0.0133638 -0.943544 0.330976,
+                          0.0133638 -0.943544 0.330976,
+                          0.00678203 -0.985769 0.167969,
+                          0.00697109 -0.984958 0.172651,
+                          -0.0467072 -0.935481 0.350278,
+                          0.0133568 -0.943605 0.330805,
+                          0.00678203 -0.985769 0.167969,
+                          0.00678203 -0.985769 0.167969,
+                          -6.8534e-07 -1 -1.69736e-05,
+                          0.0133638 -0.943544 0.330976,
+                          0.00678203 -0.985769 0.167969,
+                          0.00678203 -0.985769 0.167969,
+                          0.00678203 -0.985769 0.167969,
+                          -6.8534e-07 -1 -1.69736e-05,
+                          -6.8534e-07 -1 -1.69736e-05,
+                          0.965139 0.258819 -0.0389692,
+                          0.965139 0.258819 -0.0389692,
+                          0.965139 0.258819 -0.0389692,
+                          -0.260387 0.964561 -0.0426725,
+                          -0.260387 0.964561 -0.0426725,
+                          -0.260387 0.964561 -0.0426725,
+                          0.965139 0.258819 -0.0389692,
+                          0.965139 0.258819 -0.0389692,
+                          0.965139 0.258819 -0.0389692,
+                          0.965139 0.258819 -0.0389692,
+                          0.965139 0.258819 -0.0389692,
+                          0.965139 0.258819 -0.0389692,
+                          -0.0927518 0.477431 0.87376,
+                          -0.0927518 0.477431 0.87376,
+                          -0.0927518 0.477431 0.87376,
+                          -0.260387 0.964561 -0.0426725,
+                          -0.260387 0.964561 -0.0426725,
+                          -0.260387 0.964561 -0.0426725,
+                          -0.0927518 0.477431 0.87376,
+                          -0.0927518 0.477431 0.87376,
+                          -0.0927518 0.477431 0.87376,
+                          -0.0403439 1.26044e-15 -0.999186,
+                          -0.0403439 1.26044e-15 -0.999186,
+                          -0.0403439 1.26044e-15 -0.999186,
+                          -0.0403439 1.26044e-15 -0.999186,
+                          -0.0403439 1.26044e-15 -0.999186,
+                          -0.0403439 1.26044e-15 -0.999186,
+                          0.965139 0.258819 -0.0389692,
+                          0.965139 0.258819 -0.0389692,
+                          0.965139 0.258819 -0.0389692,
+                          0.71352 0.700042 -0.0288096,
+                          0.965139 0.258819 -0.0389692,
+                          0.965139 0.258819 -0.0389692,
+                          0.71352 0.700042 -0.0288096,
+                          0.965139 0.258819 -0.0389692,
+                          0.71352 0.700042 -0.0288096,
+                          0.0403439 3.17483e-15 0.999186,
+                          0.0403439 3.17483e-15 0.999186,
+                          0.0403439 3.17483e-15 0.999186,
+                          0.965139 0.258819 -0.0389692,
+                          0.965139 0.258819 -0.0389692,
+                          0.965139 0.258819 -0.0389692,
+                          0.0403439 -1.26044e-15 0.999186,
+                          0.0403439 -1.26044e-15 0.999186,
+                          0.0403439 -1.26044e-15 0.999186,
+                          -0.0403439 -3.17313e-15 -0.999186,
+                          -0.0403439 -3.17313e-15 -0.999186,
+                          -0.0403439 -3.17313e-15 -0.999186,
+                          -0.0403439 -3.17313e-15 -0.999186,
+                          -0.0403439 -3.17313e-15 -0.999186,
+                          -0.0403439 -3.17313e-15 -0.999186,
+                          -0.0403439 -3.17313e-15 -0.999186,
+                          -0.0403439 -3.17313e-15 -0.999186,
+                          -0.0403439 -3.17313e-15 -0.999186,
+                          -0.176989 0.535678 -0.825666,
+                          -0.176989 0.535678 -0.825666,
+                          -0.176989 0.535678 -0.825666,
+                          0.0403439 -1.26044e-15 0.999186,
+                          0.0403439 -1.26044e-15 0.999186,
+                          0.0403439 -1.26044e-15 0.999186,
+                          0.979866 0.195695 -0.0395638,
+                          0.965139 0.258819 -0.0389692,
+                          0.965139 0.258819 -0.0389692,
+                          0.979784 0.196108 -0.0395605,
+                          0.965139 0.258819 -0.0389692,
+                          0.979866 0.195695 -0.0395638,
+                          -0.130591 0.802524 -0.582152,
+                          -0.177039 0.535887 -0.82552,
+                          -0.143477 0.550998 -0.82208,
+                          -0.176989 0.535678 -0.825666,
+                          -0.176989 0.535678 -0.825666,
+                          -0.176989 0.535678 -0.825666,
+                          -0.181723 0.789718 -0.585937,
+                          -0.231107 0.772806 -0.591067,
+                          -0.177039 0.535887 -0.82552,
+                          -0.130591 0.802524 -0.582152,
+                          -0.181723 0.789718 -0.585937,
+                          -0.177039 0.535887 -0.82552,
+                          -0.167698 0.725799 0.667153,
+                          -0.0623735 0.48829 0.870449,
+                          -0.092899 0.477936 0.873469,
+                          0.965139 -0.258819 -0.0389692,
+                          0.965139 -0.258819 -0.0389692,
+                          0.965139 -0.258819 -0.0389692,
+                          -0.0927518 -0.477431 0.87376,
+                          -0.0927518 -0.477431 0.87376,
+                          -0.0927518 -0.477431 0.87376,
+                          -0.260387 -0.964561 -0.0426725,
+                          -0.260387 -0.964561 -0.0426725,
+                          -0.260387 -0.964561 -0.0426725,
+                          0.965139 -0.258819 -0.0389692,
+                          0.965139 -0.258819 -0.0389692,
+                          0.965139 -0.258819 -0.0389692,
+                          0.979784 -0.196108 -0.0395605,
+                          0.965139 -0.258819 -0.0389692,
+                          0.965139 -0.258819 -0.0389692,
+                          0.965139 -0.258819 -0.0389692,
+                          0.965139 -0.258819 -0.0389692,
+                          0.965139 -0.258819 -0.0389692,
+                          0.965139 -0.258819 -0.0389692,
+                          0.965139 -0.258819 -0.0389692,
+                          0.965139 -0.258819 -0.0389692,
+                          0.979866 -0.195695 -0.0395638,
+                          0.965139 -0.258819 -0.0389692,
+                          0.979784 -0.196108 -0.0395605,
+                          -0.073183 -0.750214 0.657133,
+                          -0.092899 -0.477936 0.873469,
+                          -0.0623735 -0.48829 0.870449,
+                          -0.0927518 -0.477431 0.87376,
+                          -0.0927518 -0.477431 0.87376,
+                          -0.0927518 -0.477431 0.87376,
+                          -0.120963 -0.739544 0.66215,
+                          -0.167698 -0.725799 0.667153,
+                          -0.092899 -0.477936 0.873469,
+                          -0.120963 -0.739544 0.66215,
+                          -0.092899 -0.477936 0.873469,
+                          -0.073183 -0.750214 0.657133,
+                          0.965139 -0.258819 -0.0389692,
+                          0.965139 -0.258819 -0.0389692,
+                          0.965139 -0.258819 -0.0389692,
+                          -0.176989 -0.535678 -0.825666,
+                          -0.176989 -0.535678 -0.825666,
+                          -0.176989 -0.535678 -0.825666,
+                          -0.231107 -0.772806 -0.591067,
+                          -0.143477 -0.550998 -0.82208,
+                          -0.177039 -0.535887 -0.82552,
+                          0.0403439 4.03307e-15 0.999186,
+                          0.0403439 4.03307e-15 0.999186,
+                          0.0403439 4.03307e-15 0.999186,
+                          -0.176989 -0.535678 -0.825666,
+                          -0.176989 -0.535678 -0.825666,
+                          -0.176989 -0.535678 -0.825666,
+                          0.71352 -0.700042 -0.0288096,
+                          0.965139 -0.258819 -0.0389692,
+                          0.965139 -0.258819 -0.0389692,
+                          0.71352 -0.700042 -0.0288096,
+                          0.965139 -0.258819 -0.0389692,
+                          0.71352 -0.700042 -0.0288096,
+                          -0.0403439 1.39622e-15 -0.999186,
+                          -0.0403439 1.39622e-15 -0.999186,
+                          -0.0403439 1.39622e-15 -0.999186,
+                          0.0403439 4.03307e-15 0.999186,
+                          0.0403439 4.03307e-15 0.999186,
+                          0.0403439 4.03307e-15 0.999186,
+                          -0.0403439 -2.44491e-15 -0.999186,
+                          -0.0403439 -2.44491e-15 -0.999186,
+                          -0.0403439 -2.44491e-15 -0.999186,
+                          0.0403439 -1.39622e-15 0.999186,
+                          0.0403439 -1.39622e-15 0.999186,
+                          0.0403439 -1.39622e-15 0.999186,
+                          0.0403439 -1.39622e-15 0.999186,
+                          0.0403439 -1.39622e-15 0.999186,
+                          0.0403439 -1.39622e-15 0.999186,
+                          0.0403439 -1.39622e-15 0.999186,
+                          0.0403439 -1.39622e-15 0.999186,
+                          0.0403439 -1.39622e-15 0.999186,
+                          -0.0403439 -2.44491e-15 -0.999186,
+                          -0.0403439 -2.44491e-15 -0.999186,
+                          -0.0403439 -2.44491e-15 -0.999186,
+                          -0.260387 -0.964561 -0.0426725,
+                          -0.260387 -0.964561 -0.0426725,
+                          -0.260387 -0.964561 -0.0426725,
+                          -2.27764e-16 -1 6.17631e-16,
+                          -2.27764e-16 -1 6.17631e-16,
+                          -2.27764e-16 -1 6.17631e-16,
+                          0.147217 -0.989086 -0.00594414,
+                          6.21153e-15 -1 3.57423e-16,
+                          6.21153e-15 -1 3.57423e-16,
+                          0.00513697 5.97799e-16 0.999987,
+                          0.00513697 5.97799e-16 0.999987,
+                          0.00513697 5.97799e-16 0.999987,
+                          0.147217 -0.989086 -0.00594414,
+                          0.0957621 -0.995397 -0.00386656,
+                          6.21153e-15 -1 3.57423e-16,
+                          -0.0300847 6.02626e-16 0.999547,
+                          0.00508901 5.97806e-16 0.999987,
+                          0.0054554 -0.00335952 0.999979,
+                          0.00513697 5.97799e-16 0.999987,
+                          0.00513697 5.97799e-16 0.999987,
+                          0.00513697 5.97799e-16 0.999987,
+                          -2.27764e-16 -1 6.17631e-16,
+                          -2.27764e-16 -1 6.17631e-16,
+                          -2.27764e-16 -1 6.17631e-16,
+                          -4.12243e-15 -1.48094e-14 -1,
+                          -4.12243e-15 -1.48094e-14 -1,
+                          -4.12243e-15 -1.48094e-14 -1,
+                          -2.27764e-16 -1 6.17631e-16,
+                          -2.27764e-16 -1 6.17631e-16,
+                          -2.27764e-16 -1 6.17631e-16,
+                          -0.0403439 9.75507e-15 -0.999186,
+                          -0.0403439 9.75507e-15 -0.999186,
+                          -0.0403439 9.75507e-15 -0.999186,
+                          -0.0403439 9.75507e-15 -0.999186,
+                          -0.0403439 9.75507e-15 -0.999186,
+                          -0.0403439 9.75507e-15 -0.999186,
+                          -0.0403439 9.75507e-15 -0.999186,
+                          -0.0403439 9.75507e-15 -0.999186,
+                          -0.0403439 9.75507e-15 -0.999186,
+                          -0.0403439 9.75507e-15 -0.999186,
+                          -0.0403439 9.75507e-15 -0.999186,
+                          -0.0403439 9.75507e-15 -0.999186,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -4.12243e-15 -1.48094e-14 -1,
+                          -4.12243e-15 -1.48094e-14 -1,
+                          -4.12243e-15 -1.48094e-14 -1,
+                          -1 1.44497e-16 4.03659e-15,
+                          -1 1.44497e-16 4.03659e-15,
+                          -1 1.44497e-16 4.03659e-15,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -1 1.44497e-16 4.03659e-15,
+                          -1 1.44497e-16 4.03659e-15,
+                          -1 1.44497e-16 4.03659e-15,
+                          6.12303e-17 1 -1.17274e-15,
+                          6.12303e-17 1 -1.17274e-15,
+                          6.12303e-17 1 -1.17274e-15,
+                          0.0957621 0.995397 -0.00386656,
+                          -5.77148e-16 1 -1.14672e-15,
+                          -5.77148e-16 1 -1.14672e-15,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          0.0957621 0.995397 -0.00386656,
+                          0.147217 0.989086 -0.00594414,
+                          -5.77148e-16 1 -1.14672e-15,
+                          -0.0403439 -1.04865e-14 -0.999186,
+                          -0.0403439 -1.04865e-14 -0.999186,
+                          -0.0403439 -1.04865e-14 -0.999186,
+                          -0.0403439 -1.04865e-14 -0.999186,
+                          -0.0403439 -1.04865e-14 -0.999186,
+                          -0.0403439 -1.04865e-14 -0.999186,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -0.0403439 -1.04865e-14 -0.999186,
+                          -0.0403439 -1.04865e-14 -0.999186,
+                          -0.0403439 -1.04865e-14 -0.999186,
+                          6.12303e-17 1 -1.17274e-15,
+                          6.12303e-17 1 -1.17274e-15,
+                          6.12303e-17 1 -1.17274e-15,
+                          0.00513697 5.97799e-16 0.999987,
+                          0.00513697 5.97799e-16 0.999987,
+                          0.00513697 5.97799e-16 0.999987,
+                          6.12303e-17 1 -1.17274e-15,
+                          6.12303e-17 1 -1.17274e-15,
+                          6.12303e-17 1 -1.17274e-15,
+                          -0.0300847 6.02626e-16 0.999547,
+                          0.0054554 0.00335952 0.999979,
+                          0.00508901 5.97806e-16 0.999987,
+                          -0.621456 -0.202115 0.756929,
+                          -0.445741 -0.647208 0.618415,
+                          -0.524319 -0.728839 0.440322,
+                          -1 1.44497e-16 3.70928e-15,
+                          -1 1.44497e-16 3.70928e-15,
+                          -1 1.44497e-16 3.70928e-15,
+                          0.00513697 5.97799e-16 0.999987,
+                          0.00513697 5.97799e-16 0.999987,
+                          0.00513697 5.97799e-16 0.999987,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -1 1.44497e-16 3.70928e-15,
+                          -1 1.44497e-16 3.70928e-15,
+                          -1 1.44497e-16 3.70928e-15,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          0.566073 4.11621e-16 0.824355,
+                          0.546578 4.22251e-16 0.837408,
+                          0.280995 5.3383e-16 0.959709,
+                          -0.310718 0.937957 0.153918,
+                          -0.153822 0.987071 0.0450605,
+                          -0.252576 0.953426 0.164878,
+                          -0.178731 0.983029 0.0413357,
+                          0.00111921 0.999999 -6.02884e-16,
+                          -0.153822 0.987071 0.0450605,
+                          -0.310718 0.937957 0.153918,
+                          -0.178731 0.983029 0.0413357,
+                          -0.153822 0.987071 0.0450605,
+                          0.566073 4.11621e-16 0.824355,
+                          0.77293 2.68088e-16 0.634492,
+                          0.546578 4.22251e-16 0.837408,
+                          -0.35891 0.883365 0.301412,
+                          -0.252576 0.953426 0.164878,
+                          -0.255805 0.915144 0.311569,
+                          -0.35891 0.883365 0.301412,
+                          -0.310718 0.937957 0.153918,
+                          -0.252576 0.953426 0.164878,
+                          -0.32386 0.832602 0.44932,
+                          -0.35891 0.883365 0.301412,
+                          -0.255805 0.915144 0.311569,
+                          0.546578 4.22251e-16 0.837408,
+                          0.77293 2.68088e-16 0.634492,
+                          0.566073 4.11621e-16 0.824355,
+                          -0.35891 -0.883365 0.301412,
+                          -0.255805 -0.915144 0.311569,
+                          -0.252576 -0.953426 0.164878,
+                          -0.32386 -0.832602 0.44932,
+                          -0.223673 -0.782355 0.581284,
+                          -0.255805 -0.915144 0.311569,
+                          -0.35891 -0.883365 0.301412,
+                          -0.32386 -0.832602 0.44932,
+                          -0.255805 -0.915144 0.311569,
+                          -0.310718 -0.937957 0.153918,
+                          -0.252576 -0.953426 0.164878,
+                          -0.153822 -0.987071 0.0450605,
+                          -0.310718 -0.937957 0.153918,
+                          -0.35891 -0.883365 0.301412,
+                          -0.252576 -0.953426 0.164878,
+                          -0.178731 -0.983029 0.0413357,
+                          -0.310718 -0.937957 0.153918,
+                          -0.153822 -0.987071 0.0450605,
+                          0.990422 0.132158 -0.03999,
+                          0.979866 0.195695 -0.0395638,
+                          0.990489 0.131653 -0.0399927,
+                          -0.167698 0.725799 0.667153,
+                          -0.0309904 0.49665 0.867397,
+                          -0.0623735 0.48829 0.870449,
+                          0.99699 0.0662598 -0.0402552,
+                          0.990422 0.132158 -0.03999,
+                          0.990489 0.131653 -0.0399927,
+                          0.997108 0.0644586 -0.04026,
+                          0.99699 0.0662598 -0.0402552,
+                          0.990489 0.131653 -0.0399927,
+                          -0.121314 0.972742 0.197626,
+                          -0.0463338 0.935505 0.350263,
+                          -0.107712 0.922766 0.370002,
+                          -0.120963 0.739544 0.66215,
+                          -0.0309904 0.49665 0.867397,
+                          -0.167698 0.725799 0.667153,
+                          -0.120963 0.739544 0.66215,
+                          -0.073183 0.750214 0.657133,
+                          -0.0309904 0.49665 0.867397,
+                          0.990422 0.132158 -0.03999,
+                          0.979784 0.196108 -0.0395605,
+                          0.979866 0.195695 -0.0395638,
+                          -0.130591 0.802524 -0.582152,
+                          -0.143477 0.550998 -0.82208,
+                          -0.108183 0.562774 -0.819501,
+                          -0.0403439 -5.92232e-16 -0.999186,
+                          -0.0403439 -5.92232e-16 -0.999186,
+                          -0.0403439 -5.92232e-16 -0.999186,
+                          0.00198165 -0.999998 5.90873e-16,
+                          -0.30567 -0.94951 0.0706932,
+                          0.00111921 -0.999999 5.94214e-16,
+                          -0.0403439 -5.92232e-16 -0.999186,
+                          -0.0403439 -5.92232e-16 -0.999186,
+                          -0.0403439 -5.92232e-16 -0.999186,
+                          0.990489 -0.131653 -0.0399927,
+                          0.990422 -0.132158 -0.03999,
+                          0.99699 -0.0662598 -0.0402552,
+                          0.997082 -0.0648573 -0.0402589,
+                          0.990489 -0.131653 -0.0399927,
+                          0.99699 -0.0662598 -0.0402552,
+                          0.979866 -0.195695 -0.0395638,
+                          0.979784 -0.196108 -0.0395605,
+                          0.990422 -0.132158 -0.03999,
+                          -0.231107 -0.772806 -0.591067,
+                          -0.108183 -0.562774 -0.819501,
+                          -0.143477 -0.550998 -0.82208,
+                          0.990489 -0.131653 -0.0399927,
+                          0.979866 -0.195695 -0.0395638,
+                          0.990422 -0.132158 -0.03999,
+                          -0.30567 -0.94951 0.0706932,
+                          -0.178731 -0.983029 0.0413357,
+                          0.00111921 -0.999999 5.94214e-16,
+                          -0.181723 -0.789718 -0.585937,
+                          -0.108183 -0.562774 -0.819501,
+                          -0.231107 -0.772806 -0.591067,
+                          -0.0403439 -5.92232e-16 -0.999186,
+                          -0.0403439 -5.92232e-16 -0.999186,
+                          -0.0403439 -5.92232e-16 -0.999186,
+                          -0.181723 -0.789718 -0.585937,
+                          -0.130591 -0.802524 -0.582152,
+                          -0.108183 -0.562774 -0.819501,
+                          -0.073183 -0.750214 0.657133,
+                          -0.0623735 -0.48829 0.870449,
+                          -0.0309904 -0.49665 0.867397,
+                          0.00697109 -0.984958 0.172651,
+                          -0.107692 -0.922683 0.370214,
+                          -0.0467072 -0.935481 0.350278,
+                          -0.056351 -0.981127 0.184971,
+                          -0.107692 -0.922683 0.370214,
+                          0.00697109 -0.984958 0.172651,
+                          -0.121306 -0.972718 0.197751,
+                          -0.107692 -0.922683 0.370214,
+                          -0.056351 -0.981127 0.184971,
+                          0.147217 -0.989086 -0.00594414,
+                          0.190641 -0.98163 -0.00769747,
+                          0.0957621 -0.995397 -0.00386656,
+                          -0.0300847 6.02626e-16 0.999547,
+                          0.0054554 -0.00335952 0.999979,
+                          0.0063712 -0.00660385 0.999958,
+                          -0.524319 -0.728839 0.440322,
+                          -0.445741 -0.647208 0.618415,
+                          -0.35891 -0.883365 0.301412,
+                          0.285752 -0.958234 -0.0115377,
+                          0.238695 -0.971047 -0.00963772,
+                          0.190641 -0.98163 -0.00769747,
+                          0.0403439 -9.2078e-15 0.999186,
+                          0.0403439 -9.2078e-15 0.999186,
+                          0.0403439 -9.2078e-15 0.999186,
+                          0.147217 -0.989086 -0.00594414,
+                          0.285752 -0.958234 -0.0115377,
+                          0.190641 -0.98163 -0.00769747,
+                          -0.0275279 -0.013184 0.999534,
+                          -0.0300847 6.02626e-16 0.999547,
+                          0.0063712 -0.00660385 0.999958,
+                          -0.445741 -0.647208 0.618415,
+                          -0.32386 -0.832602 0.44932,
+                          -0.35891 -0.883365 0.301412,
+                          0.0403439 -9.2078e-15 0.999186,
+                          0.0403439 -9.2078e-15 0.999186,
+                          0.0403439 -9.2078e-15 0.999186,
+                          0.285752 -0.958234 -0.0115377,
+                          0.285752 -0.958234 -0.0115377,
+                          0.238695 -0.971047 -0.00963772,
+                          0.0403439 -9.2078e-15 0.999186,
+                          0.0403439 -9.2078e-15 0.999186,
+                          0.0403439 -9.2078e-15 0.999186,
+                          0.71352 -0.700042 -0.0288096,
+                          0.71352 -0.700042 -0.0288096,
+                          0.285752 -0.958234 -0.0115377,
+                          0.0403439 -1.39622e-15 0.999186,
+                          0.0403439 -1.39622e-15 0.999186,
+                          0.0403439 -1.39622e-15 0.999186,
+                          0.285752 -0.958234 -0.0115377,
+                          0.71352 -0.700042 -0.0288096,
+                          0.285752 -0.958234 -0.0115377,
+                          -0.0403439 1.39622e-15 -0.999186,
+                          -0.0403439 1.39622e-15 -0.999186,
+                          -0.0403439 1.39622e-15 -0.999186,
+                          -0.0403439 1.39622e-15 -0.999186,
+                          -0.0403439 1.39622e-15 -0.999186,
+                          -0.0403439 1.39622e-15 -0.999186,
+                          -0.0403439 1.39622e-15 -0.999186,
+                          -0.0403439 1.39622e-15 -0.999186,
+                          -0.0403439 1.39622e-15 -0.999186,
+                          0.285752 0.958234 -0.0115377,
+                          0.285752 0.958234 -0.0115377,
+                          0.147217 0.989086 -0.00594414,
+                          -0.0403439 -1.04865e-14 -0.999186,
+                          -0.0403439 -1.04865e-14 -0.999186,
+                          -0.0403439 -1.04865e-14 -0.999186,
+                          0.238695 0.971047 -0.00963772,
+                          0.285752 0.958234 -0.0115377,
+                          0.147217 0.989086 -0.00594414,
+                          0.190641 0.98163 -0.00769747,
+                          0.238695 0.971047 -0.00963772,
+                          0.147217 0.989086 -0.00594414,
+                          0.0957621 0.995397 -0.00386656,
+                          0.190641 0.98163 -0.00769747,
+                          0.147217 0.989086 -0.00594414,
+                          0.71352 0.700042 -0.0288096,
+                          0.71352 0.700042 -0.0288096,
+                          0.285752 0.958234 -0.0115377,
+                          -0.0403439 -3.17313e-15 -0.999186,
+                          -0.0403439 -3.17313e-15 -0.999186,
+                          -0.0403439 -3.17313e-15 -0.999186,
+                          0.285752 0.958234 -0.0115377,
+                          0.71352 0.700042 -0.0288096,
+                          0.285752 0.958234 -0.0115377,
+                          0.0403439 3.17483e-15 0.999186,
+                          0.0403439 3.17483e-15 0.999186,
+                          0.0403439 3.17483e-15 0.999186,
+                          0.0403439 3.17483e-15 0.999186,
+                          0.0403439 3.17483e-15 0.999186,
+                          0.0403439 3.17483e-15 0.999186,
+                          0.0403439 3.17483e-15 0.999186,
+                          0.0403439 3.17483e-15 0.999186,
+                          0.0403439 3.17483e-15 0.999186,
+                          0.0403439 1.04835e-14 0.999186,
+                          0.0403439 1.04835e-14 0.999186,
+                          0.0403439 1.04835e-14 0.999186,
+                          0.0403439 1.04835e-14 0.999186,
+                          0.0403439 1.04835e-14 0.999186,
+                          0.0403439 1.04835e-14 0.999186,
+                          -0.0275279 0.013184 0.999534,
+                          0.0063712 0.00660385 0.999958,
+                          0.0054554 0.00335952 0.999979,
+                          -3.81171e-15 -5.98549e-16 -1,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -0.546578 -4.22251e-16 -0.837408,
+                          0.0403439 1.04835e-14 0.999186,
+                          0.0403439 1.04835e-14 0.999186,
+                          0.0403439 1.04835e-14 0.999186,
+                          -0.0300847 6.02626e-16 0.999547,
+                          -0.0275279 0.013184 0.999534,
+                          0.0054554 0.00335952 0.999979,
+                          2.27764e-16 1 -6.17631e-16,
+                          2.27764e-16 1 -6.17631e-16,
+                          2.27764e-16 1 -6.17631e-16,
+                          2.27764e-16 1 -6.17631e-16,
+                          2.27764e-16 1 -6.17631e-16,
+                          2.27764e-16 1 -6.17631e-16,
+                          -0.49076 -0.836693 0.243104,
+                          -0.310718 -0.937957 0.153918,
+                          -0.178731 -0.983029 0.0413357,
+                          2.27764e-16 1 -6.17631e-16,
+                          2.27764e-16 1 -6.17631e-16,
+                          2.27764e-16 1 -6.17631e-16,
+                          -6.12303e-17 -1 1.17274e-15,
+                          -6.12303e-17 -1 1.17274e-15,
+                          -6.12303e-17 -1 1.17274e-15,
+                          -0.147217 -0.989086 0.00594414,
+                          -1.31619e-14 -1 1.70183e-15,
+                          -1.31619e-14 -1 1.70183e-15,
+                          -0.804806 -0.276181 0.525367,
+                          -0.524319 -0.728839 0.440322,
+                          -0.49076 -0.836693 0.243104,
+                          -6.12303e-17 -1 1.17274e-15,
+                          -6.12303e-17 -1 1.17274e-15,
+                          -6.12303e-17 -1 1.17274e-15,
+                          -6.12303e-17 -1 1.17274e-15,
+                          -6.12303e-17 -1 1.17274e-15,
+                          -6.12303e-17 -1 1.17274e-15,
+                          -0.147217 0.989086 0.00594414,
+                          -2.20364e-17 1 -6.08958e-16,
+                          -0.190641 0.98163 0.00769747,
+                          -2.20364e-17 1 -6.08958e-16,
+                          -2.20364e-17 1 -6.08958e-16,
+                          -0.147217 0.989086 0.00594414,
+                          -0.524319 -0.728839 0.440322,
+                          -0.35891 -0.883365 0.301412,
+                          -0.310718 -0.937957 0.153918,
+                          -0.147217 0.989086 0.00594414,
+                          -0.190641 0.98163 0.00769747,
+                          -0.285752 0.958234 0.0115377,
+                          -0.285752 0.958234 0.0115377,
+                          -0.285752 0.958234 0.0115377,
+                          -0.71352 0.700042 0.0288096,
+                          -0.147217 0.989086 0.00594414,
+                          -0.285752 0.958234 0.0115377,
+                          -0.285752 0.958234 0.0115377,
+                          -0.71352 0.700042 0.0288096,
+                          -0.71352 0.700042 0.0288096,
+                          -0.965139 0.258819 0.0389692,
+                          -0.285752 0.958234 0.0115377,
+                          -0.71352 0.700042 0.0288096,
+                          -0.71352 0.700042 0.0288096,
+                          -0.71352 0.700042 0.0288096,
+                          -0.965139 0.258819 0.0389692,
+                          -0.965139 0.258819 0.0389692,
+                          -0.965139 0.258819 0.0389692,
+                          -0.965139 0.258819 0.0389692,
+                          -0.965139 0.258819 0.0389692,
+                          -0.965139 0.258819 0.0389692,
+                          -0.965139 0.258819 0.0389692,
+                          -0.965139 0.258819 0.0389692,
+                          -0.965139 0.258819 0.0389692,
+                          -0.965139 0.258819 0.0389692,
+                          -0.965139 0.258819 0.0389692,
+                          -0.965139 0.258819 0.0389692,
+                          -0.965139 0.258819 0.0389692,
+                          -0.965139 0.258819 0.0389692,
+                          -0.190641 -0.98163 0.00769747,
+                          -0.147217 -0.989086 0.00594414,
+                          -0.285752 -0.958234 0.0115377,
+                          -1.31619e-14 -1 1.70183e-15,
+                          -0.147217 -0.989086 0.00594414,
+                          -0.190641 -0.98163 0.00769747,
+                          -0.285752 -0.958234 0.0115377,
+                          -0.285752 -0.958234 0.0115377,
+                          -0.71352 -0.700042 0.0288096,
+                          0.00858026 -0.999963 5.65297e-16,
+                          -0.30567 -0.94951 0.0706932,
+                          0.00198165 -0.999998 5.90873e-16,
+                          -0.190641 -0.98163 0.00769747,
+                          -0.285752 -0.958234 0.0115377,
+                          -0.285752 -0.958234 0.0115377,
+                          -0.71352 -0.700042 0.0288096,
+                          -0.71352 -0.700042 0.0288096,
+                          -0.965139 -0.258819 0.0389692,
+                          -0.285752 -0.958234 0.0115377,
+                          -0.71352 -0.700042 0.0288096,
+                          -0.71352 -0.700042 0.0288096,
+                          -0.71352 -0.700042 0.0288096,
+                          -0.965139 -0.258819 0.0389692,
+                          -0.965139 -0.258819 0.0389692,
+                          -0.965139 -0.258819 0.0389692,
+                          -0.965139 -0.258819 0.0389692,
+                          -0.965139 -0.258819 0.0389692,
+                          -0.965139 -0.258819 0.0389692,
+                          -0.965139 -0.258819 0.0389692,
+                          -0.965139 -0.258819 0.0389692,
+                          -0.965139 -0.258819 0.0389692,
+                          -0.965139 -0.258819 0.0389692,
+                          -0.965139 -0.258819 0.0389692,
+                          -0.965139 -0.258819 0.0389692,
+                          -0.965139 -0.258819 0.0389692,
+                          -0.965139 -0.258819 0.0389692,
+                          -0.445741 0.647208 0.618415,
+                          -0.223673 0.782355 0.581284,
+                          -0.2929 0.578616 0.761192,
+                          -0.445741 0.647208 0.618415,
+                          -0.32386 0.832602 0.44932,
+                          -0.223673 0.782355 0.581284,
+                          -0.621456 0.202115 0.756929,
+                          -0.2929 0.578616 0.761192,
+                          -0.354397 0.161686 0.921011,
+                          -0.621456 0.202115 0.756929,
+                          -0.445741 0.647208 0.618415,
+                          -0.2929 0.578616 0.761192,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -0.77293 -2.68088e-16 -0.634492,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -0.170351 -0.880334 0.442711,
+                          -0.170351 -0.880334 0.442711,
+                          -0.170351 -0.880334 0.442711,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -0.170351 -0.880334 0.442711,
+                          -0.170351 -0.880334 0.442711,
+                          -0.170351 -0.880334 0.442711,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -0.445741 -0.647208 0.618415,
+                          -0.354397 -0.161686 0.921011,
+                          -0.2929 -0.578616 0.761192,
+                          -0.77293 -2.68088e-16 -0.634492,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -0.621456 -0.202115 0.756929,
+                          -0.354397 -0.161686 0.921011,
+                          -0.445741 -0.647208 0.618415,
+                          -0.32386 -0.832602 0.44932,
+                          -0.2929 -0.578616 0.761192,
+                          -0.223673 -0.782355 0.581284,
+                          -0.445741 -0.647208 0.618415,
+                          -0.2929 -0.578616 0.761192,
+                          -0.32386 -0.832602 0.44932,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.30567 -0.94951 0.0706932,
+                          -0.49076 -0.836693 0.243104,
+                          -0.178731 -0.983029 0.0413357,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.997108 -0.0644586 0.04026,
+                          -0.999186 2.29758e-16 0.0403439,
+                          -0.999186 2.29758e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.49076 -0.836693 0.243104,
+                          -0.524319 -0.728839 0.440322,
+                          -0.310718 -0.937957 0.153918,
+                          -0.965139 -0.258819 0.0389692,
+                          -0.965139 -0.258819 0.0389692,
+                          -0.965139 -0.258819 0.0389692,
+                          -0.979784 -0.196108 0.0395605,
+                          -0.965139 -0.258819 0.0389692,
+                          -0.965139 -0.258819 0.0389692,
+                          -0.979866 -0.195695 0.0395638,
+                          -0.965139 -0.258819 0.0389692,
+                          -0.979784 -0.196108 0.0395605,
+                          -0.965139 0.258819 0.0389692,
+                          -0.965139 0.258819 0.0389692,
+                          -0.965139 0.258819 0.0389692,
+                          -0.979866 0.195695 0.0395638,
+                          -0.965139 0.258819 0.0389692,
+                          -0.965139 0.258819 0.0389692,
+                          -0.979866 0.195695 0.0395638,
+                          -0.979784 0.196108 0.0395605,
+                          -0.965139 0.258819 0.0389692,
+                          -0.979866 -0.195695 0.0395638,
+                          -0.979784 -0.196108 0.0395605,
+                          -0.990422 -0.132158 0.03999,
+                          -0.990489 -0.131653 0.0399927,
+                          -0.990422 -0.132158 0.03999,
+                          -0.999186 2.29758e-16 0.0403439,
+                          -0.979866 -0.195695 0.0395638,
+                          -0.990422 -0.132158 0.03999,
+                          -0.990489 -0.131653 0.0399927,
+                          -0.997108 -0.0644586 0.04026,
+                          -0.990489 -0.131653 0.0399927,
+                          -0.999186 2.29758e-16 0.0403439,
+                          -0.990489 0.131653 0.0399927,
+                          -0.999186 1.07297e-16 0.0403439,
+                          -0.990422 0.132158 0.03999,
+                          -0.997082 0.0648573 0.0402589,
+                          -0.999186 1.07297e-16 0.0403439,
+                          -0.999186 1.07297e-16 0.0403439,
+                          -0.990489 0.131653 0.0399927,
+                          -0.997082 0.0648573 0.0402589,
+                          -0.999186 1.07297e-16 0.0403439,
+                          -0.979866 0.195695 0.0395638,
+                          -0.990422 0.132158 0.03999,
+                          -0.979784 0.196108 0.0395605,
+                          -0.979866 0.195695 0.0395638,
+                          -0.990489 0.131653 0.0399927,
+                          -0.990422 0.132158 0.03999,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -0.986666 4.51512e-17 -0.162759,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -0.986666 4.51512e-17 -0.162759,
+                          -0.986666 4.51512e-17 -0.162759,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          0.00858026 -0.999963 5.65297e-16,
+                          -0.49076 -0.836693 0.243104,
+                          -0.30567 -0.94951 0.0706932,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.986666 4.51512e-17 -0.162759,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.986666 4.51512e-17 -0.162759,
+                          -0.999186 1.68527e-16 0.0403439,
+                          -0.986666 4.51512e-17 -0.162759,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.81171e-15 -5.98549e-16 -1,
+                          -3.81171e-15 -5.98549e-16 -1,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -0.546578 -4.22251e-16 -0.837408,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -3.81171e-15 -5.98549e-16 -1,
+                          -0.546578 -4.22251e-16 -0.837408,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -0.77293 -2.68088e-16 -0.634492,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -0.546578 -4.22251e-16 -0.837408,
+                          -3.81171e-15 -5.98549e-16 -1,
+                          -3.81171e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -3.87294e-15 -5.98549e-16 -1,
+                          -0.77293 -2.68088e-16 -0.634492,
+                          -0.933291 -8.00944e-17 -0.359122,
+                          -0.546578 -4.22251e-16 -0.837408,
+                          0.00198165 0.999998 -6.06223e-16,
+                          0.00111921 0.999999 -6.02884e-16,
+                          -0.178731 0.983029 0.0413357,
+                          -0.30567 0.94951 0.0706932,
+                          -0.178731 0.983029 0.0413357,
+                          -0.310718 0.937957 0.153918,
+                          -0.30567 0.94951 0.0706932,
+                          0.00198165 0.999998 -6.06223e-16,
+                          -0.178731 0.983029 0.0413357,
+                          -0.49076 0.836693 0.243104,
+                          -0.310718 0.937957 0.153918,
+                          -0.35891 0.883365 0.301412,
+                          -0.49076 0.836693 0.243104,
+                          -0.30567 0.94951 0.0706932,
+                          -0.310718 0.937957 0.153918,
+                          -0.524319 0.728839 0.440322,
+                          -0.35891 0.883365 0.301412,
+                          -0.32386 0.832602 0.44932,
+                          -0.524319 0.728839 0.440322,
+                          -0.49076 0.836693 0.243104,
+                          -0.35891 0.883365 0.301412,
+                          -0.445741 0.647208 0.618415,
+                          -0.524319 0.728839 0.440322,
+                          -0.32386 0.832602 0.44932,
+                          0.00858026 0.999963 -6.31758e-16,
+                          0.00198165 0.999998 -6.06223e-16,
+                          -0.30567 0.94951 0.0706932,
+                          0.00858026 0.999963 -6.31758e-16,
+                          -0.30567 0.94951 0.0706932,
+                          -0.49076 0.836693 0.243104,
+                          -0.621456 0.202115 0.756929,
+                          -0.804806 0.276181 0.525367,
+                          -0.524319 0.728839 0.440322,
+                          -0.804806 0.276181 0.525367,
+                          -0.49076 0.836693 0.243104,
+                          -0.524319 0.728839 0.440322,
+                          -0.804806 0.276181 0.525367,
+                          0.00858026 0.999963 -6.31758e-16,
+                          -0.49076 0.836693 0.243104,
+                          -0.621456 0.202115 0.756929,
+                          -0.524319 0.728839 0.440322,
+                          -0.445741 0.647208 0.618415 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 48.5449 115 567,
+                          14.8041 82.9463 567,
+                          47.2102 66 567,
+                          47.2102 66 566,
+                          47.2102 66 567,
+                          14.8041 82.9463 567,
+                          48.5449 66 567,
+                          48.5449 115 567,
+                          47.2102 66 567,
+                          48.5449 66 566.667,
+                          48.5449 66 567,
+                          47.2102 66 567,
+                          48.5449 66 566.333,
+                          48.5449 66 566.667,
+                          47.2102 66 567,
+                          48.5449 66 566,
+                          48.5449 66 566.333,
+                          47.2102 66 567,
+                          47.2102 66 566,
+                          48.5449 66 566,
+                          47.2102 66 567,
+                          48.5449 115 567,
+                          -20.4705 92.5699 567,
+                          14.8041 82.9463 567,
+                          14.8041 82.9463 566,
+                          14.8041 82.9463 567,
+                          -20.4705 92.5699 567,
+                          14.8041 82.9463 566,
+                          47.2102 66 566,
+                          14.8041 82.9463 567,
+                          48.5449 115 567,
+                          -57 94.4281 567,
+                          -20.4705 92.5699 567,
+                          -20.4705 92.5699 566,
+                          -20.4705 92.5699 567,
+                          -57 94.4281 567,
+                          14.8041 82.9463 566,
+                          -20.4705 92.5699 567,
+                          -20.4705 92.5699 566,
+                          48.5449 115 567,
+                          -57 115 567,
+                          -57 94.4281 567,
+                          -57 94.4281 566,
+                          -57 94.4281 567,
+                          -57 115 567,
+                          -20.4705 92.5699 566,
+                          -57 94.4281 567,
+                          -57 94.4281 566,
+                          -57 115 566,
+                          -57 115 567,
+                          48.5449 115 567,
+                          -57 94.4281 566,
+                          -57 115 567,
+                          -57 115 566,
+                          48.854 65.9743 566.956,
+                          48.5449 115 567,
+                          48.5449 66 567,
+                          49.1673 115 566.806,
+                          49.5716 115 566.295,
+                          48.5449 115 567,
+                          48.5449 115 566,
+                          48.5449 115 567,
+                          49.5716 115 566.295,
+                          49.1462 65.8965 566.821,
+                          49.1673 115 566.806,
+                          48.5449 115 567,
+                          48.854 65.9743 566.956,
+                          49.1462 65.8965 566.821,
+                          48.5449 115 567,
+                          48.5449 115 566,
+                          -57 115 566,
+                          48.5449 115 567,
+                          48.7177 65.9837 566.647,
+                          48.854 65.9743 566.956,
+                          48.5449 66 567,
+                          48.5449 66 566.667,
+                          48.7177 65.9837 566.647,
+                          48.5449 66 567,
+                          -57 -115 567,
+                          -29.1903 -93.6551 567,
+                          -57 -94.4281 567,
+                          -57 -94.4281 566,
+                          -57 -94.4281 567,
+                          -29.1903 -93.6551 567,
+                          -57 -115 566,
+                          -57 -115 567,
+                          -57 -94.4281 567,
+                          -57 -94.4281 566,
+                          -57 -115 566,
+                          -57 -94.4281 567,
+                          -57 -115 567,
+                          -1.89655 -88.1989 567,
+                          -29.1903 -93.6551 567,
+                          -29.1903 -93.6551 566,
+                          -29.1903 -93.6551 567,
+                          -1.89655 -88.1989 567,
+                          -29.1903 -93.6551 566,
+                          -57 -94.4281 566,
+                          -29.1903 -93.6551 567,
+                          -57 -115 567,
+                          24.0854 -78.2163 567,
+                          -1.89655 -88.1989 567,
+                          -1.89655 -88.1989 566,
+                          -1.89655 -88.1989 567,
+                          24.0854 -78.2163 567,
+                          -29.1903 -93.6551 566,
+                          -1.89655 -88.1989 567,
+                          -1.89655 -88.1989 566,
+                          48.5449 -64 567,
+                          48 -64 567,
+                          24.0854 -78.2163 567,
+                          24.0854 -78.2163 566,
+                          24.0854 -78.2163 567,
+                          48 -64 567,
+                          48.5449 -115 567,
+                          48.5449 -64 567,
+                          24.0854 -78.2163 567,
+                          -57 -115 567,
+                          48.5449 -115 567,
+                          24.0854 -78.2163 567,
+                          -1.89655 -88.1989 566,
+                          24.0854 -78.2163 567,
+                          24.0854 -78.2163 566,
+                          48.5449 -64 566.667,
+                          48 -64 567,
+                          48.5449 -64 567,
+                          48.5449 -64 566.333,
+                          48 -64 567,
+                          48.5449 -64 566.667,
+                          48.5449 -64 566,
+                          48 -64 567,
+                          48.5449 -64 566.333,
+                          48 -64 566,
+                          48 -64 567,
+                          48.5449 -64 566,
+                          24.0854 -78.2163 566,
+                          48 -64 567,
+                          48 -64 566,
+                          49.1673 -115 566.806,
+                          48.5449 -64 567,
+                          48.5449 -115 567,
+                          49.1673 -115 566.806,
+                          48.854 -63.9743 566.956,
+                          48.5449 -64 567,
+                          48.5449 -64 566.667,
+                          48.5449 -64 567,
+                          48.854 -63.9743 566.956,
+                          48.5449 -115 566,
+                          48.5449 -115 567,
+                          -57 -115 567,
+                          48.5449 -115 566,
+                          49.1673 -115 566.806,
+                          48.5449 -115 567,
+                          -57 -115 566,
+                          48.5449 -115 566,
+                          -57 -115 567,
+                          57.3044 -51.9904 546.199,
+                          49.5716 -63.593 566.295,
+                          49.5716 -115 566.295,
+                          49.3952 -63.7686 566.598,
+                          49.5716 -115 566.295,
+                          49.5716 -63.593 566.295,
+                          95.5836 115 446.718,
+                          57.3044 -51.9904 546.199,
+                          49.5716 -115 566.295,
+                          95.5836 -115 446.718,
+                          95.5836 115 446.718,
+                          49.5716 -115 566.295,
+                          94.6503 -115 446.359,
+                          95.5836 -115 446.718,
+                          49.5716 -115 566.295,
+                          49.1673 -115 566.806,
+                          49.5716 -115 566.295,
+                          49.3952 -63.7686 566.598,
+                          48.5449 -115 566,
+                          49.5716 -115 566.295,
+                          49.1673 -115 566.806,
+                          94.6503 -115 446.359,
+                          49.5716 -115 566.295,
+                          48.6383 -115 565.936,
+                          48.5449 66 566,
+                          48.5996 65.8965 565.984,
+                          48.7372 65.9339 566.288,
+                          48.6383 -115 565.936,
+                          49.5716 -115 566.295,
+                          48.5449 -115 566,
+                          49.2605 -63.593 566.175,
+                          49.5716 -63.593 566.295,
+                          57.3044 -51.9904 546.199,
+                          49.1668 -63.7372 566.348,
+                          49.3952 -63.7686 566.598,
+                          49.5716 -63.593 566.295,
+                          49.1668 -63.7372 566.348,
+                          49.5716 -63.593 566.295,
+                          49.2605 -63.593 566.175,
+                          95.5836 115 446.718,
+                          62.768 1 532,
+                          57.3044 -51.9904 546.199,
+                          56.3711 -51.9904 545.84,
+                          57.3044 -51.9904 546.199,
+                          62.768 1 532,
+                          48.9491 -63.593 566.055,
+                          49.2605 -63.593 566.175,
+                          57.3044 -51.9904 546.199,
+                          48.6383 -63.593 565.936,
+                          48.9491 -63.593 566.055,
+                          57.3044 -51.9904 546.199,
+                          56.3711 -51.9904 545.84,
+                          48.6383 -63.593 565.936,
+                          57.3044 -51.9904 546.199,
+                          95.5836 115 446.718,
+                          57.3044 53.9904 546.199,
+                          62.768 1 532,
+                          61.8347 1 531.641,
+                          62.768 1 532,
+                          57.3044 53.9904 546.199,
+                          61.8347 1 531.641,
+                          56.3711 -51.9904 545.84,
+                          62.768 1 532,
+                          95.5836 115 446.718,
+                          49.5716 65.593 566.295,
+                          57.3044 53.9904 546.199,
+                          56.3711 53.9904 545.84,
+                          57.3044 53.9904 546.199,
+                          49.5716 65.593 566.295,
+                          56.3711 53.9904 545.84,
+                          61.8347 1 531.641,
+                          57.3044 53.9904 546.199,
+                          95.5836 115 446.718,
+                          49.5716 115 566.295,
+                          49.5716 65.593 566.295,
+                          49.1673 115 566.806,
+                          49.5716 65.593 566.295,
+                          49.5716 115 566.295,
+                          49.3952 65.7686 566.598,
+                          49.5716 65.593 566.295,
+                          49.1673 115 566.806,
+                          49.2605 65.593 566.175,
+                          49.5716 65.593 566.295,
+                          49.3952 65.7686 566.598,
+                          49.2605 65.593 566.175,
+                          56.3711 53.9904 545.84,
+                          49.5716 65.593 566.295,
+                          48.6383 115 565.936,
+                          49.5716 115 566.295,
+                          95.5836 115 446.718,
+                          48.5996 65.8965 565.984,
+                          48.6222 65.7686 565.963,
+                          48.8234 65.851 566.232,
+                          48.6383 115 565.936,
+                          48.5449 115 566,
+                          49.5716 115 566.295,
+                          95.6904 -115 446.326,
+                          95.5836 115 446.718,
+                          95.5836 -115 446.718,
+                          95.6904 115 446.326,
+                          95.7154 115 445.919,
+                          95.5836 115 446.718,
+                          94.6503 115 446.359,
+                          95.5836 115 446.718,
+                          95.7154 115 445.919,
+                          95.6904 -115 446.326,
+                          95.6904 115 446.326,
+                          95.5836 115 446.718,
+                          48.6383 115 565.936,
+                          95.5836 115 446.718,
+                          94.6503 115 446.359,
+                          94.6503 -115 446.359,
+                          95.6904 -115 446.326,
+                          95.5836 -115 446.718,
+                          94.065 -115 405.045,
+                          95.7154 115 445.919,
+                          95.7154 -115 445.919,
+                          95.6904 115 446.326,
+                          95.7154 -115 445.919,
+                          95.7154 115 445.919,
+                          93.0658 -115 405.085,
+                          94.065 -115 405.045,
+                          95.7154 -115 445.919,
+                          95.6904 -115 446.326,
+                          95.7154 -115 445.919,
+                          95.6904 115 446.326,
+                          94.6503 -115 446.359,
+                          95.7154 -115 445.919,
+                          95.6904 -115 446.326,
+                          94.7037 -115 446.163,
+                          95.7154 -115 445.919,
+                          94.6503 -115 446.359,
+                          93.0658 -115 405.085,
+                          95.7154 -115 445.919,
+                          94.7162 -115 445.96,
+                          94.7037 -115 446.163,
+                          94.7162 -115 445.96,
+                          95.7154 -115 445.919,
+                          94.065 -115 405.045,
+                          94.065 115 405.045,
+                          95.7154 115 445.919,
+                          94.7162 115 445.96,
+                          95.7154 115 445.919,
+                          94.065 115 405.045,
+                          94.7037 115 446.163,
+                          94.6503 115 446.359,
+                          95.7154 115 445.919,
+                          94.7037 115 446.163,
+                          95.7154 115 445.919,
+                          94.7162 115 445.96,
+                          93.9165 -115.312 401.365,
+                          93.9165 115.312 401.365,
+                          94.065 115 405.045,
+                          93.0658 115 405.085,
+                          94.065 115 405.045,
+                          93.9165 115.312 401.365,
+                          94.065 -115 405.045,
+                          93.9165 -115.312 401.365,
+                          94.065 115 405.045,
+                          94.7162 115 445.96,
+                          94.065 115 405.045,
+                          93.0658 115 405.085,
+                          93.7723 -116.237 397.794,
+                          93.7723 116.237 397.794,
+                          93.9165 115.312 401.365,
+                          92.9173 115.312 401.405,
+                          93.9165 115.312 401.365,
+                          93.7723 116.237 397.794,
+                          93.9165 -115.312 401.365,
+                          93.7723 -116.237 397.794,
+                          93.9165 115.312 401.365,
+                          93.0658 115 405.085,
+                          93.9165 115.312 401.365,
+                          92.9173 115.312 401.405,
+                          88.6339 -116.237 270.534,
+                          88.6339 116.237 270.534,
+                          93.7723 116.237 397.794,
+                          88.6296 116.369 270.535,
+                          93.7723 116.237 397.794,
+                          88.6339 116.237 270.534,
+                          93.7723 -116.237 397.794,
+                          88.6339 -116.237 270.534,
+                          93.7723 116.237 397.794,
+                          93.7537 116.366 397.437,
+                          93.7723 116.237 397.794,
+                          88.6296 116.369 270.535,
+                          92.7357 116.368 397.124,
+                          93.7723 116.237 397.794,
+                          93.7537 116.366 397.437,
+                          92.9173 115.312 401.405,
+                          93.7723 116.237 397.794,
+                          92.7731 116.237 397.835,
+                          92.7566 116.301 397.478,
+                          92.7731 116.237 397.835,
+                          93.7723 116.237 397.794,
+                          92.7566 116.301 397.478,
+                          93.7723 116.237 397.794,
+                          92.7357 116.368 397.124,
+                          86.3288 -101.202 213.442,
+                          88.6339 116.5 270.534,
+                          88.6339 116.237 270.534,
+                          87.6348 116.5 270.575,
+                          88.6339 116.237 270.534,
+                          88.6339 116.5 270.534,
+                          88.6339 -116.237 270.534,
+                          86.3288 -101.202 213.442,
+                          88.6339 116.237 270.534,
+                          87.6348 116.237 270.575,
+                          88.6296 116.369 270.535,
+                          88.6339 116.237 270.534,
+                          87.6348 116.5 270.575,
+                          87.6348 116.237 270.575,
+                          88.6339 116.237 270.534,
+                          86.3288 -101.202 213.442,
+                          86.3288 101.202 213.442,
+                          88.6339 116.5 270.534,
+                          87.6348 116.5 270.575,
+                          88.6339 116.5 270.534,
+                          86.3288 101.202 213.442,
+                          86.2033 -100.793 210.336,
+                          86.1275 100.943 208.459,
+                          86.3288 101.202 213.442,
+                          85.3296 101.202 213.483,
+                          86.3288 101.202 213.442,
+                          86.1275 100.943 208.459,
+                          86.2666 -100.896 211.903,
+                          86.2033 -100.793 210.336,
+                          86.3288 101.202 213.442,
+                          86.3288 -101.202 213.442,
+                          86.2666 -100.896 211.903,
+                          86.3288 101.202 213.442,
+                          85.3296 101.202 213.483,
+                          87.6348 116.5 270.575,
+                          86.3288 101.202 213.442,
+                          85.9395 -102.729 203.801,
+                          85.9395 102.729 203.801,
+                          86.1275 100.943 208.459,
+                          85.1284 100.943 208.5,
+                          86.1275 100.943 208.459,
+                          85.9395 102.729 203.801,
+                          86.0657 -101.288 206.928,
+                          85.9395 -102.729 203.801,
+                          86.1275 100.943 208.459,
+                          86.2033 -100.793 210.336,
+                          86.0657 -101.288 206.928,
+                          86.1275 100.943 208.459,
+                          85.1284 100.943 208.5,
+                          85.3296 101.202 213.483,
+                          86.1275 100.943 208.459,
+                          85.2036 -114.564 185.577,
+                          85.2036 114.564 185.577,
+                          85.9395 102.729 203.801,
+                          84.9403 102.729 203.841,
+                          85.9395 102.729 203.801,
+                          85.2036 114.564 185.577,
+                          85.9395 -102.729 203.801,
+                          85.2036 -114.564 185.577,
+                          85.9395 102.729 203.801,
+                          84.9403 102.729 203.841,
+                          85.1284 100.943 208.5,
+                          85.9395 102.729 203.801,
+                          84.9862 -116.445 180.191,
+                          84.9862 116.445 180.191,
+                          85.2036 114.564 185.577,
+                          84.2044 114.564 185.617,
+                          85.2036 114.564 185.577,
+                          84.9862 116.445 180.191,
+                          85.2036 -114.564 185.577,
+                          84.9862 -116.445 180.191,
+                          85.2036 114.564 185.577,
+                          84.2044 114.564 185.617,
+                          84.9403 102.729 203.841,
+                          85.2036 114.564 185.577,
+                          84.7582 -115.626 174.546,
+                          84.7582 115.626 174.546,
+                          84.9862 116.445 180.191,
+                          83.987 116.445 180.232,
+                          84.9862 116.445 180.191,
+                          84.7582 115.626 174.546,
+                          84.9862 -116.445 180.191,
+                          84.7582 -115.626 174.546,
+                          84.9862 116.445 180.191,
+                          83.987 116.445 180.232,
+                          84.2044 114.564 185.617,
+                          84.9862 116.445 180.191,
+                          83 -98.0326 131,
+                          83 98.0326 131,
+                          84.7582 115.626 174.546,
+                          83.759 115.626 174.586,
+                          84.7582 115.626 174.546,
+                          83 98.0326 131,
+                          84.7582 -115.626 174.546,
+                          83 -98.0326 131,
+                          84.7582 115.626 174.546,
+                          83.759 115.626 174.586,
+                          83.987 116.445 180.232,
+                          84.7582 115.626 174.546,
+                          82.0008 98.0326 131.04,
+                          83 98.0326 131,
+                          83 -98.0326 131,
+                          82.0008 98.0326 131.04,
+                          83.759 115.626 174.586,
+                          83 98.0326 131,
+                          82.0008 -98.0326 131.04,
+                          83 -98.0326 131,
+                          84.7582 -115.626 174.546,
+                          82.0008 -98.0326 131.04,
+                          82.0008 98.0326 131.04,
+                          83 -98.0326 131,
+                          83.759 -115.626 174.586,
+                          84.7582 -115.626 174.546,
+                          84.9862 -116.445 180.191,
+                          83.759 -115.626 174.586,
+                          82.0008 -98.0326 131.04,
+                          84.7582 -115.626 174.546,
+                          83.987 -116.445 180.232,
+                          84.9862 -116.445 180.191,
+                          85.2036 -114.564 185.577,
+                          83.987 -116.445 180.232,
+                          83.759 -115.626 174.586,
+                          84.9862 -116.445 180.191,
+                          84.2044 -114.564 185.617,
+                          85.2036 -114.564 185.577,
+                          85.9395 -102.729 203.801,
+                          84.2044 -114.564 185.617,
+                          83.987 -116.445 180.232,
+                          85.2036 -114.564 185.577,
+                          84.9403 -102.729 203.841,
+                          85.9395 -102.729 203.801,
+                          86.0657 -101.288 206.928,
+                          84.9403 -102.729 203.841,
+                          84.2044 -114.564 185.617,
+                          85.9395 -102.729 203.801,
+                          85.0665 -101.288 206.968,
+                          86.0657 -101.288 206.928,
+                          86.2033 -100.793 210.336,
+                          85.0665 -101.288 206.968,
+                          84.9403 -102.729 203.841,
+                          86.0657 -101.288 206.928,
+                          85.2042 -100.793 210.377,
+                          86.2033 -100.793 210.336,
+                          86.2666 -100.896 211.903,
+                          85.2042 -100.793 210.377,
+                          85.0665 -101.288 206.968,
+                          86.2033 -100.793 210.336,
+                          85.2674 -100.896 211.943,
+                          86.2666 -100.896 211.903,
+                          86.3288 -101.202 213.442,
+                          85.2674 -100.896 211.943,
+                          85.2042 -100.793 210.377,
+                          86.2666 -100.896 211.903,
+                          88.6339 -116.237 270.534,
+                          88.6339 -116.5 270.534,
+                          86.3288 -101.202 213.442,
+                          85.3296 -101.202 213.483,
+                          86.3288 -101.202 213.442,
+                          88.6339 -116.5 270.534,
+                          85.3296 -101.202 213.483,
+                          85.2674 -100.896 211.943,
+                          86.3288 -101.202 213.442,
+                          87.6348 -116.237 270.575,
+                          88.6339 -116.5 270.534,
+                          88.6339 -116.237 270.534,
+                          87.6348 -116.5 270.575,
+                          85.3296 -101.202 213.483,
+                          88.6339 -116.5 270.534,
+                          87.6348 -116.237 270.575,
+                          87.6348 -116.5 270.575,
+                          88.6339 -116.5 270.534,
+                          93.7536 -116.366 397.435,
+                          88.6339 -116.237 270.534,
+                          93.7723 -116.237 397.794,
+                          88.6164 -116.501 270.535,
+                          88.6339 -116.237 270.534,
+                          88.6296 -116.369 270.535,
+                          93.7536 -116.366 397.435,
+                          88.6296 -116.369 270.535,
+                          88.6339 -116.237 270.534,
+                          87.6348 -116.237 270.575,
+                          88.6339 -116.237 270.534,
+                          88.6164 -116.501 270.535,
+                          92.7731 -116.237 397.835,
+                          93.7723 -116.237 397.794,
+                          93.9165 -115.312 401.365,
+                          92.7731 -116.237 397.835,
+                          93.7536 -116.366 397.435,
+                          93.7723 -116.237 397.794,
+                          92.9173 -115.312 401.405,
+                          93.9165 -115.312 401.365,
+                          94.065 -115 405.045,
+                          92.7731 -116.237 397.835,
+                          93.9165 -115.312 401.365,
+                          92.9173 -115.312 401.405,
+                          92.9173 -115.312 401.405,
+                          94.065 -115 405.045,
+                          93.0658 -115 405.085,
+                          75.6316 178.518 360.407,
+                          75.5763 178.724 360.409,
+                          75.5957 178.762 361.138,
+                          74.6112 178.465 360.448,
+                          75.5957 178.762 361.138,
+                          75.5763 178.724 360.409,
+                          88.5729 116.754 270.713,
+                          75.6316 178.518 360.407,
+                          75.5957 178.762 361.138,
+                          93.6695 116.754 396.938,
+                          88.5729 116.754 270.713,
+                          75.5957 178.762 361.138,
+                          92.7043 116.496 396.977,
+                          93.6695 116.754 396.938,
+                          75.5957 178.762 361.138,
+                          74.6112 178.465 360.448,
+                          74.6306 178.503 361.177,
+                          75.5957 178.762 361.138,
+                          92.7043 116.496 396.977,
+                          75.5957 178.762 361.138,
+                          74.6306 178.503 361.177,
+                          74.6664 178.259 360.446,
+                          75.5763 178.724 360.409,
+                          75.6316 178.518 360.407,
+                          74.6112 178.465 360.448,
+                          75.5763 178.724 360.409,
+                          74.6664 178.259 360.446,
+                          88.5729 116.754 270.713,
+                          73.7975 178.518 314.982,
+                          75.6316 178.518 360.407,
+                          73.294 179.4 315.002,
+                          75.6316 178.518 360.407,
+                          73.7975 178.518 314.982,
+                          75.1281 179.4 360.427,
+                          75.6316 178.518 360.407,
+                          73.294 179.4 315.002,
+                          74.6664 178.259 360.446,
+                          75.6316 178.518 360.407,
+                          75.1281 179.4 360.427,
+                          88.5729 116.754 270.713,
+                          73.4006 180 314.998,
+                          73.7975 178.518 314.982,
+                          72.8323 178.259 315.021,
+                          73.7975 178.518 314.982,
+                          73.4006 180 314.998,
+                          72.1529 178.958 315.048,
+                          73.294 179.4 315.002,
+                          73.7975 178.518 314.982,
+                          72.5806 178.7 315.031,
+                          72.1529 178.958 315.048,
+                          73.7975 178.518 314.982,
+                          72.8323 178.259 315.021,
+                          72.5806 178.7 315.031,
+                          73.7975 178.518 314.982,
+                          72.4354 179.741 315.037,
+                          73.4006 180 314.998,
+                          88.5729 116.754 270.713,
+                          72.4354 179.741 315.037,
+                          72.8323 178.259 315.021,
+                          73.4006 180 314.998,
+                          93.7019 116.628 397.01,
+                          88.5729 116.754 270.713,
+                          93.6695 116.754 396.938,
+                          88.5987 116.629 270.625,
+                          88.5729 116.754 270.713,
+                          93.7019 116.628 397.01,
+                          87.626 116.369 270.575,
+                          88.5729 116.754 270.713,
+                          88.5987 116.629 270.625,
+                          87.6078 116.496 270.752,
+                          72.4354 179.741 315.037,
+                          88.5729 116.754 270.713,
+                          87.6189 116.433 270.664,
+                          87.6078 116.496 270.752,
+                          88.5729 116.754 270.713,
+                          87.626 116.369 270.575,
+                          87.6189 116.433 270.664,
+                          88.5729 116.754 270.713,
+                          92.7043 116.496 396.977,
+                          93.7019 116.628 397.01,
+                          93.6695 116.754 396.938,
+                          75.5763 -178.724 360.409,
+                          93.6695 -116.754 396.938,
+                          75.5957 -178.762 361.138,
+                          74.6306 -178.503 361.177,
+                          75.5957 -178.762 361.138,
+                          93.6695 -116.754 396.938,
+                          74.6306 -178.503 361.177,
+                          75.5763 -178.724 360.409,
+                          75.5957 -178.762 361.138,
+                          73.7975 -178.518 314.982,
+                          88.5729 -116.754 270.713,
+                          93.6695 -116.754 396.938,
+                          88.5987 -116.629 270.625,
+                          93.6695 -116.754 396.938,
+                          88.5729 -116.754 270.713,
+                          75.6316 -178.518 360.407,
+                          73.7975 -178.518 314.982,
+                          93.6695 -116.754 396.938,
+                          75.5763 -178.724 360.409,
+                          75.6316 -178.518 360.407,
+                          93.6695 -116.754 396.938,
+                          93.7019 -116.628 397.01,
+                          93.6695 -116.754 396.938,
+                          88.5987 -116.629 270.625,
+                          92.7357 -116.368 397.124,
+                          93.6695 -116.754 396.938,
+                          93.7019 -116.628 397.01,
+                          92.7043 -116.496 396.977,
+                          74.6306 -178.503 361.177,
+                          93.6695 -116.754 396.938,
+                          92.7221 -116.432 397.05,
+                          92.7043 -116.496 396.977,
+                          93.6695 -116.754 396.938,
+                          92.7221 -116.432 397.05,
+                          93.6695 -116.754 396.938,
+                          92.7357 -116.368 397.124,
+                          73.7975 -178.518 314.982,
+                          73.4006 -180 314.998,
+                          88.5729 -116.754 270.713,
+                          87.6078 -116.496 270.752,
+                          88.5729 -116.754 270.713,
+                          73.4006 -180 314.998,
+                          87.6078 -116.496 270.752,
+                          88.5987 -116.629 270.625,
+                          88.5729 -116.754 270.713,
+                          72.4354 -179.741 315.037,
+                          73.4006 -180 314.998,
+                          73.7975 -178.518 314.982,
+                          72.4354 -179.741 315.037,
+                          87.6078 -116.496 270.752,
+                          73.4006 -180 314.998,
+                          75.1281 -179.4 360.427,
+                          73.7975 -178.518 314.982,
+                          75.6316 -178.518 360.407,
+                          73.294 -179.4 315.002,
+                          73.7975 -178.518 314.982,
+                          75.1281 -179.4 360.427,
+                          72.8323 -178.259 315.021,
+                          73.7975 -178.518 314.982,
+                          73.294 -179.4 315.002,
+                          72.4354 -179.741 315.037,
+                          73.7975 -178.518 314.982,
+                          72.8323 -178.259 315.021,
+                          74.6112 -178.465 360.448,
+                          75.6316 -178.518 360.407,
+                          75.5763 -178.724 360.409,
+                          73.9871 -178.958 360.473,
+                          75.1281 -179.4 360.427,
+                          75.6316 -178.518 360.407,
+                          74.4147 -178.7 360.456,
+                          73.9871 -178.958 360.473,
+                          75.6316 -178.518 360.407,
+                          74.6664 -178.259 360.446,
+                          74.4147 -178.7 360.456,
+                          75.6316 -178.518 360.407,
+                          74.6112 -178.465 360.448,
+                          74.6664 -178.259 360.446,
+                          75.6316 -178.518 360.407,
+                          74.6306 -178.503 361.177,
+                          74.6112 -178.465 360.448,
+                          75.5763 -178.724 360.409,
+                          15 -180 360.773,
+                          71.8672 -180 315.06,
+                          73.7008 -180 360.471,
+                          72.1616 -179.978 315.048,
+                          73.7008 -180 360.471,
+                          71.8672 -180 315.06,
+                          15 -179 360.773,
+                          15 -180 360.773,
+                          73.7008 -180 360.471,
+                          72.1616 -179.978 315.048,
+                          73.8926 -179.991 360.47,
+                          73.7008 -180 360.471,
+                          73.7008 -179 360.471,
+                          73.7008 -180 360.471,
+                          73.8926 -179.991 360.47,
+                          73.7008 -179 360.471,
+                          15 -179 360.773,
+                          73.7008 -180 360.471,
+                          15 -180 317.356,
+                          14.9073 -180 315.06,
+                          71.8672 -180 315.06,
+                          71.8672 -179 315.06,
+                          71.8672 -180 315.06,
+                          14.9073 -180 315.06,
+                          15 -180 360.773,
+                          15 -180 317.356,
+                          71.8672 -180 315.06,
+                          72.1616 -179.978 315.048,
+                          71.8672 -180 315.06,
+                          72.4387 -179.916 315.036,
+                          72.1529 -178.958 315.048,
+                          72.4387 -179.916 315.036,
+                          71.8672 -180 315.06,
+                          72.0144 -178.989 315.054,
+                          72.1529 -178.958 315.048,
+                          71.8672 -180 315.06,
+                          71.8672 -179 315.06,
+                          72.0144 -178.989 315.054,
+                          71.8672 -180 315.06,
+                          14.9073 -179 315.06,
+                          14.9073 -180 315.06,
+                          15 -180 317.356,
+                          14.9073 -179 315.06,
+                          71.8672 -179 315.06,
+                          14.9073 -180 315.06,
+                          15 -179 317.356,
+                          15 -180 317.356,
+                          15 -180 360.773,
+                          14.9073 -179 315.06,
+                          15 -180 317.356,
+                          15 -179 317.356,
+                          15 -179 360.773,
+                          15 -179 317.356,
+                          15 -180 360.773,
+                          14.9073 180 315.06,
+                          73.7008 180 360.471,
+                          71.8672 180 315.06,
+                          73.8926 179.991 360.47,
+                          71.8672 180 315.06,
+                          73.7008 180 360.471,
+                          14.9073 179 315.06,
+                          14.9073 180 315.06,
+                          71.8672 180 315.06,
+                          73.8926 179.991 360.47,
+                          72.1616 179.978 315.048,
+                          71.8672 180 315.06,
+                          72.1529 178.958 315.048,
+                          71.8672 180 315.06,
+                          72.1616 179.978 315.048,
+                          72.0144 178.989 315.054,
+                          71.8672 179 315.06,
+                          71.8672 180 315.06,
+                          14.9073 179 315.06,
+                          71.8672 180 315.06,
+                          71.8672 179 315.06,
+                          72.1529 178.958 315.048,
+                          72.0144 178.989 315.054,
+                          71.8672 180 315.06,
+                          15 180 317.356,
+                          15 180 360.773,
+                          73.7008 180 360.471,
+                          73.7008 179 360.471,
+                          73.7008 180 360.471,
+                          15 180 360.773,
+                          14.9073 180 315.06,
+                          15 180 317.356,
+                          73.7008 180 360.471,
+                          73.7008 179 360.471,
+                          73.8926 179.991 360.47,
+                          73.7008 180 360.471,
+                          48.6222 65.7686 565.963,
+                          48.8961 65.7372 566.153,
+                          48.8234 65.851 566.232,
+                          15 179 360.773,
+                          15 180 360.773,
+                          15 180 317.356,
+                          15 179 360.773,
+                          73.7008 179 360.471,
+                          15 180 360.773,
+                          15 179 317.356,
+                          15 180 317.356,
+                          14.9073 180 315.06,
+                          15 179 317.356,
+                          15 179 360.773,
+                          15 180 317.356,
+                          14.9073 179 315.06,
+                          15 179 317.356,
+                          14.9073 180 315.06,
+                          49.1673 -115 566.806,
+                          49.1462 -63.8965 566.821,
+                          48.854 -63.9743 566.956,
+                          48.8853 -63.9339 566.587,
+                          48.854 -63.9743 566.956,
+                          49.1462 -63.8965 566.821,
+                          48.7177 -63.9837 566.647,
+                          48.5449 -64 566.667,
+                          48.854 -63.9743 566.956,
+                          48.8853 -63.9339 566.587,
+                          48.7177 -63.9837 566.647,
+                          48.854 -63.9743 566.956,
+                          49.1673 -115 566.806,
+                          49.3952 -63.7686 566.598,
+                          49.1462 -63.8965 566.821,
+                          49.038 -63.851 566.487,
+                          49.1462 -63.8965 566.821,
+                          49.3952 -63.7686 566.598,
+                          49.038 -63.851 566.487,
+                          48.8853 -63.9339 566.587,
+                          49.1462 -63.8965 566.821,
+                          49.1668 -63.7372 566.348,
+                          49.038 -63.851 566.487,
+                          49.3952 -63.7686 566.598,
+                          49.1462 65.8965 566.821,
+                          49.3952 65.7686 566.598,
+                          49.1673 115 566.806,
+                          49.038 65.851 566.487,
+                          49.3952 65.7686 566.598,
+                          49.1462 65.8965 566.821,
+                          49.1668 65.7372 566.348,
+                          49.2605 65.593 566.175,
+                          49.3952 65.7686 566.598,
+                          49.038 65.851 566.487,
+                          49.1668 65.7372 566.348,
+                          49.3952 65.7686 566.598,
+                          48.8853 65.9339 566.587,
+                          49.1462 65.8965 566.821,
+                          48.854 65.9743 566.956,
+                          48.8853 65.9339 566.587,
+                          49.038 65.851 566.487,
+                          49.1462 65.8965 566.821,
+                          48.7177 65.9837 566.647,
+                          48.8853 65.9339 566.587,
+                          48.854 65.9743 566.956,
+                          88.6164 116.501 270.535,
+                          93.7019 116.628 397.01,
+                          93.7262 116.5 397.084,
+                          92.7043 116.496 396.977,
+                          93.7262 116.5 397.084,
+                          93.7019 116.628 397.01,
+                          88.6296 116.369 270.535,
+                          88.6164 116.501 270.535,
+                          93.7262 116.5 397.084,
+                          93.7537 116.366 397.437,
+                          88.6296 116.369 270.535,
+                          93.7262 116.5 397.084,
+                          92.7357 116.368 397.124,
+                          93.7537 116.366 397.437,
+                          93.7262 116.5 397.084,
+                          92.7221 116.432 397.05,
+                          93.7262 116.5 397.084,
+                          92.7043 116.496 396.977,
+                          92.7221 116.432 397.05,
+                          92.7357 116.368 397.124,
+                          93.7262 116.5 397.084,
+                          88.6164 116.501 270.535,
+                          88.5987 116.629 270.625,
+                          93.7019 116.628 397.01,
+                          87.626 116.369 270.575,
+                          88.5987 116.629 270.625,
+                          88.6164 116.501 270.535,
+                          87.6348 116.237 270.575,
+                          88.6164 116.501 270.535,
+                          88.6296 116.369 270.535,
+                          48.5449 66 566.333,
+                          48.6425 65.9837 566.322,
+                          48.5449 66 566.667,
+                          87.6348 116.237 270.575,
+                          87.626 116.369 270.575,
+                          88.6164 116.501 270.535,
+                          93.7262 -116.5 397.084,
+                          88.6164 -116.501 270.535,
+                          88.6296 -116.369 270.535,
+                          93.7536 -116.366 397.435,
+                          93.7262 -116.5 397.084,
+                          88.6296 -116.369 270.535,
+                          93.7019 -116.628 397.01,
+                          88.5987 -116.629 270.625,
+                          88.6164 -116.501 270.535,
+                          87.6078 -116.496 270.752,
+                          88.6164 -116.501 270.535,
+                          88.5987 -116.629 270.625,
+                          93.7262 -116.5 397.084,
+                          93.7019 -116.628 397.01,
+                          88.6164 -116.501 270.535,
+                          48.6425 65.9837 566.322,
+                          48.7177 65.9837 566.647,
+                          48.5449 66 566.667,
+                          87.6189 -116.433 270.664,
+                          88.6164 -116.501 270.535,
+                          87.6078 -116.496 270.752,
+                          87.626 -116.369 270.575,
+                          87.6348 -116.237 270.575,
+                          88.6164 -116.501 270.535,
+                          87.6189 -116.433 270.664,
+                          87.626 -116.369 270.575,
+                          88.6164 -116.501 270.535,
+                          92.7357 -116.368 397.124,
+                          93.7019 -116.628 397.01,
+                          93.7262 -116.5 397.084,
+                          92.7731 -116.237 397.835,
+                          93.7262 -116.5 397.084,
+                          93.7536 -116.366 397.435,
+                          92.7565 -116.302 397.475,
+                          93.7262 -116.5 397.084,
+                          92.7731 -116.237 397.835,
+                          92.7357 -116.368 397.124,
+                          93.7262 -116.5 397.084,
+                          92.7565 -116.302 397.475,
+                          72.1616 -179.978 315.048,
+                          74.0826 -179.963 360.469,
+                          73.8926 -179.991 360.47,
+                          73.7008 -179 360.471,
+                          73.8926 -179.991 360.47,
+                          74.0826 -179.963 360.469,
+                          48.8234 65.851 566.232,
+                          48.8961 65.7372 566.153,
+                          49.038 65.851 566.487,
+                          72.4387 -179.916 315.036,
+                          74.1787 -179.942 360.465,
+                          74.0826 -179.963 360.469,
+                          73.9871 -178.958 360.473,
+                          74.0826 -179.963 360.469,
+                          74.1787 -179.942 360.465,
+                          72.1616 -179.978 315.048,
+                          72.4387 -179.916 315.036,
+                          74.0826 -179.963 360.469,
+                          73.8919 -178.982 360.477,
+                          73.7008 -179 360.471,
+                          74.0826 -179.963 360.469,
+                          48.8961 65.7372 566.153,
+                          49.1668 65.7372 566.348,
+                          49.038 65.851 566.487,
+                          73.9871 -178.958 360.473,
+                          73.8919 -178.982 360.477,
+                          74.0826 -179.963 360.469,
+                          72.4387 -179.916 315.036,
+                          74.2728 -179.916 360.461,
+                          74.1787 -179.942 360.465,
+                          73.9871 -178.958 360.473,
+                          74.1787 -179.942 360.465,
+                          74.2728 -179.916 360.461,
+                          73.294 -179.4 315.002,
+                          75.1281 -179.4 360.427,
+                          74.2728 -179.916 360.461,
+                          73.9871 -178.958 360.473,
+                          74.2728 -179.916 360.461,
+                          75.1281 -179.4 360.427,
+                          72.4387 -179.916 315.036,
+                          73.294 -179.4 315.002,
+                          74.2728 -179.916 360.461,
+                          72.1529 -178.958 315.048,
+                          73.294 -179.4 315.002,
+                          72.4387 -179.916 315.036,
+                          72.5806 -178.7 315.031,
+                          72.8323 -178.259 315.021,
+                          73.294 -179.4 315.002,
+                          72.1529 -178.958 315.048,
+                          72.5806 -178.7 315.031,
+                          73.294 -179.4 315.002,
+                          74.2728 179.916 360.461,
+                          72.4387 179.916 315.036,
+                          72.1616 179.978 315.048,
+                          72.1529 178.958 315.048,
+                          72.1616 179.978 315.048,
+                          72.4387 179.916 315.036,
+                          74.1787 179.942 360.465,
+                          74.2728 179.916 360.461,
+                          72.1616 179.978 315.048,
+                          74.0826 179.963 360.469,
+                          74.1787 179.942 360.465,
+                          72.1616 179.978 315.048,
+                          73.8926 179.991 360.47,
+                          74.0826 179.963 360.469,
+                          72.1616 179.978 315.048,
+                          75.1281 179.4 360.427,
+                          73.294 179.4 315.002,
+                          72.4387 179.916 315.036,
+                          72.1529 178.958 315.048,
+                          72.4387 179.916 315.036,
+                          73.294 179.4 315.002,
+                          74.2728 179.916 360.461,
+                          75.1281 179.4 360.427,
+                          72.4387 179.916 315.036,
+                          73.9871 178.958 360.473,
+                          75.1281 179.4 360.427,
+                          74.2728 179.916 360.461,
+                          74.4147 178.7 360.456,
+                          74.6664 178.259 360.446,
+                          75.1281 179.4 360.427,
+                          73.9871 178.958 360.473,
+                          74.4147 178.7 360.456,
+                          75.1281 179.4 360.427,
+                          74.0826 179.963 360.469,
+                          74.2728 179.916 360.461,
+                          74.1787 179.942 360.465,
+                          73.9871 178.958 360.473,
+                          74.2728 179.916 360.461,
+                          74.0826 179.963 360.469,
+                          73.8919 178.982 360.477,
+                          74.0826 179.963 360.469,
+                          73.8926 179.991 360.47,
+                          48.5449 66 566,
+                          48.6383 115 565.936,
+                          48.5996 65.8965 565.984,
+                          73.8919 178.982 360.477,
+                          73.9871 178.958 360.473,
+                          74.0826 179.963 360.469,
+                          73.7008 179 360.471,
+                          73.8919 178.982 360.477,
+                          73.8926 179.991 360.47,
+                          73.7008 -179 360.471,
+                          15 -179 317.356,
+                          15 -179 360.773,
+                          14.9073 -179 315.06,
+                          15 -179 317.356,
+                          73.7008 -179 360.471,
+                          48.7372 65.9339 566.288,
+                          48.8853 65.9339 566.587,
+                          48.7177 65.9837 566.647,
+                          14.9073 -179 315.06,
+                          73.7008 -179 360.471,
+                          71.8672 -179 315.06,
+                          71.8672 179 315.06,
+                          73.7008 179 360.471,
+                          15 179 360.773,
+                          72.0144 178.989 315.054,
+                          73.7008 179 360.471,
+                          71.8672 179 315.06,
+                          48.5996 65.8965 565.984,
+                          48.8234 65.851 566.232,
+                          48.7372 65.9339 566.288,
+                          71.8672 179 315.06,
+                          15 179 360.773,
+                          15 179 317.356,
+                          14.9073 179 315.06,
+                          71.8672 179 315.06,
+                          15 179 317.356,
+                          72.0144 -178.989 315.054,
+                          73.7008 -179 360.471,
+                          73.8919 -178.982 360.477,
+                          71.8672 -179 315.06,
+                          73.7008 -179 360.471,
+                          72.0144 -178.989 315.054,
+                          48.8234 65.851 566.232,
+                          49.038 65.851 566.487,
+                          48.8853 65.9339 566.587,
+                          72.0144 -178.989 315.054,
+                          73.8919 -178.982 360.477,
+                          73.9871 -178.958 360.473,
+                          72.1529 -178.958 315.048,
+                          73.9871 -178.958 360.473,
+                          74.4147 -178.7 360.456,
+                          72.0144 -178.989 315.054,
+                          73.9871 -178.958 360.473,
+                          72.1529 -178.958 315.048,
+                          72.5806 -178.7 315.031,
+                          74.4147 -178.7 360.456,
+                          74.6664 -178.259 360.446,
+                          72.1529 -178.958 315.048,
+                          74.4147 -178.7 360.456,
+                          72.5806 -178.7 315.031,
+                          72.5806 -178.7 315.031,
+                          74.6664 -178.259 360.446,
+                          72.8323 -178.259 315.021,
+                          87.6078 -116.496 270.752,
+                          72.8323 -178.259 315.021,
+                          74.6664 -178.259 360.446,
+                          74.6306 -178.503 361.177,
+                          74.6664 -178.259 360.446,
+                          74.6112 -178.465 360.448,
+                          87.6078 -116.496 270.752,
+                          74.6664 -178.259 360.446,
+                          74.6306 -178.503 361.177,
+                          72.4354 -179.741 315.037,
+                          72.8323 -178.259 315.021,
+                          87.6078 -116.496 270.752,
+                          73.8919 178.982 360.477,
+                          72.0144 178.989 315.054,
+                          72.1529 178.958 315.048,
+                          73.7008 179 360.471,
+                          72.0144 178.989 315.054,
+                          73.8919 178.982 360.477,
+                          73.9871 178.958 360.473,
+                          72.1529 178.958 315.048,
+                          72.5806 178.7 315.031,
+                          48.5449 66 566,
+                          48.6425 65.9837 566.322,
+                          48.5449 66 566.333,
+                          73.8919 178.982 360.477,
+                          72.1529 178.958 315.048,
+                          73.9871 178.958 360.473,
+                          74.4147 178.7 360.456,
+                          72.5806 178.7 315.031,
+                          72.8323 178.259 315.021,
+                          73.9871 178.958 360.473,
+                          72.5806 178.7 315.031,
+                          74.4147 178.7 360.456,
+                          74.4147 178.7 360.456,
+                          72.8323 178.259 315.021,
+                          74.6664 178.259 360.446,
+                          92.7043 116.496 396.977,
+                          74.6664 178.259 360.446,
+                          72.8323 178.259 315.021,
+                          87.6078 116.496 270.752,
+                          72.8323 178.259 315.021,
+                          72.4354 179.741 315.037,
+                          92.7043 116.496 396.977,
+                          72.8323 178.259 315.021,
+                          87.6078 116.496 270.752,
+                          92.7043 116.496 396.977,
+                          74.6112 178.465 360.448,
+                          74.6664 178.259 360.446,
+                          48.8961 -63.7372 566.153,
+                          49.2605 -63.593 566.175,
+                          48.9491 -63.593 566.055,
+                          48.8961 -63.7372 566.153,
+                          49.1668 -63.7372 566.348,
+                          49.2605 -63.593 566.175,
+                          48.6222 -63.7686 565.963,
+                          48.9491 -63.593 566.055,
+                          48.6383 -63.593 565.936,
+                          48.6222 -63.7686 565.963,
+                          48.8961 -63.7372 566.153,
+                          48.9491 -63.593 566.055,
+                          94.6503 -115 446.359,
+                          48.6383 -63.593 565.936,
+                          56.3711 -51.9904 545.84,
+                          94.6503 -115 446.359,
+                          48.6383 -115 565.936,
+                          48.6383 -63.593 565.936,
+                          14.8041 82.9463 566,
+                          48.5449 66 566,
+                          47.2102 66 566,
+                          48.6222 -63.7686 565.963,
+                          48.6383 -63.593 565.936,
+                          48.6383 -115 565.936,
+                          94.6503 -115 446.359,
+                          56.3711 -51.9904 545.84,
+                          61.8347 1 531.641,
+                          94.6503 -115 446.359,
+                          61.8347 1 531.641,
+                          56.3711 53.9904 545.84,
+                          48.9491 65.593 566.055,
+                          48.6383 65.593 565.936,
+                          56.3711 53.9904 545.84,
+                          48.6383 115 565.936,
+                          56.3711 53.9904 545.84,
+                          48.6383 65.593 565.936,
+                          49.2605 65.593 566.175,
+                          48.9491 65.593 566.055,
+                          56.3711 53.9904 545.84,
+                          48.6383 115 565.936,
+                          94.6503 -115 446.359,
+                          56.3711 53.9904 545.84,
+                          48.8961 65.7372 566.153,
+                          48.6383 65.593 565.936,
+                          48.9491 65.593 566.055,
+                          48.6222 65.7686 565.963,
+                          48.6383 115 565.936,
+                          48.6383 65.593 565.936,
+                          48.6222 65.7686 565.963,
+                          48.6383 65.593 565.936,
+                          48.8961 65.7372 566.153,
+                          49.1668 65.7372 566.348,
+                          48.9491 65.593 566.055,
+                          49.2605 65.593 566.175,
+                          48.8961 65.7372 566.153,
+                          48.9491 65.593 566.055,
+                          49.1668 65.7372 566.348,
+                          85.3296 101.202 213.483,
+                          87.6348 116.237 270.575,
+                          87.6348 116.5 270.575,
+                          87.6348 -116.237 270.575,
+                          87.6348 116.237 270.575,
+                          85.3296 101.202 213.483,
+                          92.7731 -116.237 397.835,
+                          87.6348 116.237 270.575,
+                          87.6348 -116.237 270.575,
+                          48.6425 65.9837 566.322,
+                          48.7372 65.9339 566.288,
+                          48.7177 65.9837 566.647,
+                          92.7731 116.237 397.835,
+                          87.6348 116.237 270.575,
+                          92.7731 -116.237 397.835,
+                          92.7566 116.301 397.478,
+                          87.6348 116.237 270.575,
+                          92.7731 116.237 397.835,
+                          85.3296 -101.202 213.483,
+                          85.3296 101.202 213.483,
+                          85.1284 100.943 208.5,
+                          87.6348 -116.5 270.575,
+                          85.3296 101.202 213.483,
+                          85.3296 -101.202 213.483,
+                          87.6348 -116.237 270.575,
+                          85.3296 101.202 213.483,
+                          87.6348 -116.5 270.575,
+                          85.0665 -101.288 206.968,
+                          85.1284 100.943 208.5,
+                          84.9403 102.729 203.841,
+                          85.2042 -100.793 210.377,
+                          85.1284 100.943 208.5,
+                          85.0665 -101.288 206.968,
+                          85.2674 -100.896 211.943,
+                          85.1284 100.943 208.5,
+                          85.2042 -100.793 210.377,
+                          85.3296 -101.202 213.483,
+                          85.1284 100.943 208.5,
+                          85.2674 -100.896 211.943,
+                          84.9403 -102.729 203.841,
+                          84.9403 102.729 203.841,
+                          84.2044 114.564 185.617,
+                          85.0665 -101.288 206.968,
+                          84.9403 102.729 203.841,
+                          84.9403 -102.729 203.841,
+                          84.2044 -114.564 185.617,
+                          84.2044 114.564 185.617,
+                          83.987 116.445 180.232,
+                          84.9403 -102.729 203.841,
+                          84.2044 114.564 185.617,
+                          84.2044 -114.564 185.617,
+                          83.987 -116.445 180.232,
+                          83.987 116.445 180.232,
+                          83.759 115.626 174.586,
+                          84.2044 -114.564 185.617,
+                          83.987 116.445 180.232,
+                          83.987 -116.445 180.232,
+                          83.759 -115.626 174.586,
+                          83.759 115.626 174.586,
+                          82.0008 98.0326 131.04,
+                          83.987 -116.445 180.232,
+                          83.759 115.626 174.586,
+                          83.759 -115.626 174.586,
+                          83.759 -115.626 174.586,
+                          82.0008 98.0326 131.04,
+                          82.0008 -98.0326 131.04,
+                          48.7372 65.9339 566.288,
+                          48.8234 65.851 566.232,
+                          48.8853 65.9339 566.587,
+                          92.7043 116.496 396.977,
+                          74.6306 178.503 361.177,
+                          74.6112 178.465 360.448,
+                          87.6189 116.433 270.664,
+                          92.7043 116.496 396.977,
+                          87.6078 116.496 270.752,
+                          92.7221 116.432 397.05,
+                          92.7043 116.496 396.977,
+                          87.6189 116.433 270.664,
+                          87.6078 -116.496 270.752,
+                          74.6306 -178.503 361.177,
+                          92.7043 -116.496 396.977,
+                          92.7221 -116.432 397.05,
+                          87.6078 -116.496 270.752,
+                          92.7043 -116.496 396.977,
+                          92.7221 -116.432 397.05,
+                          87.6189 -116.433 270.664,
+                          87.6078 -116.496 270.752,
+                          92.7221 116.432 397.05,
+                          87.6189 116.433 270.664,
+                          87.626 116.369 270.575,
+                          92.7357 116.368 397.124,
+                          87.626 116.369 270.575,
+                          87.6348 116.237 270.575,
+                          92.7221 116.432 397.05,
+                          87.626 116.369 270.575,
+                          92.7357 116.368 397.124,
+                          92.7566 116.301 397.478,
+                          92.7357 116.368 397.124,
+                          87.6348 116.237 270.575,
+                          92.7357 -116.368 397.124,
+                          87.6348 -116.237 270.575,
+                          87.626 -116.369 270.575,
+                          92.7565 -116.302 397.475,
+                          92.7731 -116.237 397.835,
+                          87.6348 -116.237 270.575,
+                          92.7357 -116.368 397.124,
+                          92.7565 -116.302 397.475,
+                          87.6348 -116.237 270.575,
+                          92.7221 -116.432 397.05,
+                          87.626 -116.369 270.575,
+                          87.6189 -116.433 270.664,
+                          92.7221 -116.432 397.05,
+                          92.7357 -116.368 397.124,
+                          87.626 -116.369 270.575,
+                          48.6383 115 565.936,
+                          94.6503 115 446.359,
+                          94.6503 -115 446.359,
+                          94.7037 115 446.163,
+                          94.6503 -115 446.359,
+                          94.6503 115 446.359,
+                          94.7037 115 446.163,
+                          94.7037 -115 446.163,
+                          94.6503 -115 446.359,
+                          48.5449 66 566,
+                          48.7372 65.9339 566.288,
+                          48.6425 65.9837 566.322,
+                          93.0658 115 405.085,
+                          93.0658 -115 405.085,
+                          94.7162 -115 445.96,
+                          94.7162 115 445.96,
+                          93.0658 115 405.085,
+                          94.7162 -115 445.96,
+                          94.7037 -115 446.163,
+                          94.7162 115 445.96,
+                          94.7162 -115 445.96,
+                          92.9173 115.312 401.405,
+                          92.9173 -115.312 401.405,
+                          93.0658 -115 405.085,
+                          93.0658 115 405.085,
+                          92.9173 115.312 401.405,
+                          93.0658 -115 405.085,
+                          92.7731 116.237 397.835,
+                          92.7731 -116.237 397.835,
+                          92.9173 -115.312 401.405,
+                          92.9173 115.312 401.405,
+                          92.7731 116.237 397.835,
+                          92.9173 -115.312 401.405,
+                          94.7037 115 446.163,
+                          94.7162 115 445.96,
+                          94.7037 -115 446.163,
+                          14.8041 82.9463 566,
+                          -57 115 566,
+                          48.5449 115 566,
+                          -20.4705 92.5699 566,
+                          -57 94.4281 566,
+                          -57 115 566,
+                          14.8041 82.9463 566,
+                          -20.4705 92.5699 566,
+                          -57 115 566,
+                          48.5449 66 566,
+                          48.5449 115 566,
+                          48.6383 115 565.936,
+                          14.8041 82.9463 566,
+                          48.5449 115 566,
+                          48.5449 66 566,
+                          -57 -94.4281 566,
+                          48.5449 -115 566,
+                          -57 -115 566,
+                          48.5996 -63.8965 565.984,
+                          48.6383 -115 565.936,
+                          48.5449 -115 566,
+                          48.5996 65.8965 565.984,
+                          48.6383 115 565.936,
+                          48.6222 65.7686 565.963,
+                          48 -64 566,
+                          48.5449 -64 566,
+                          48.5449 -115 566,
+                          48.5996 -63.8965 565.984,
+                          48.5449 -115 566,
+                          48.5449 -64 566,
+                          -29.1903 -93.6551 566,
+                          48.5449 -115 566,
+                          -57 -94.4281 566,
+                          24.0854 -78.2163 566,
+                          48 -64 566,
+                          48.5449 -115 566,
+                          -1.89655 -88.1989 566,
+                          24.0854 -78.2163 566,
+                          48.5449 -115 566,
+                          -29.1903 -93.6551 566,
+                          -1.89655 -88.1989 566,
+                          48.5449 -115 566,
+                          48.6222 -63.7686 565.963,
+                          48.6383 -115 565.936,
+                          48.5996 -63.8965 565.984,
+                          48.5449 -64 566.333,
+                          48.5449 -64 566.667,
+                          48.7177 -63.9837 566.647,
+                          48.6425 -63.9837 566.322,
+                          48.7177 -63.9837 566.647,
+                          48.8853 -63.9339 566.587,
+                          48.6425 -63.9837 566.322,
+                          48.5449 -64 566.333,
+                          48.7177 -63.9837 566.647,
+                          48.7372 -63.9339 566.288,
+                          48.8853 -63.9339 566.587,
+                          49.038 -63.851 566.487,
+                          48.7372 -63.9339 566.288,
+                          48.6425 -63.9837 566.322,
+                          48.8853 -63.9339 566.587,
+                          48.8234 -63.851 566.232,
+                          49.038 -63.851 566.487,
+                          49.1668 -63.7372 566.348,
+                          48.8234 -63.851 566.232,
+                          48.7372 -63.9339 566.288,
+                          49.038 -63.851 566.487,
+                          48.8961 -63.7372 566.153,
+                          48.8234 -63.851 566.232,
+                          49.1668 -63.7372 566.348,
+                          48.5449 -64 566,
+                          48.5449 -64 566.333,
+                          48.6425 -63.9837 566.322,
+                          48.5449 -64 566,
+                          48.6425 -63.9837 566.322,
+                          48.7372 -63.9339 566.288,
+                          48.6222 -63.7686 565.963,
+                          48.5996 -63.8965 565.984,
+                          48.8234 -63.851 566.232,
+                          48.5996 -63.8965 565.984,
+                          48.7372 -63.9339 566.288,
+                          48.8234 -63.851 566.232,
+                          48.5996 -63.8965 565.984,
+                          48.5449 -64 566,
+                          48.7372 -63.9339 566.288,
+                          48.6222 -63.7686 565.963,
+                          48.8234 -63.851 566.232,
+                          48.8961 -63.7372 566.153 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+    Separator {
+        Normal {
+            vector      [ -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.965769 -0.259324 -0.00644921,
+                          -0.999978 2.86279e-14 -0.00667765,
+                          -0.999978 3.157e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.00535529 -0.49445 0.86919,
+                          -0.00535529 -0.49445 0.86919,
+                          -0.00535529 -0.49445 0.86919,
+                          -0.964963 -0.262305 -0.00644383,
+                          -0.999978 2.86279e-14 -0.00667765,
+                          -0.965769 -0.259324 -0.00644921,
+                          -0.00317658 -0.754307 0.656514,
+                          -0.00533122 -0.498128 0.867087,
+                          0.119928 -0.464837 0.877236,
+                          -0.00535529 -0.49445 0.86919,
+                          -0.00535529 -0.49445 0.86919,
+                          -0.00535529 -0.49445 0.86919,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          0.00277433 -0.909609 -0.415455,
+                          0.00277433 -0.909609 -0.415455,
+                          0.00277433 -0.909609 -0.415455,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          0.253897 -0.939882 -0.228381,
+                          0.237287 -0.873111 -0.425879,
+                          0.00275237 -0.911104 -0.412168,
+                          0.253897 -0.939882 -0.228381,
+                          0.00275237 -0.911104 -0.412168,
+                          0.00147324 -0.975359 -0.220618,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -3.67152e-14 -1 5.59242e-15,
+                          -3.67152e-14 -1 5.59242e-15,
+                          -3.67152e-14 -1 5.59242e-15,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          0.00277433 -0.909609 -0.415455,
+                          0.00277433 -0.909609 -0.415455,
+                          0.00277433 -0.909609 -0.415455,
+                          0.00667765 -5.87821e-15 -0.999978,
+                          0.00667765 -5.87821e-15 -0.999978,
+                          0.00667765 -5.87821e-15 -0.999978,
+                          -3.67152e-14 -1 5.59242e-15,
+                          -3.67152e-14 -1 5.59242e-15,
+                          -3.67152e-14 -1 5.59242e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          0.00667765 -5.87821e-15 -0.999978,
+                          0.00667765 -5.87821e-15 -0.999978,
+                          0.00667765 -5.87821e-15 -0.999978,
+                          0.00275622 0.910843 -0.412744,
+                          0.00275622 0.910843 -0.412744,
+                          0.00275622 0.910843 -0.412744,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          -0.964959 0.262321 -0.0064438,
+                          -0.999978 2.61299e-14 -0.00667765,
+                          -0.999978 3.93416e-14 -0.00667765,
+                          -0.96578 0.259281 -0.00644928,
+                          -0.999978 2.61299e-14 -0.00667765,
+                          -0.964959 0.262321 -0.0064438,
+                          0.0014622 0.975732 -0.218964,
+                          0.00273434 0.91232 -0.409468,
+                          0.237568 0.874378 -0.423113,
+                          0.00275622 0.910843 -0.412744,
+                          0.00275622 0.910843 -0.412744,
+                          0.00275622 0.910843 -0.412744,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.00498697 0.497112 0.867672,
+                          -0.00498697 0.497112 0.867672,
+                          -0.00498697 0.497112 0.867672,
+                          0.18993 0.715278 0.672536,
+                          0.120267 0.466803 0.876145,
+                          -0.00496006 0.500138 0.865932,
+                          0.18993 0.715278 0.672536,
+                          -0.00496006 0.500138 0.865932,
+                          -0.00238337 0.756047 0.654513,
+                          -0.00498697 0.497112 0.867672,
+                          -0.00498697 0.497112 0.867672,
+                          -0.00498697 0.497112 0.867672,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.00579661 0.496456 0.868043,
+                          -0.00579661 0.496456 0.868043,
+                          -0.00579661 0.496456 0.868043,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.00579661 0.496456 0.868043,
+                          -0.00579661 0.496456 0.868043,
+                          -0.00415819 0.809641 0.586911,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.00579661 0.496456 0.868043,
+                          -0.00579661 0.496456 0.868043,
+                          -0.00579661 0.496456 0.868043,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.00415383 0.809863 0.586605,
+                          -0.00415819 0.809641 0.586911,
+                          -0.000674018 0.979408 0.201889,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.999978 3.6677e-14 -0.00667765,
+                          -0.00579661 0.496456 0.868043,
+                          -0.00415819 0.809641 0.586911,
+                          -0.00415383 0.809863 0.586605,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          0.000410252 0.979409 0.201885,
+                          0.000410252 0.979409 0.201885,
+                          0.00104928 0.991213 0.13227,
+                          -0.00415383 0.809863 0.586605,
+                          -0.000674018 0.979408 0.201889,
+                          -0.000674018 0.979408 0.201889,
+                          -0.00105029 -0.949238 0.314558,
+                          -0.00105029 -0.949238 0.314558,
+                          -0.00396948 -0.77338 0.63393,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          0.00094879 -0.969512 0.245042,
+                          0.000951216 -0.969562 0.244844,
+                          -3.71309e-05 -0.94924 0.314552,
+                          0.00094879 -0.969512 0.245042,
+                          -3.71309e-05 -0.94924 0.314552,
+                          -3.71309e-05 -0.94924 0.314552,
+                          -0.00396696 -0.773475 0.633814,
+                          -0.00396948 -0.77338 0.63393,
+                          -0.00580425 -0.49445 0.869187,
+                          -0.00396696 -0.773475 0.633814,
+                          -0.00105029 -0.949238 0.314558,
+                          -0.00396948 -0.77338 0.63393,
+                          -0.00580425 -0.49445 0.869187,
+                          -0.00580425 -0.49445 0.869187,
+                          -0.00580425 -0.49445 0.869187,
+                          -0.00396696 -0.773475 0.633814,
+                          -0.00580425 -0.49445 0.869187,
+                          -0.00580425 -0.49445 0.869187,
+                          -0.00580425 -0.49445 0.869187,
+                          -0.00580425 -0.49445 0.869187,
+                          -0.00580425 -0.49445 0.869187,
+                          0.00105172 0.991187 0.132463,
+                          0.00104928 0.991213 0.13227,
+                          0.00108426 0.998091 0.0617575,
+                          0.000410252 0.979409 0.201885,
+                          0.00104928 0.991213 0.13227,
+                          0.00105172 0.991187 0.132463,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -0.92405 3.61749e-14 0.382272,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -0.945059 3.66209e-14 0.326899,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -0.92405 3.61749e-14 0.382272,
+                          3.28548e-14 0.994926 0.100605,
+                          3.44369e-14 0.998165 0.0605595,
+                          0.00934554 0.999591 0.0270178,
+                          0.00105172 0.991187 0.132463,
+                          0.00108426 0.998091 0.0617575,
+                          0.00108426 0.998091 0.0617575,
+                          0.00101313 -0.98467 0.174424,
+                          0.00101313 -0.98467 0.174424,
+                          0.000951216 -0.969562 0.244844,
+                          0.0786066 -0.97863 0.190012,
+                          0.0478154 -0.992146 0.115582,
+                          -4.26102e-14 -0.984178 0.177182,
+                          0.0786066 -0.97863 0.190012,
+                          -4.26102e-14 -0.984178 0.177182,
+                          -4.56692e-14 -0.957813 0.287393,
+                          0.00101313 -0.98467 0.174424,
+                          0.000951216 -0.969562 0.244844,
+                          0.00094879 -0.969512 0.245042,
+                          -0.708204 3.01521e-14 0.706008,
+                          -3.66004e-14 5.87659e-15 1,
+                          -3.66004e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.66004e-14 5.87659e-15 1,
+                          -0.708204 3.01521e-14 0.706008,
+                          -3.66004e-14 5.87659e-15 1,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.61487e-14 3.65392e-14,
+                          1 -3.61487e-14 3.65392e-14,
+                          0.902599 0.430482 3.04505e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          -0.708204 3.01521e-14 0.706008,
+                          -0.708204 3.01521e-14 0.706008,
+                          -3.66004e-14 5.87659e-15 1,
+                          -3.67171e-14 -1 5.87659e-15,
+                          -3.67171e-14 -1 5.87659e-15,
+                          -3.67171e-14 -1 5.87659e-15,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.67171e-14 -1 5.87659e-15,
+                          -3.67171e-14 -1 5.87659e-15,
+                          -3.67171e-14 -1 5.87659e-15,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.67171e-14 -1 5.87659e-15,
+                          -3.67171e-14 -1 5.87659e-15,
+                          -3.67171e-14 -1 5.87659e-15,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -0.708204 3.01521e-14 0.706008,
+                          -3.67171e-14 -1 5.87659e-15,
+                          -3.67171e-14 -1 5.87659e-15,
+                          -3.67171e-14 -1 5.87659e-15,
+                          -0.708204 3.01521e-14 0.706008,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -0.708204 3.01521e-14 0.706008,
+                          -3.67171e-14 -1 5.87659e-15,
+                          -3.67171e-14 -1 5.87659e-15,
+                          -3.67171e-14 -1 5.87659e-15,
+                          -3.67171e-14 -1 5.87659e-15,
+                          -3.67171e-14 -1 5.87659e-15,
+                          -3.67171e-14 -1 5.87659e-15,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -3.67171e-14 -1 5.87659e-15,
+                          -3.67171e-14 -1 5.87659e-15,
+                          -3.67171e-14 -1 5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          -3.66004e-14 5.87659e-15 1,
+                          -3.66004e-14 5.87659e-15 1,
+                          -0.708204 3.01521e-14 0.706008,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          0.902599 -0.430482 3.551e-14,
+                          0.902599 -0.430482 3.551e-14,
+                          1 -3.81326e-14 3.65392e-14,
+                          0.902599 -0.430482 3.551e-14,
+                          1 -3.81326e-14 3.65392e-14,
+                          1 -3.79106e-14 3.65392e-14,
+                          0.233538 0.972348 2.81922e-15,
+                          0.233538 0.972348 2.81922e-15,
+                          0.145987 0.989286 -4.79383e-16,
+                          0.62937 0.777106 1.84299e-14,
+                          0.62937 0.777106 1.84299e-14,
+                          0.233538 0.972348 2.81922e-15,
+                          0.233538 0.972348 2.81922e-15,
+                          0.62937 0.777106 1.84299e-14,
+                          0.233538 0.972348 2.81922e-15,
+                          0.145987 0.989286 -4.79383e-16,
+                          0.145987 0.989286 -4.79383e-16,
+                          0.0573189 0.998356 -3.77254e-15,
+                          0.145987 0.989286 -4.79383e-16,
+                          0.233538 0.972348 2.81922e-15,
+                          0.145987 0.989286 -4.79383e-16,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          0.145987 0.989286 -4.79383e-16,
+                          0.0573189 0.998356 -3.77254e-15,
+                          0.0573189 0.998356 -3.77254e-15,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          0.902599 0.430482 3.04505e-14,
+                          0.902599 0.430482 3.04505e-14,
+                          0.62937 0.777106 1.84299e-14,
+                          0.902599 0.430482 3.04505e-14,
+                          1 -3.61487e-14 3.65392e-14,
+                          0.902599 0.430482 3.04505e-14,
+                          0.62937 0.777106 1.84299e-14,
+                          0.902599 0.430482 3.04505e-14,
+                          0.62937 0.777106 1.84299e-14,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          0.0573189 -0.998356 7.96131e-15,
+                          0.0573189 -0.998356 7.96131e-15,
+                          0.145987 -0.989286 1.11479e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          0.145987 -0.989286 1.11479e-14,
+                          0.145987 -0.989286 1.11479e-14,
+                          0.233538 -0.972348 1.42474e-14,
+                          0.145987 -0.989286 1.11479e-14,
+                          0.0573189 -0.998356 7.96131e-15,
+                          0.145987 -0.989286 1.11479e-14,
+                          0.233538 -0.972348 1.42474e-14,
+                          0.233538 -0.972348 1.42474e-14,
+                          0.62937 -0.777106 2.75634e-14,
+                          0.145987 -0.989286 1.11479e-14,
+                          0.233538 -0.972348 1.42474e-14,
+                          0.233538 -0.972348 1.42474e-14,
+                          0.62937 -0.777106 2.75634e-14,
+                          0.62937 -0.777106 2.75634e-14,
+                          0.902599 -0.430482 3.551e-14,
+                          0.62937 -0.777106 2.75634e-14,
+                          0.233538 -0.972348 1.42474e-14,
+                          0.62937 -0.777106 2.75634e-14,
+                          0.902599 -0.430482 3.551e-14,
+                          0.62937 -0.777106 2.75634e-14,
+                          0.902599 -0.430482 3.551e-14,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          -0.706647 3.01041e-14 0.707567,
+                          -0.438074 2.13675e-14 0.898939,
+                          -0.785362 3.2474e-14 0.619037,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          -0.92405 3.61749e-14 0.382272,
+                          -0.706647 3.01041e-14 0.707567,
+                          -0.785362 3.2474e-14 0.619037,
+                          -0.945059 3.66209e-14 0.326899,
+                          -0.92405 3.61749e-14 0.382272,
+                          -0.785362 3.2474e-14 0.619037,
+                          0.0155646 0.998866 0.0449969,
+                          0.00934554 0.999591 0.0270178,
+                          -0.00197748 0.999995 -0.00250879,
+                          0.0155646 0.998866 0.0449969,
+                          -0.00197748 0.999995 -0.00250879,
+                          -0.00329576 0.999986 -0.00418128,
+                          -3.66004e-14 5.87659e-15 1,
+                          -3.66004e-14 5.87659e-15 1,
+                          -0.438074 2.13675e-14 0.898939,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          -0.381343 1.94343e-14 0.924433,
+                          -3.66004e-14 5.87659e-15 1,
+                          -0.438074 2.13675e-14 0.898939,
+                          -0.706647 3.01041e-14 0.707567,
+                          -0.381343 1.94343e-14 0.924433,
+                          -0.438074 2.13675e-14 0.898939,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          -0.00593653 -0.999982 5.65957e-15,
+                          -0.00356196 -0.999994 5.7464e-15,
+                          0.0294416 -0.999493 0.0121451,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -0.000502898 -1 5.85821e-15,
+                          -0.000502898 -1 5.85821e-15,
+                          -0.000502898 -1 5.85821e-15,
+                          -0.000502898 -1 5.85821e-15,
+                          -0.000502898 -1 5.85821e-15,
+                          -0.000502898 -1 5.85821e-15,
+                          0.0490251 -0.998593 0.0202236,
+                          0.0294416 -0.999493 0.0121451,
+                          0.0518075 -0.997316 0.0517401,
+                          -0.00593653 -0.999982 5.65957e-15,
+                          0.0294416 -0.999493 0.0121451,
+                          0.0490251 -0.998593 0.0202236,
+                          0.0859372 -0.992597 0.0858255,
+                          0.0518075 -0.997316 0.0517401,
+                          0.0478154 -0.992146 0.115582,
+                          0.0490251 -0.998593 0.0202236,
+                          0.0518075 -0.997316 0.0517401,
+                          0.0859372 -0.992597 0.0858255,
+                          0.0859372 -0.992597 0.0858255,
+                          0.0478154 -0.992146 0.115582,
+                          0.0786066 -0.97863 0.190012,
+                          0.0155646 0.998866 0.0449969,
+                          3.28548e-14 0.994926 0.100605,
+                          0.00934554 0.999591 0.0270178,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -3.65392e-14 5.87659e-15 1,
+                          -0.706784 3.01083e-14 0.707429,
+                          -3.67229e-14 5.87659e-15 1,
+                          -3.67229e-14 5.87659e-15 1,
+                          -0.707107 3.01183e-14 0.707107,
+                          -3.67229e-14 5.87659e-15 1,
+                          -0.706784 3.01083e-14 0.707429,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          -0.000502898 -1 5.85821e-15,
+                          -0.000502898 -1 5.85821e-15,
+                          -0.000502898 -1 5.85821e-15,
+                          0.0126771 -0.999839 0.0126656,
+                          0.0379825 -0.998558 0.037948,
+                          0.00391043 -0.999992 6.01943e-15,
+                          0.0126771 -0.999839 0.0126656,
+                          0.00391043 -0.999992 6.01943e-15,
+                          0.00130349 -0.999999 5.92421e-15,
+                          -0.000502898 -1 5.85821e-15,
+                          -0.000502898 -1 5.85821e-15,
+                          -0.000502898 -1 5.85821e-15,
+                          -0.707107 3.01183e-14 0.707107,
+                          -1 3.67171e-14 -3.66616e-14,
+                          -1 3.67171e-14 -3.66616e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          -0.707107 3.01183e-14 0.707107,
+                          -0.706784 3.01083e-14 0.707429,
+                          -1 3.67171e-14 -3.66616e-14,
+                          -3.75524e-14 -0.999736 0.0229868,
+                          -3.91598e-14 -0.997629 0.068815,
+                          0.0379825 -0.998558 0.037948,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -3.78233e-14 -0.999527 0.0307487,
+                          -3.78233e-14 -0.999527 0.0307487,
+                          -3.88904e-14 -0.998115 0.0613736,
+                          -3.78233e-14 -0.999527 0.0307487,
+                          -3.88904e-14 -0.998115 0.0613736,
+                          -3.88904e-14 -0.998115 0.0613736,
+                          -3.75524e-14 -0.999736 0.0229868,
+                          0.0379825 -0.998558 0.037948,
+                          0.0126771 -0.999839 0.0126656,
+                          5.00127e-14 0.868067 -0.496447,
+                          5.00127e-14 0.868067 -0.496447,
+                          5.00127e-14 0.868067 -0.496447,
+                          4.48701e-14 0.966454 -0.256839,
+                          4.48701e-14 0.966454 -0.256839,
+                          5.00126e-14 0.868068 -0.496446,
+                          4.48701e-14 0.966454 -0.256839,
+                          5.00126e-14 0.868068 -0.496446,
+                          5.00126e-14 0.868068 -0.496446,
+                          5.00127e-14 0.868067 -0.496447,
+                          5.00127e-14 0.868067 -0.496447,
+                          5.00127e-14 0.868067 -0.496447,
+                          1.86993e-15 -0.67934 -0.733824,
+                          1.86993e-15 -0.67934 -0.733824,
+                          1.86993e-15 -0.67934 -0.733824,
+                          -3.67171e-14 -1 5.87659e-15,
+                          -3.67171e-14 -1 5.87659e-15,
+                          -3.67171e-14 -1 5.87659e-15,
+                          1.75921e-15 -0.680908 -0.732369,
+                          1.75921e-15 -0.680908 -0.732369,
+                          -1.90145e-14 -0.916335 -0.400411,
+                          1.86993e-15 -0.67934 -0.733824,
+                          1.86993e-15 -0.67934 -0.733824,
+                          1.86993e-15 -0.67934 -0.733824,
+                          -1.90145e-14 -0.916335 -0.400411,
+                          -1.90145e-14 -0.916335 -0.400411,
+                          -3.66388e-14 -0.999998 -0.00214021,
+                          1.75921e-15 -0.680908 -0.732369,
+                          -1.90145e-14 -0.916335 -0.400411,
+                          -1.90145e-14 -0.916335 -0.400411,
+                          -3.67171e-14 -1 5.87659e-15,
+                          -3.67171e-14 -1 5.87659e-15,
+                          -3.67171e-14 -1 5.87659e-15,
+                          -1.90145e-14 -0.916335 -0.400411,
+                          -3.66388e-14 -0.999998 -0.00214021,
+                          -3.66388e-14 -0.999998 -0.00214021,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -3.67171e-14 -1 -9.698e-10,
+                          -3.67171e-14 -1 -9.698e-10,
+                          -3.78233e-14 -0.999527 0.0307487,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -1 3.67171e-14 -3.65392e-14,
+                          -3.67171e-14 -1 5.87659e-15,
+                          -3.67171e-14 -1 5.87659e-15,
+                          -3.67171e-14 -1 5.87659e-15,
+                          -3.67171e-14 -1 -9.698e-10,
+                          -3.78233e-14 -0.999527 0.0307487,
+                          -3.78233e-14 -0.999527 0.0307487,
+                          3.67171e-14 1 1.70652e-07,
+                          3.67171e-14 1 1.70652e-07,
+                          4.48701e-14 0.966454 -0.256839,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 -5.87659e-15,
+                          3.67171e-14 1 1.70652e-07,
+                          4.48701e-14 0.966454 -0.256839,
+                          4.48701e-14 0.966454 -0.256839,
+                          -0.866006 -0.5 -0.00578301,
+                          -0.866006 -0.5 -0.00578301,
+                          -0.866006 -0.5 -0.00578301,
+                          0.214967 -0.382718 0.898508,
+                          0.214967 -0.382718 0.898508,
+                          0.214967 -0.382718 0.898508,
+                          -0.964963 -0.262305 -0.00644383,
+                          -0.866006 -0.5 -0.00578301,
+                          -0.866006 -0.5 -0.00578301,
+                          0.189464 -0.713916 0.674112,
+                          0.119928 -0.464837 0.877236,
+                          0.216629 -0.385577 0.896885,
+                          0.189464 -0.713916 0.674112,
+                          0.216629 -0.385577 0.896885,
+                          0.347826 -0.610667 0.711409,
+                          -0.866006 -0.5 -0.00578301,
+                          -0.866006 -0.5 -0.00578301,
+                          -0.866006 -0.5 -0.00578301,
+                          -0.499989 -0.866025 -0.00333882,
+                          -0.866006 -0.5 -0.00578301,
+                          -0.866006 -0.5 -0.00578301,
+                          0.214967 -0.382718 0.898508,
+                          0.214967 -0.382718 0.898508,
+                          0.214967 -0.382718 0.898508,
+                          0.237101 -0.149758 0.959873,
+                          0.348956 -0.612598 0.709192,
+                          0.217762 -0.387527 0.895769,
+                          -0.52383 -0.851815 -0.00349803,
+                          -0.866006 -0.5 -0.00578301,
+                          -0.499989 -0.866025 -0.00333882,
+                          0.445199 -0.765722 -0.464185,
+                          0.445199 -0.765722 -0.464185,
+                          0.445199 -0.765722 -0.464185,
+                          -0.809591 0.468769 -0.353296,
+                          -0.397531 0.695452 -0.598594,
+                          -0.466438 0.811936 -0.350992,
+                          -0.809591 0.468769 -0.353296,
+                          -0.691447 0.401514 -0.600572,
+                          -0.397531 0.695452 -0.598594,
+                          -0.964963 -0.262305 -0.00644383,
+                          -0.965769 -0.259324 -0.00644921,
+                          -0.866006 -0.5 -0.00578301,
+                          0.48545 -0.83792 -0.249457,
+                          0.446265 -0.767617 -0.460013,
+                          0.237287 -0.873111 -0.425879,
+                          0.445199 -0.765722 -0.464185,
+                          0.445199 -0.765722 -0.464185,
+                          0.445199 -0.765722 -0.464185,
+                          0.253897 -0.939882 -0.228381,
+                          0.48545 -0.83792 -0.249457,
+                          0.237287 -0.873111 -0.425879,
+                          -0.00317658 -0.754307 0.656514,
+                          0.119928 -0.464837 0.877236,
+                          0.189464 -0.713916 0.674112,
+                          -0.866006 0.5 -0.00578301,
+                          -0.866006 0.5 -0.00578301,
+                          -0.866006 0.5 -0.00578301,
+                          -0.96578 0.259281 -0.00644928,
+                          -0.866006 0.5 -0.00578301,
+                          -0.866006 0.5 -0.00578301,
+                          -0.866006 0.5 -0.00578301,
+                          -0.866006 0.5 -0.00578301,
+                          -0.866006 0.5 -0.00578301,
+                          0.215928 0.384372 0.897571,
+                          0.215928 0.384372 0.897571,
+                          0.215928 0.384372 0.897571,
+                          -0.96578 0.259281 -0.00644928,
+                          -0.964959 0.262321 -0.0064438,
+                          -0.866006 0.5 -0.00578301,
+                          0.348786 0.612309 0.709525,
+                          0.217592 0.387234 0.895937,
+                          0.120267 0.466803 0.876145,
+                          0.215928 0.384372 0.897571,
+                          0.215928 0.384372 0.897571,
+                          0.215928 0.384372 0.897571,
+                          0.44594 0.767038 -0.461293,
+                          0.44594 0.767038 -0.461293,
+                          0.44594 0.767038 -0.461293,
+                          0.253949 0.940284 -0.22666,
+                          0.237568 0.874378 -0.423113,
+                          0.446996 0.768916 -0.457124,
+                          0.253949 0.940284 -0.22666,
+                          0.446996 0.768916 -0.457124,
+                          0.485681 0.838342 -0.247583,
+                          -0.484575 0.874744 -0.00323589,
+                          -0.866006 0.5 -0.00578301,
+                          -0.866006 0.5 -0.00578301,
+                          0.44594 0.767038 -0.461293,
+                          0.44594 0.767038 -0.461293,
+                          0.44594 0.767038 -0.461293,
+                          -0.689902 -0.400631 -0.602935,
+                          -0.466073 -0.811326 -0.352882,
+                          -0.396632 -0.693923 -0.60096,
+                          -0.499989 0.866025 -0.00333882,
+                          -0.866006 0.5 -0.00578301,
+                          -0.484575 0.874744 -0.00323589,
+                          0.42935 0.237946 0.871229,
+                          0.2192 0.39 0.894344,
+                          0.35038 0.615032 0.706378,
+                          0.42935 0.237946 0.871229,
+                          0.227495 0.129613 0.965115,
+                          0.2192 0.39 0.894344,
+                          0.18993 0.715278 0.672536,
+                          0.348786 0.612309 0.709525,
+                          0.120267 0.466803 0.876145,
+                          0.0014622 0.975732 -0.218964,
+                          0.237568 0.874378 -0.423113,
+                          0.253949 0.940284 -0.22666,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          0.945059 -3.66209e-14 -0.326899,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          0.92405 -3.61749e-14 -0.382272,
+                          1 -3.67171e-14 3.65392e-14,
+                          0.945059 -3.66209e-14 -0.326899,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.866006 0.5 0.00578301,
+                          0.866006 0.5 0.00578301,
+                          0.866006 0.5 0.00578301,
+                          0.965769 0.259324 0.00644921,
+                          0.866006 0.5 0.00578301,
+                          0.866006 0.5 0.00578301,
+                          0.866006 0.5 0.00578301,
+                          0.866006 0.5 0.00578301,
+                          0.866006 0.5 0.00578301,
+                          0.965769 0.259324 0.00644921,
+                          0.965213 0.261385 0.0064455,
+                          0.866006 0.5 0.00578301,
+                          0.52383 0.851815 0.00349803,
+                          0.866006 0.5 0.00578301,
+                          0.866006 0.5 0.00578301,
+                          0.52383 0.851815 0.00349803,
+                          0.499989 0.866025 0.00333882,
+                          0.866006 0.5 0.00578301,
+                          0.430696 -0.268414 0.861658,
+                          0.348956 -0.612598 0.709192,
+                          0.237101 -0.149758 0.959873,
+                          0.999978 -1.09439e-15 0.00667765,
+                          0.999978 -1.09439e-15 0.00667765,
+                          0.965213 0.261385 0.0064455,
+                          0.965769 0.259324 0.00644921,
+                          0.999978 -1.09439e-15 0.00667765,
+                          0.965213 0.261385 0.0064455,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.92405 -3.61749e-14 -0.382272,
+                          0.945059 -3.66209e-14 -0.326899,
+                          0.785362 -3.2474e-14 -0.619037,
+                          0.706647 -3.01041e-14 -0.707567,
+                          0.92405 -3.61749e-14 -0.382272,
+                          0.785362 -3.2474e-14 -0.619037,
+                          0.438074 -2.13675e-14 -0.898939,
+                          0.706647 -3.01041e-14 -0.707567,
+                          0.785362 -3.2474e-14 -0.619037,
+                          0.438074 -2.13675e-14 -0.898939,
+                          0.381343 -1.94343e-14 -0.924433,
+                          0.706647 -3.01041e-14 -0.707567,
+                          3.66004e-14 -5.87659e-15 -1,
+                          3.66004e-14 -5.87659e-15 -1,
+                          0.381343 -1.94343e-14 -0.924433,
+                          0.438074 -2.13675e-14 -0.898939,
+                          3.66004e-14 -5.87659e-15 -1,
+                          0.381343 -1.94343e-14 -0.924433,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          0.707107 -3.01183e-14 -0.707107,
+                          3.67229e-14 -5.87659e-15 -1,
+                          3.67229e-14 -5.87659e-15 -1,
+                          0.706784 -3.01083e-14 -0.707429,
+                          3.67229e-14 -5.87659e-15 -1,
+                          0.707107 -3.01183e-14 -0.707107,
+                          0.706784 -3.01083e-14 -0.707429,
+                          0.707107 -3.01183e-14 -0.707107,
+                          1 -3.67171e-14 3.66616e-14,
+                          1 -3.67171e-14 3.66616e-14,
+                          0.706784 -3.01083e-14 -0.707429,
+                          1 -3.67171e-14 3.66616e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          0.708204 -3.01521e-14 -0.706008,
+                          1 -3.67171e-14 3.65392e-14,
+                          1 -3.67171e-14 3.65392e-14,
+                          0.708204 -3.01521e-14 -0.706008,
+                          0.708204 -3.01521e-14 -0.706008,
+                          1 -3.67171e-14 3.65392e-14,
+                          0.866006 -0.5 0.00578301,
+                          0.866006 -0.5 0.00578301,
+                          0.866006 -0.5 0.00578301,
+                          0.965391 -0.260729 0.00644668,
+                          0.866006 -0.5 0.00578301,
+                          0.866006 -0.5 0.00578301,
+                          0.866006 -0.5 0.00578301,
+                          0.866006 -0.5 0.00578301,
+                          0.866006 -0.5 0.00578301,
+                          0.499989 -0.866025 0.00333882,
+                          0.866006 -0.5 0.00578301,
+                          0.866006 -0.5 0.00578301,
+                          0.499989 -0.866025 0.00333882,
+                          0.493142 -0.869943 0.0032931,
+                          0.866006 -0.5 0.00578301,
+                          -0.808968 -0.468417 -0.355184,
+                          -0.466073 -0.811326 -0.352882,
+                          -0.689902 -0.400631 -0.602935,
+                          0.965391 -0.260729 0.00644668,
+                          0.96578 -0.259281 0.00644928,
+                          0.866006 -0.5 0.00578301,
+                          0.999978 -4.31163e-14 0.00667765,
+                          0.999978 -1.6582e-14 0.00667765,
+                          0.96578 -0.259281 0.00644928,
+                          0.965391 -0.260729 0.00644668,
+                          0.999978 -4.31163e-14 0.00667765,
+                          0.96578 -0.259281 0.00644928,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          0.999978 -3.6677e-14 0.00667765,
+                          -4.80414e-14 -1 5.77337e-15,
+                          -4.80414e-14 -1 5.77337e-15,
+                          -4.80414e-14 -1 5.77337e-15,
+                          1 4.8548e-14 3.65392e-14,
+                          1 4.8548e-14 3.65392e-14,
+                          1 4.8548e-14 3.65392e-14,
+                          0.00513697 2.01906e-14 0.999987,
+                          0.00513697 2.01906e-14 0.999987,
+                          0.00513697 2.01906e-14 0.999987,
+                          0.00513697 2.01906e-14 0.999987,
+                          0.00513697 2.01906e-14 0.999987,
+                          0.00513697 2.01906e-14 0.999987,
+                          -4.80414e-14 -1 5.77337e-15,
+                          -4.80414e-14 -1 5.77337e-15,
+                          -4.80414e-14 -1 5.77337e-15,
+                          0.0152295 -6.21867e-15 -0.999884,
+                          0.0152295 -6.21867e-15 -0.999884,
+                          0.0152295 -6.21867e-15 -0.999884,
+                          -4.80414e-14 -1 5.77337e-15,
+                          -4.80414e-14 -1 5.77337e-15,
+                          -4.80414e-14 -1 5.77337e-15,
+                          1 4.8548e-14 3.65392e-14,
+                          1 4.8548e-14 3.65392e-14,
+                          1 4.8548e-14 3.65392e-14,
+                          -4.80414e-14 -1 5.77337e-15,
+                          -4.80414e-14 -1 5.77337e-15,
+                          -4.80414e-14 -1 5.77337e-15,
+                          0.999978 -2.25614e-14 0.00667765,
+                          0.999978 -2.25614e-14 0.00667765,
+                          0.999978 -2.25614e-14 0.00667765,
+                          -4.80414e-14 -1 5.77337e-15,
+                          -4.80414e-14 -1 5.77337e-15,
+                          -4.80414e-14 -1 5.77337e-15,
+                          0.0152295 -6.21867e-15 -0.999884,
+                          0.0152295 -6.21867e-15 -0.999884,
+                          0.0152295 -6.21867e-15 -0.999884,
+                          -4.80414e-14 -1 5.77337e-15,
+                          -4.80414e-14 -1 5.77337e-15,
+                          -4.80414e-14 -1 5.77337e-15,
+                          6.04467e-14 -5.87659e-15 -1,
+                          6.04467e-14 -5.87659e-15 -1,
+                          6.04467e-14 -5.87659e-15 -1,
+                          0.999978 -2.25614e-14 0.00667765,
+                          0.999978 -2.25614e-14 0.00667765,
+                          0.999978 -2.25614e-14 0.00667765,
+                          6.04467e-14 -5.87659e-15 -1,
+                          6.04467e-14 -5.87659e-15 -1,
+                          6.04467e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          -0.0894938 -0.995987 -0.000597621,
+                          -0.499989 -0.866025 -0.00333882,
+                          -4.8652e-14 -1 5.76904e-15,
+                          -0.935199 6.56763e-14 -0.354123,
+                          -0.799042 7.13387e-14 -0.601275,
+                          -0.691447 0.401514 -0.600572,
+                          -2.20066e-14 -1 5.94685e-15,
+                          -0.0894938 -0.995987 -0.000597621,
+                          -4.8652e-14 -1 5.76904e-15,
+                          -3.02947e-14 2.00874e-14 1,
+                          -3.02947e-14 2.00874e-14 1,
+                          -3.02947e-14 2.00874e-14 1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          -0.00667765 6.19281e-15 0.999978,
+                          -0.00667765 6.19281e-15 0.999978,
+                          -0.00667765 6.19281e-15 0.999978,
+                          -3.02947e-14 2.00874e-14 1,
+                          -3.02947e-14 2.00874e-14 1,
+                          -3.02947e-14 2.00874e-14 1,
+                          -0.00667765 6.19281e-15 0.999978,
+                          -0.00667765 6.19281e-15 0.999978,
+                          -0.00667765 6.19281e-15 0.999978,
+                          -0.0894938 -0.995987 -0.000597621,
+                          -0.52383 -0.851815 -0.00349803,
+                          -0.499989 -0.866025 -0.00333882,
+                          -0.809591 0.468769 -0.353296,
+                          -0.935199 6.56763e-14 -0.354123,
+                          -0.691447 0.401514 -0.600572,
+                          0.430696 -0.268414 0.861658,
+                          0.237101 -0.149758 0.959873,
+                          0.042598 -0.00442709 0.999083,
+                          -0.0816927 0.00996487 0.996608,
+                          0.0569615 -0.00571728 0.99836,
+                          -0.0442691 0.00998598 0.99897,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          0.430696 -0.268414 0.861658,
+                          0.042598 -0.00442709 0.999083,
+                          0.09153 -0.00882186 0.995763,
+                          -0.0816927 0.00996487 0.996608,
+                          0.119856 -0.0113652 0.992726,
+                          0.0569615 -0.00571728 0.99836,
+                          6.90801e-14 1 -5.69011e-15,
+                          6.90801e-14 1 -5.69011e-15,
+                          6.90801e-14 1 -5.69011e-15,
+                          0.00513697 6.23846e-14 0.999987,
+                          0.00513697 6.23846e-14 0.999987,
+                          0.00513697 6.23846e-14 0.999987,
+                          1 -9.35605e-14 3.65392e-14,
+                          1 -9.35605e-14 3.65392e-14,
+                          1 -9.35605e-14 3.65392e-14,
+                          1 -9.35605e-14 3.65392e-14,
+                          1 -9.35605e-14 3.65392e-14,
+                          1 -9.35605e-14 3.65392e-14,
+                          6.90801e-14 1 -5.69011e-15,
+                          6.90801e-14 1 -5.69011e-15,
+                          6.90801e-14 1 -5.69011e-15,
+                          -0.00667765 6.33516e-15 0.999978,
+                          -0.00667765 6.33516e-15 0.999978,
+                          -0.00667765 6.33516e-15 0.999978,
+                          6.90801e-14 1 -5.69011e-15,
+                          6.90801e-14 1 -5.69011e-15,
+                          6.90801e-14 1 -5.69011e-15,
+                          0.00513697 6.23846e-14 0.999987,
+                          0.00513697 6.23846e-14 0.999987,
+                          0.00513697 6.23846e-14 0.999987,
+                          6.90801e-14 1 -5.69011e-15,
+                          6.90801e-14 1 -5.69011e-15,
+                          6.90801e-14 1 -5.69011e-15,
+                          -5.50942e-14 3.42983e-14 1,
+                          -5.50942e-14 3.42983e-14 1,
+                          -5.50942e-14 3.42983e-14 1,
+                          -0.00667765 6.33516e-15 0.999978,
+                          -0.00667765 6.33516e-15 0.999978,
+                          -0.00667765 6.33516e-15 0.999978,
+                          6.90801e-14 1 -5.69011e-15,
+                          6.90801e-14 1 -5.69011e-15,
+                          6.90801e-14 1 -5.69011e-15,
+                          -0.499989 0.866025 -0.00333882,
+                          6.43616e-14 1 -5.72177e-15,
+                          6.92466e-14 1 -5.68967e-15,
+                          6.90801e-14 1 -5.69011e-15,
+                          6.90801e-14 1 -5.69011e-15,
+                          6.90801e-14 1 -5.69011e-15,
+                          -0.499989 0.866025 -0.00333882,
+                          -0.484575 0.874744 -0.00323589,
+                          6.43616e-14 1 -5.72177e-15,
+                          -0.00896055 -0.00771062 0.99993,
+                          -0.00781899 -0.00771063 0.99994,
+                          0.227495 0.129613 0.965115,
+                          -5.50942e-14 3.42983e-14 1,
+                          -5.50942e-14 3.42983e-14 1,
+                          -5.50942e-14 3.42983e-14 1,
+                          -3.30423e-14 -3.42983e-14 -1,
+                          -3.30423e-14 -3.42983e-14 -1,
+                          -3.30423e-14 -3.42983e-14 -1,
+                          -0.808968 -0.468417 -0.355184,
+                          -0.689902 -0.400631 -0.602935,
+                          -0.79726 4.83853e-14 -0.603636,
+                          -3.30423e-14 -3.42983e-14 -1,
+                          -3.30423e-14 -3.42983e-14 -1,
+                          -3.30423e-14 -3.42983e-14 -1,
+                          -0.808968 -0.468417 -0.355184,
+                          -0.79726 4.83853e-14 -0.603636,
+                          -0.934482 5.87789e-14 -0.35601,
+                          1 -6.51388e-14 4.66035e-14,
+                          1 -6.51388e-14 4.66035e-14,
+                          1 -6.51388e-14 4.66035e-14,
+                          0.0153493 -6.37125e-14 -0.999882,
+                          0.0153493 -6.37125e-14 -0.999882,
+                          0.0153493 -6.37125e-14 -0.999882,
+                          1 -6.51388e-14 4.66035e-14,
+                          1 -6.51388e-14 4.66035e-14,
+                          1 -6.51388e-14 4.66035e-14,
+                          0.0153493 -6.37125e-14 -0.999882,
+                          0.0153493 -6.37125e-14 -0.999882,
+                          0.0153493 -6.37125e-14 -0.999882,
+                          0.42935 0.237946 0.871229,
+                          -0.00896055 -0.00771062 0.99993,
+                          0.227495 0.129613 0.965115,
+                          4.80414e-14 1 -5.77337e-15,
+                          4.80414e-14 1 -5.77337e-15,
+                          4.80414e-14 1 -5.77337e-15,
+                          4.80414e-14 1 -5.77337e-15,
+                          4.80414e-14 1 -5.77337e-15,
+                          4.80414e-14 1 -5.77337e-15,
+                          4.80414e-14 1 -5.77337e-15,
+                          4.80414e-14 1 -5.77337e-15,
+                          4.80414e-14 1 -5.77337e-15,
+                          4.80414e-14 1 -5.77337e-15,
+                          4.80414e-14 1 -5.77337e-15,
+                          4.80414e-14 1 -5.77337e-15,
+                          4.80414e-14 1 -5.77337e-15,
+                          4.80414e-14 1 -5.77337e-15,
+                          4.80414e-14 1 -5.77337e-15,
+                          4.80414e-14 1 -5.77337e-15,
+                          4.80414e-14 1 -5.77337e-15,
+                          4.80414e-14 1 -5.77337e-15,
+                          0.499989 0.866025 0.00333882,
+                          7.44092e-14 1 -5.5973e-15,
+                          7.44092e-14 1 -5.5973e-15,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          0.52383 0.851815 0.00349803,
+                          0.0894938 0.995987 0.000597621,
+                          0.499989 0.866025 0.00333882,
+                          0.499989 0.866025 0.00333882,
+                          0.0894938 0.995987 0.000597621,
+                          7.44092e-14 1 -5.5973e-15,
+                          -6.90801e-14 -1 5.69011e-15,
+                          -6.90801e-14 -1 5.69011e-15,
+                          -6.90801e-14 -1 5.69011e-15,
+                          -6.90801e-14 -1 5.69011e-15,
+                          -6.90801e-14 -1 5.69011e-15,
+                          -6.90801e-14 -1 5.69011e-15,
+                          -6.90801e-14 -1 5.69011e-15,
+                          -6.90801e-14 -1 5.69011e-15,
+                          -6.90801e-14 -1 5.69011e-15,
+                          -6.90801e-14 -1 5.69011e-15,
+                          -6.90801e-14 -1 5.69011e-15,
+                          -6.90801e-14 -1 5.69011e-15,
+                          0.493142 -0.869943 0.0032931,
+                          -4.83744e-14 -1 5.82889e-15,
+                          -9.73867e-15 -1 6.08693e-15,
+                          -6.90801e-14 -1 5.69011e-15,
+                          -6.90801e-14 -1 5.69011e-15,
+                          -6.90801e-14 -1 5.69011e-15,
+                          0.499989 -0.866025 0.00333882,
+                          -4.83744e-14 -1 5.82889e-15,
+                          0.493142 -0.869943 0.0032931,
+                          -6.90801e-14 -1 5.69011e-15,
+                          -6.90801e-14 -1 5.69011e-15,
+                          -6.90801e-14 -1 5.69011e-15,
+                          3.66004e-14 -5.87659e-15 -1,
+                          3.66004e-14 -5.87659e-15 -1,
+                          0.708204 -3.01521e-14 -0.706008,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.66004e-14 -5.87659e-15 -1,
+                          0.708204 -3.01521e-14 -0.706008,
+                          0.708204 -3.01521e-14 -0.706008,
+                          3.66004e-14 -5.87659e-15 -1,
+                          0.708204 -3.01521e-14 -0.706008,
+                          3.66004e-14 -5.87659e-15 -1,
+                          3.66004e-14 -5.87659e-15 -1,
+                          3.66004e-14 -5.87659e-15 -1,
+                          0.708204 -3.01521e-14 -0.706008,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1,
+                          3.65392e-14 -5.87659e-15 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -164.341 117.456 177.024,
+                          -164.348 -117.472 178.111,
+                          -165.806 -117.472 396.371,
+                          -164.287 -117.991 179.246,
+                          -165.806 -117.472 396.371,
+                          -164.348 -117.472 178.111,
+                          -165.807 117.456 396.563,
+                          -164.341 117.456 177.024,
+                          -165.806 -117.472 396.371,
+                          -165.809 -116.509 396.919,
+                          -165.807 117.456 396.563,
+                          -165.806 -117.472 396.371,
+                          -164.809 -116.511 396.925,
+                          -165.809 -116.509 396.919,
+                          -165.806 -117.472 396.371,
+                          -165.733 -117.997 396.074,
+                          -165.806 -117.472 396.371,
+                          -164.287 -117.991 179.246,
+                          -164.806 -117.472 396.378,
+                          -165.806 -117.472 396.371,
+                          -165.733 -117.997 396.074,
+                          -164.809 -116.511 396.925,
+                          -165.806 -117.472 396.371,
+                          -164.806 -117.472 396.378,
+                          -164.334 116.992 176,
+                          -164.334 -116.508 176,
+                          -164.348 -117.472 178.111,
+                          -163.348 -117.472 178.117,
+                          -164.348 -117.472 178.111,
+                          -164.334 -116.508 176,
+                          -164.341 117.456 177.024,
+                          -164.334 116.992 176,
+                          -164.348 -117.472 178.111,
+                          -163.321 -117.731 179.253,
+                          -164.287 -117.991 179.246,
+                          -164.348 -117.472 178.111,
+                          -163.321 -117.731 179.253,
+                          -164.348 -117.472 178.111,
+                          -163.348 -117.472 178.117,
+                          -164 116.992 126,
+                          -164 -116.508 126,
+                          -164.334 -116.508 176,
+                          -163.334 -116.508 176.007,
+                          -164.334 -116.508 176,
+                          -164 -116.508 126,
+                          -164.334 116.992 176,
+                          -164 116.992 126,
+                          -164.334 -116.508 176,
+                          -163.334 -116.508 176.007,
+                          -163.348 -117.472 178.117,
+                          -164.334 -116.508 176,
+                          -163 -116.508 126.007,
+                          -164 -116.508 126,
+                          -164 116.992 126,
+                          -163.334 -116.508 176.007,
+                          -164 -116.508 126,
+                          -163 -116.508 126.007,
+                          -163 116.992 126.007,
+                          -164 116.992 126,
+                          -164.334 116.992 176,
+                          -163 -116.508 126.007,
+                          -164 116.992 126,
+                          -163 116.992 126.007,
+                          -163.334 116.992 176.007,
+                          -164.334 116.992 176,
+                          -164.341 117.456 177.024,
+                          -163 116.992 126.007,
+                          -164.334 116.992 176,
+                          -163.334 116.992 176.007,
+                          -165.735 117.981 396.263,
+                          -164.341 117.456 177.024,
+                          -165.807 117.456 396.563,
+                          -164.28 117.975 178.169,
+                          -164.341 117.456 177.024,
+                          -165.735 117.981 396.263,
+                          -163.341 117.456 177.031,
+                          -164.341 117.456 177.024,
+                          -164.28 117.975 178.169,
+                          -163.334 116.992 176.007,
+                          -164.341 117.456 177.024,
+                          -163.341 117.456 177.031,
+                          -165.809 -116.509 396.919,
+                          -165.809 116.993 396.828,
+                          -165.807 117.456 396.563,
+                          -164.809 116.994 396.834,
+                          -165.807 117.456 396.563,
+                          -165.809 116.993 396.828,
+                          -164.77 117.717 396.271,
+                          -165.735 117.981 396.263,
+                          -165.807 117.456 396.563,
+                          -164.77 117.717 396.271,
+                          -165.807 117.456 396.563,
+                          -164.807 117.456 396.569,
+                          -164.809 116.994 396.834,
+                          -164.807 117.456 396.569,
+                          -165.807 117.456 396.563,
+                          -165.809 -116.509 396.919,
+                          -165.889 95.984 408.843,
+                          -165.809 116.993 396.828,
+                          -164.809 116.994 396.834,
+                          -165.809 116.993 396.828,
+                          -165.889 95.984 408.843,
+                          -165.907 -90.6468 411.631,
+                          -165.936 88.1547 415.871,
+                          -165.889 95.984 408.843,
+                          -164.889 95.984 408.849,
+                          -165.889 95.984 408.843,
+                          -165.936 88.1547 415.871,
+                          -165.809 -116.509 396.919,
+                          -165.907 -90.6468 411.631,
+                          -165.889 95.984 408.843,
+                          -164.809 116.994 396.834,
+                          -165.889 95.984 408.843,
+                          -164.889 95.984 408.849,
+                          -166 -79.2771 425.497,
+                          -166 83.9102 425.497,
+                          -165.936 88.1547 415.871,
+                          -164.936 88.1519 415.882,
+                          -165.936 88.1547 415.871,
+                          -166 83.9102 425.497,
+                          -165.947 -83.6735 417.512,
+                          -166 -79.2771 425.497,
+                          -165.936 88.1547 415.871,
+                          -165.907 -90.6468 411.631,
+                          -165.947 -83.6735 417.512,
+                          -165.936 88.1547 415.871,
+                          -164.889 95.984 408.849,
+                          -165.936 88.1547 415.871,
+                          -164.936 88.1519 415.882,
+                          -166 83.615 427.237,
+                          -166 83.9102 425.497,
+                          -166 -79.2771 425.497,
+                          -165 83.9102 425.5,
+                          -166 83.9102 425.497,
+                          -166 83.615 427.237,
+                          -164.936 88.1519 415.882,
+                          -166 83.9102 425.497,
+                          -165 83.9102 425.5,
+                          -165 -79.2771 425.5,
+                          -166 -79.2771 425.497,
+                          -165.947 -83.6735 417.512,
+                          -166 83.4431 429,
+                          -166 83.615 427.237,
+                          -166 -79.2771 425.497,
+                          -166 -78.769 427.239,
+                          -166 83.4431 429,
+                          -166 -79.2771 425.497,
+                          -165 -78.7675 427.246,
+                          -166 -78.769 427.239,
+                          -166 -79.2771 425.497,
+                          -165 -78.7675 427.246,
+                          -166 -79.2771 425.497,
+                          -165 -79.2771 425.5,
+                          -164.947 -83.6732 417.519,
+                          -165.947 -83.6735 417.512,
+                          -165.907 -90.6468 411.631,
+                          -164.947 -83.6732 417.519,
+                          -165 -79.2771 425.5,
+                          -165.947 -83.6735 417.512,
+                          -164.907 -90.6468 411.637,
+                          -165.907 -90.6468 411.631,
+                          -165.809 -116.509 396.919,
+                          -164.947 -83.6732 417.519,
+                          -165.907 -90.6468 411.631,
+                          -164.907 -90.6468 411.637,
+                          -164.907 -90.6468 411.637,
+                          -165.809 -116.509 396.919,
+                          -164.809 -116.511 396.925,
+                          -165 83.6156 427.233,
+                          -166 83.615 427.237,
+                          -166 83.4431 429,
+                          -165 83.9102 425.5,
+                          -166 83.615 427.237,
+                          -165 83.6156 427.233,
+                          -166 -78.769 427.239,
+                          -166 -78.3913 429,
+                          -166 83.4431 429,
+                          -165.81 -78.2412 429.956,
+                          -166 83.4431 429,
+                          -166 -78.3913 429,
+                          -165.863 83.406 429.817,
+                          -166 83.4431 429,
+                          -165.81 -78.2412 429.956,
+                          -165 83.4431 429,
+                          -166 83.4431 429,
+                          -165.863 83.406 429.817,
+                          -165 83.6156 427.233,
+                          -166 83.4431 429,
+                          -165 83.4431 429,
+                          -165 -78.3913 429,
+                          -166 -78.3913 429,
+                          -166 -78.769 427.239,
+                          -164.886 -78.2412 429.573,
+                          -165.81 -78.2412 429.956,
+                          -166 -78.3913 429,
+                          -164.886 -78.2412 429.573,
+                          -166 -78.3913 429,
+                          -165 -78.3913 429,
+                          -165 -78.3913 429,
+                          -166 -78.769 427.239,
+                          -165 -78.7675 427.246,
+                          -139.387 114.992 566.383,
+                          -137.9 -115.008 567,
+                          -137.9 -61.021 567,
+                          -135.465 -71.783 567,
+                          -137.9 -61.021 567,
+                          -137.9 -115.008 567,
+                          -137.9 61.0049 567,
+                          -139.387 114.992 566.383,
+                          -137.9 -61.021 567,
+                          -137.9 61.0049 566,
+                          -137.9 61.0049 567,
+                          -137.9 -61.021 567,
+                          -137.9 -61.021 566,
+                          -137.9 -61.021 567,
+                          -135.465 -71.783 567,
+                          -137.9 61.0049 566,
+                          -137.9 -61.021 567,
+                          -137.9 -61.021 566,
+                          -139.387 114.992 566.383,
+                          -139.387 -115.008 566.383,
+                          -137.9 -115.008 567,
+                          -137.9 -115.008 566,
+                          -137.9 -115.008 567,
+                          -139.387 -115.008 566.383,
+                          -88.0955 -91.2583 567,
+                          -118.738 -85.3297 567,
+                          -137.9 -115.008 567,
+                          -128.634 -80.4486 567,
+                          -137.9 -115.008 567,
+                          -118.738 -85.3297 567,
+                          -57.0616 -94.4326 567,
+                          -88.0955 -91.2583 567,
+                          -137.9 -115.008 567,
+                          -57.0616 -115.008 567,
+                          -57.0616 -94.4326 567,
+                          -137.9 -115.008 567,
+                          -57.0616 -115.008 566,
+                          -57.0616 -115.008 567,
+                          -137.9 -115.008 567,
+                          -128.634 -80.4486 567,
+                          -135.465 -71.783 567,
+                          -137.9 -115.008 567,
+                          -57.0616 -115.008 566,
+                          -137.9 -115.008 567,
+                          -137.9 -115.008 566,
+                          -140 114.992 564.9,
+                          -140 -115.008 564.9,
+                          -139.387 -115.008 566.383,
+                          -139 -115.008 564.9,
+                          -139.387 -115.008 566.383,
+                          -140 -115.008 564.9,
+                          -139.387 114.992 566.383,
+                          -140 114.992 564.9,
+                          -139.387 -115.008 566.383,
+                          -138.679 -115.008 565.677,
+                          -139.387 -115.008 566.383,
+                          -139 -115.008 564.9,
+                          -138.679 -115.008 565.677,
+                          -137.9 -115.008 566,
+                          -139.387 -115.008 566.383,
+                          -140 -115.008 488.408,
+                          -140 -115.008 564.9,
+                          -140 114.992 564.9,
+                          -139 -115.008 564.9,
+                          -140 -115.008 564.9,
+                          -140 -115.008 488.408,
+                          -139 114.992 564.9,
+                          -140 114.992 564.9,
+                          -139.387 114.992 566.383,
+                          -140 114.992 500.125,
+                          -140 86.6938 450.644,
+                          -140 114.992 564.9,
+                          -140 84.2346 444.653,
+                          -140 114.992 564.9,
+                          -140 86.6938 450.644,
+                          -139 114.992 500.125,
+                          -140 114.992 500.125,
+                          -140 114.992 564.9,
+                          -140 -86.0247 461.577,
+                          -140 -115.008 488.408,
+                          -140 114.992 564.9,
+                          -140 -80.0997 453.242,
+                          -140 -86.0247 461.577,
+                          -140 114.992 564.9,
+                          -140 -78.008 443.231,
+                          -140 -80.0997 453.242,
+                          -140 114.992 564.9,
+                          -140 -78.008 433.534,
+                          -140 -78.008 443.231,
+                          -140 114.992 564.9,
+                          -140 84.2346 444.653,
+                          -140 -78.008 433.534,
+                          -140 114.992 564.9,
+                          -139 114.992 500.125,
+                          -140 114.992 564.9,
+                          -139 114.992 564.9,
+                          -137.9 61.0049 567,
+                          -137.9 114.992 567,
+                          -139.387 114.992 566.383,
+                          -138.679 114.992 565.677,
+                          -139.387 114.992 566.383,
+                          -137.9 114.992 567,
+                          -138.679 114.992 565.677,
+                          -139 114.992 564.9,
+                          -139.387 114.992 566.383,
+                          -135.465 71.767 567,
+                          -137.9 114.992 567,
+                          -137.9 61.0049 567,
+                          -128.634 80.4326 567,
+                          -118.738 85.3136 567,
+                          -137.9 114.992 567,
+                          -57.0616 114.992 567,
+                          -137.9 114.992 567,
+                          -118.738 85.3136 567,
+                          -135.465 71.767 567,
+                          -128.634 80.4326 567,
+                          -137.9 114.992 567,
+                          -137.9 114.992 566,
+                          -137.9 114.992 567,
+                          -57.0616 114.992 567,
+                          -137.9 114.992 566,
+                          -138.679 114.992 565.677,
+                          -137.9 114.992 567,
+                          -135.465 71.767 566,
+                          -135.465 71.767 567,
+                          -137.9 61.0049 567,
+                          -135.465 71.767 566,
+                          -137.9 61.0049 567,
+                          -137.9 61.0049 566,
+                          -118.738 -85.3297 566,
+                          -118.738 -85.3297 567,
+                          -88.0955 -91.2583 567,
+                          -128.634 -80.4486 566,
+                          -128.634 -80.4486 567,
+                          -118.738 -85.3297 567,
+                          -118.738 -85.3297 566,
+                          -128.634 -80.4486 566,
+                          -118.738 -85.3297 567,
+                          -88.0955 -91.2583 566,
+                          -88.0955 -91.2583 567,
+                          -57.0616 -94.4326 567,
+                          -88.0955 -91.2583 566,
+                          -118.738 -85.3297 566,
+                          -88.0955 -91.2583 567,
+                          -57.0616 -94.4326 566,
+                          -57.0616 -94.4326 567,
+                          -57.0616 -115.008 567,
+                          -88.0955 -91.2583 566,
+                          -57.0616 -94.4326 567,
+                          -57.0616 -94.4326 566,
+                          -57.0616 -94.4326 566,
+                          -57.0616 -115.008 567,
+                          -57.0616 -115.008 566,
+                          -135.465 -71.783 566,
+                          -135.465 -71.783 567,
+                          -128.634 -80.4486 567,
+                          -135.465 -71.783 566,
+                          -137.9 -61.021 566,
+                          -135.465 -71.783 567,
+                          -128.634 -80.4486 566,
+                          -135.465 -71.783 566,
+                          -128.634 -80.4486 567,
+                          -57.0616 114.992 567,
+                          -88.0955 91.2422 567,
+                          -57.0616 94.4165 567,
+                          -57.0616 94.4165 566,
+                          -57.0616 94.4165 567,
+                          -88.0955 91.2422 567,
+                          -57.0616 114.992 566,
+                          -57.0616 114.992 567,
+                          -57.0616 94.4165 567,
+                          -57.0616 114.992 566,
+                          -57.0616 94.4165 567,
+                          -57.0616 94.4165 566,
+                          -57.0616 114.992 567,
+                          -118.738 85.3136 567,
+                          -88.0955 91.2422 567,
+                          -88.0955 91.2422 566,
+                          -88.0955 91.2422 567,
+                          -118.738 85.3136 567,
+                          -88.0955 91.2422 566,
+                          -57.0616 94.4165 566,
+                          -88.0955 91.2422 567,
+                          -118.738 85.3136 566,
+                          -118.738 85.3136 567,
+                          -128.634 80.4326 567,
+                          -88.0955 91.2422 566,
+                          -118.738 85.3136 567,
+                          -118.738 85.3136 566,
+                          -128.634 80.4326 566,
+                          -128.634 80.4326 567,
+                          -135.465 71.767 567,
+                          -128.634 80.4326 566,
+                          -118.738 85.3136 566,
+                          -128.634 80.4326 567,
+                          -135.465 71.767 566,
+                          -128.634 80.4326 566,
+                          -135.465 71.767 567,
+                          -57.0616 114.992 566,
+                          -137.9 114.992 566,
+                          -57.0616 114.992 567,
+                          -165.267 -78.1432 430.769,
+                          -164.595 83.3954 431.247,
+                          -165.463 83.3954 430.548,
+                          -164.678 83.3954 429.929,
+                          -165.463 83.3954 430.548,
+                          -164.595 83.3954 431.247,
+                          -165.81 -78.2412 429.956,
+                          -165.267 -78.1432 430.769,
+                          -165.463 83.3954 430.548,
+                          -165.863 83.406 429.817,
+                          -165.81 -78.2412 429.956,
+                          -165.463 83.3954 430.548,
+                          -164.918 83.406 429.49,
+                          -165.863 83.406 429.817,
+                          -165.463 83.3954 430.548,
+                          -164.918 83.406 429.49,
+                          -165.463 83.3954 430.548,
+                          -164.678 83.3954 429.929,
+                          -163.5 -78.0786 431.5,
+                          -163.5 83.3954 431.5,
+                          -164.595 83.3954 431.247,
+                          -163.5 83.3954 430.5,
+                          -164.595 83.3954 431.247,
+                          -163.5 83.3954 431.5,
+                          -164.453 -78.093 431.311,
+                          -163.5 -78.0786 431.5,
+                          -164.595 83.3954 431.247,
+                          -165.267 -78.1432 430.769,
+                          -164.453 -78.093 431.311,
+                          -164.595 83.3954 431.247,
+                          -164.157 83.3954 430.348,
+                          -164.678 83.3954 429.929,
+                          -164.595 83.3954 431.247,
+                          -164.157 83.3954 430.348,
+                          -164.595 83.3954 431.247,
+                          -163.5 83.3954 430.5,
+                          -140.5 83.3954 431.5,
+                          -163.5 83.3954 431.5,
+                          -163.5 -78.0786 431.5,
+                          -163.5 83.3954 430.5,
+                          -163.5 83.3954 431.5,
+                          -140.5 83.3954 431.5,
+                          -163.5 -78.0786 430.5,
+                          -163.5 -78.0786 431.5,
+                          -164.453 -78.093 431.311,
+                          -151.998 -78.0845 431.5,
+                          -140.5 83.3954 431.5,
+                          -163.5 -78.0786 431.5,
+                          -151.998 -78.0845 430.5,
+                          -151.998 -78.0845 431.5,
+                          -163.5 -78.0786 431.5,
+                          -151.998 -78.0845 430.5,
+                          -163.5 -78.0786 431.5,
+                          -163.5 -78.0786 430.5,
+                          -164.072 -78.093 430.387,
+                          -164.453 -78.093 431.311,
+                          -165.267 -78.1432 430.769,
+                          -163.5 -78.0786 430.5,
+                          -164.453 -78.093 431.311,
+                          -164.072 -78.093 430.387,
+                          -164.56 -78.1432 430.061,
+                          -165.267 -78.1432 430.769,
+                          -165.81 -78.2412 429.956,
+                          -164.072 -78.093 430.387,
+                          -165.267 -78.1432 430.769,
+                          -164.56 -78.1432 430.061,
+                          -164.56 -78.1432 430.061,
+                          -165.81 -78.2412 429.956,
+                          -164.886 -78.2412 429.573,
+                          -164.918 83.406 429.49,
+                          -165 83.4431 429,
+                          -165.863 83.406 429.817,
+                          -151.998 -78.0845 431.5,
+                          -140.5 -78.0907 431.5,
+                          -140.5 83.3954 431.5,
+                          -140.147 -78.0793 431.646,
+                          -140.5 83.3954 431.5,
+                          -140.5 -78.0907 431.5,
+                          -140.147 83.3954 431.647,
+                          -140.5 83.3954 431.5,
+                          -140.147 -78.0793 431.646,
+                          -139.441 83.3954 430.941,
+                          -140.5 83.3954 431.5,
+                          -140.147 83.3954 431.647,
+                          -140.5 83.3954 430.5,
+                          -163.5 83.3954 430.5,
+                          -140.5 83.3954 431.5,
+                          -139.441 83.3954 430.941,
+                          -140.5 83.3954 430.5,
+                          -140.5 83.3954 431.5,
+                          -140.5 -78.0907 430.5,
+                          -140.5 -78.0907 431.5,
+                          -151.998 -78.0845 431.5,
+                          -139.44 -78.0793 430.939,
+                          -140.147 -78.0793 431.646,
+                          -140.5 -78.0907 431.5,
+                          -139.44 -78.0793 430.939,
+                          -140.5 -78.0907 431.5,
+                          -140.5 -78.0907 430.5,
+                          -140.5 -78.0907 430.5,
+                          -151.998 -78.0845 431.5,
+                          -151.998 -78.0845 430.5,
+                          -140.147 83.3954 431.647,
+                          -140 -78.0552 432,
+                          -140 83.3954 432,
+                          -140 83.3954 438.232,
+                          -140 83.3954 432,
+                          -140 -78.0552 432,
+                          -139.441 83.3954 430.941,
+                          -140.147 83.3954 431.647,
+                          -140 83.3954 432,
+                          -139 83.3954 432,
+                          -140 83.3954 432,
+                          -140 83.3954 438.232,
+                          -139.441 83.3954 430.941,
+                          -140 83.3954 432,
+                          -139 83.3954 432,
+                          -140.147 83.3954 431.647,
+                          -140.147 -78.0793 431.646,
+                          -140 -78.0552 432,
+                          -139 -78.0552 432,
+                          -140 -78.0552 432,
+                          -140.147 -78.0793 431.646,
+                          -140 83.3954 438.232,
+                          -140 -78.0552 432,
+                          -140 -78.0198 432.766,
+                          -139 -78.0198 432.766,
+                          -140 -78.0198 432.766,
+                          -140 -78.0552 432,
+                          -139 -78.0198 432.766,
+                          -140 -78.0552 432,
+                          -139 -78.0552 432,
+                          -139 -78.0552 432,
+                          -140.147 -78.0793 431.646,
+                          -139.44 -78.0793 430.939,
+                          -139 86.6938 450.644,
+                          -140 86.6938 450.644,
+                          -140 114.992 500.125,
+                          -139 84.2346 444.653,
+                          -140 84.2346 444.653,
+                          -140 86.6938 450.644,
+                          -139 84.2346 444.653,
+                          -140 86.6938 450.644,
+                          -139 86.6938 450.644,
+                          -139 114.992 500.125,
+                          -139 86.6938 450.644,
+                          -140 114.992 500.125,
+                          -139 -115.008 488.408,
+                          -140 -115.008 488.408,
+                          -140 -86.0247 461.577,
+                          -139 -115.008 564.9,
+                          -140 -115.008 488.408,
+                          -139 -115.008 488.408,
+                          -139 -86.0247 461.577,
+                          -140 -86.0247 461.577,
+                          -140 -80.0997 453.242,
+                          -139 -115.008 488.408,
+                          -140 -86.0247 461.577,
+                          -139 -86.0247 461.577,
+                          -139 -80.0997 453.242,
+                          -140 -80.0997 453.242,
+                          -140 -78.008 443.231,
+                          -139 -86.0247 461.577,
+                          -140 -80.0997 453.242,
+                          -139 -80.0997 453.242,
+                          -139 -78.008 443.231,
+                          -140 -78.008 443.231,
+                          -140 -78.008 433.534,
+                          -139 -80.0997 453.242,
+                          -140 -78.008 443.231,
+                          -139 -78.008 443.231,
+                          -140 83.3954 438.232,
+                          -140 -78.0198 432.766,
+                          -140 -78.008 433.534,
+                          -139 -78.008 433.534,
+                          -140 -78.008 433.534,
+                          -140 -78.0198 432.766,
+                          -140 84.2346 444.653,
+                          -140 83.3954 438.232,
+                          -140 -78.008 433.534,
+                          -139 -78.008 443.231,
+                          -140 -78.008 433.534,
+                          -139 -78.008 433.534,
+                          -139 -78.008 433.534,
+                          -140 -78.0198 432.766,
+                          -139 -78.0198 432.766,
+                          -139 83.3954 438.232,
+                          -140 83.3954 438.232,
+                          -140 84.2346 444.653,
+                          -139 83.3954 438.232,
+                          -139 83.3954 432,
+                          -140 83.3954 438.232,
+                          -139 83.3954 438.232,
+                          -140 84.2346 444.653,
+                          -139 84.2346 444.653,
+                          -164.095 -118.472 180.3,
+                          -130.35 -179.016 361.598,
+                          -165.534 -118.472 395.804,
+                          -164.668 -117.972 395.81,
+                          -165.534 -118.472 395.804,
+                          -130.35 -179.016 361.598,
+                          -165.733 -117.997 396.074,
+                          -164.095 -118.472 180.3,
+                          -165.534 -118.472 395.804,
+                          -164.769 -117.734 396.081,
+                          -165.733 -117.997 396.074,
+                          -165.534 -118.472 395.804,
+                          -164.769 -117.734 396.081,
+                          -165.534 -118.472 395.804,
+                          -164.668 -117.972 395.81,
+                          -164.095 -118.472 180.3,
+                          -130.024 -179.016 312.851,
+                          -130.35 -179.016 361.598,
+                          -129.283 -179.748 311.444,
+                          -130.35 -179.016 361.598,
+                          -130.024 -179.016 312.851,
+                          -129.484 -178.516 361.604,
+                          -164.668 -117.972 395.81,
+                          -130.35 -179.016 361.598,
+                          -129.662 -179.72 361.203,
+                          -129.484 -178.516 361.604,
+                          -130.35 -179.016 361.598,
+                          -129.662 -179.72 361.203,
+                          -130.35 -179.016 361.598,
+                          -129.283 -179.748 311.444,
+                          -129.158 -178.516 312.856,
+                          -130.024 -179.016 312.851,
+                          -164.095 -118.472 180.3,
+                          -128.783 -178.882 311.448,
+                          -130.024 -179.016 312.851,
+                          -129.158 -178.516 312.856,
+                          -128.783 -178.882 311.448,
+                          -129.283 -179.748 311.444,
+                          -130.024 -179.016 312.851,
+                          -165.733 -117.997 396.074,
+                          -164.287 -117.991 179.246,
+                          -164.095 -118.472 180.3,
+                          -163.229 -117.972 180.306,
+                          -164.095 -118.472 180.3,
+                          -164.287 -117.991 179.246,
+                          -129.158 -178.516 312.856,
+                          -164.095 -118.472 180.3,
+                          -163.229 -117.972 180.306,
+                          -163.321 -117.731 179.253,
+                          -163.229 -117.972 180.306,
+                          -164.287 -117.991 179.246,
+                          -164.806 -117.472 396.378,
+                          -165.733 -117.997 396.074,
+                          -164.769 -117.734 396.081,
+                          -130.024 179 312.833,
+                          -164.088 118.456 179.231,
+                          -165.535 118.456 395.993,
+                          -164.28 117.975 178.169,
+                          -165.535 118.456 395.993,
+                          -164.088 118.456 179.231,
+                          -130.35 179 361.601,
+                          -130.024 179 312.833,
+                          -165.535 118.456 395.993,
+                          -129.484 178.5 361.607,
+                          -130.35 179 361.601,
+                          -165.535 118.456 395.993,
+                          -164.28 117.975 178.169,
+                          -165.735 117.981 396.263,
+                          -165.535 118.456 395.993,
+                          -164.669 117.956 395.999,
+                          -165.535 118.456 395.993,
+                          -165.735 117.981 396.263,
+                          -129.484 178.5 361.607,
+                          -165.535 118.456 395.993,
+                          -164.669 117.956 395.999,
+                          -163.222 117.956 179.237,
+                          -164.088 118.456 179.231,
+                          -130.024 179 312.833,
+                          -163.314 117.715 178.175,
+                          -164.28 117.975 178.169,
+                          -164.088 118.456 179.231,
+                          -163.314 117.715 178.175,
+                          -164.088 118.456 179.231,
+                          -163.222 117.956 179.237,
+                          -129.584 179.749 361.178,
+                          -130.024 179 312.833,
+                          -130.35 179 361.601,
+                          -163.222 117.956 179.237,
+                          -130.024 179 312.833,
+                          -129.158 178.5 312.839,
+                          -129.282 179.732 311.436,
+                          -129.158 178.5 312.839,
+                          -130.024 179 312.833,
+                          -129.282 179.732 311.436,
+                          -130.024 179 312.833,
+                          -129.584 179.749 361.178,
+                          -129.108 178.87 361.183,
+                          -130.35 179 361.601,
+                          -129.484 178.5 361.607,
+                          -129.108 178.87 361.183,
+                          -129.584 179.749 361.178,
+                          -130.35 179 361.601,
+                          -164.77 117.717 396.271,
+                          -164.669 117.956 395.999,
+                          -165.735 117.981 396.263,
+                          -163.341 117.456 177.031,
+                          -164.28 117.975 178.169,
+                          -163.314 117.715 178.175,
+                          -165 83.9102 425.5,
+                          -165 -78.7675 427.246,
+                          -165 -79.2771 425.5,
+                          -164.947 -83.6732 417.519,
+                          -165 83.9102 425.5,
+                          -165 -79.2771 425.5,
+                          -165 83.9102 425.5,
+                          -165 -78.3913 429,
+                          -165 -78.7675 427.246,
+                          -165 83.6156 427.233,
+                          -165 83.4431 429,
+                          -165 -78.3913 429,
+                          -164.918 83.406 429.49,
+                          -165 -78.3913 429,
+                          -165 83.4431 429,
+                          -165 83.9102 425.5,
+                          -165 83.6156 427.233,
+                          -165 -78.3913 429,
+                          -164.886 -78.2412 429.573,
+                          -165 -78.3913 429,
+                          -164.918 83.406 429.49,
+                          -164.936 88.1519 415.882,
+                          -165 83.9102 425.5,
+                          -164.947 -83.6732 417.519,
+                          -129.158 -178.516 312.856,
+                          -163.229 -117.972 180.306,
+                          -164.668 -117.972 395.81,
+                          -163.321 -117.731 179.253,
+                          -164.668 -117.972 395.81,
+                          -163.229 -117.972 180.306,
+                          -129.484 -178.516 361.604,
+                          -129.158 -178.516 312.856,
+                          -164.668 -117.972 395.81,
+                          -163.321 -117.731 179.253,
+                          -164.769 -117.734 396.081,
+                          -164.668 -117.972 395.81,
+                          -129.139 -178.868 361.206,
+                          -129.158 -178.516 312.856,
+                          -129.484 -178.516 361.604,
+                          -129.139 -178.868 361.206,
+                          -128.783 -178.882 311.448,
+                          -129.158 -178.516 312.856,
+                          -129.139 -178.868 361.206,
+                          -129.484 -178.516 361.604,
+                          -129.662 -179.72 361.203,
+                          -163.348 -117.472 178.117,
+                          -164.806 -117.472 396.378,
+                          -164.769 -117.734 396.081,
+                          -163.321 -117.731 179.253,
+                          -163.348 -117.472 178.117,
+                          -164.769 -117.734 396.081,
+                          -164.807 117.456 396.569,
+                          -164.806 -117.472 396.378,
+                          -163.348 -117.472 178.117,
+                          -164.809 116.994 396.834,
+                          -164.806 -117.472 396.378,
+                          -164.807 117.456 396.569,
+                          -164.809 116.994 396.834,
+                          -164.809 -116.511 396.925,
+                          -164.806 -117.472 396.378,
+                          -164.807 117.456 396.569,
+                          -163.348 -117.472 178.117,
+                          -163.341 117.456 177.031,
+                          -163.334 -116.508 176.007,
+                          -163.341 117.456 177.031,
+                          -163.348 -117.472 178.117,
+                          -164.886 -78.2412 429.573,
+                          -164.918 83.406 429.49,
+                          -164.678 83.3954 429.929,
+                          -164.56 -78.1432 430.061,
+                          -164.886 -78.2412 429.573,
+                          -164.678 83.3954 429.929,
+                          -164.157 83.3954 430.348,
+                          -164.56 -78.1432 430.061,
+                          -164.678 83.3954 429.929,
+                          -164.157 83.3954 430.348,
+                          -164.072 -78.093 430.387,
+                          -164.56 -78.1432 430.061,
+                          -163.5 83.3954 430.5,
+                          -163.5 -78.0786 430.5,
+                          -164.072 -78.093 430.387,
+                          -164.157 83.3954 430.348,
+                          -163.5 83.3954 430.5,
+                          -164.072 -78.093 430.387,
+                          -151.998 -78.0845 430.5,
+                          -163.5 -78.0786 430.5,
+                          -163.5 83.3954 430.5,
+                          -140.5 -78.0907 430.5,
+                          -151.998 -78.0845 430.5,
+                          -163.5 83.3954 430.5,
+                          -140.5 83.3954 430.5,
+                          -140.5 -78.0907 430.5,
+                          -163.5 83.3954 430.5,
+                          -139.441 83.3954 430.941,
+                          -140.5 -78.0907 430.5,
+                          -140.5 83.3954 430.5,
+                          -139.44 -78.0793 430.939,
+                          -140.5 -78.0907 430.5,
+                          -139.441 83.3954 430.941,
+                          -139.44 -78.0793 430.939,
+                          -139.441 83.3954 430.941,
+                          -139 83.3954 432,
+                          -139 -78.0552 432,
+                          -139.44 -78.0793 430.939,
+                          -139 83.3954 432,
+                          -139 -78.0198 432.766,
+                          -139 -78.0552 432,
+                          -139 83.3954 432,
+                          -139 -115.008 564.9,
+                          -139 83.3954 432,
+                          -139 83.3954 438.232,
+                          -139 -78.008 433.534,
+                          -139 -78.0198 432.766,
+                          -139 83.3954 432,
+                          -139 -78.008 443.231,
+                          -139 -78.008 433.534,
+                          -139 83.3954 432,
+                          -139 -80.0997 453.242,
+                          -139 -78.008 443.231,
+                          -139 83.3954 432,
+                          -139 -115.008 564.9,
+                          -139 -80.0997 453.242,
+                          -139 83.3954 432,
+                          -139 -115.008 564.9,
+                          -139 84.2346 444.653,
+                          -139 86.6938 450.644,
+                          -139 114.992 500.125,
+                          -139 -115.008 564.9,
+                          -139 86.6938 450.644,
+                          -139 -115.008 564.9,
+                          -139 83.3954 438.232,
+                          -139 84.2346 444.653,
+                          -139 -115.008 564.9,
+                          -139 -86.0247 461.577,
+                          -139 -80.0997 453.242,
+                          -139 -115.008 564.9,
+                          -139 -115.008 488.408,
+                          -139 -86.0247 461.577,
+                          -139 114.992 500.125,
+                          -139 114.992 564.9,
+                          -139 -115.008 564.9,
+                          -138.679 114.992 565.677,
+                          -139 -115.008 564.9,
+                          -139 114.992 564.9,
+                          -138.679 114.992 565.677,
+                          -138.679 -115.008 565.677,
+                          -139 -115.008 564.9,
+                          -163.222 117.956 179.237,
+                          -129.484 178.5 361.607,
+                          -164.669 117.956 395.999,
+                          -164.77 117.717 396.271,
+                          -163.222 117.956 179.237,
+                          -164.669 117.956 395.999,
+                          -163.222 117.956 179.237,
+                          -129.158 178.5 312.839,
+                          -129.484 178.5 361.607,
+                          -128.782 178.866 311.439,
+                          -129.484 178.5 361.607,
+                          -129.158 178.5 312.839,
+                          -128.782 178.866 311.439,
+                          -129.108 178.87 361.183,
+                          -129.484 178.5 361.607,
+                          -128.782 178.866 311.439,
+                          -129.158 178.5 312.839,
+                          -129.282 179.732 311.436,
+                          -164.77 117.717 396.271,
+                          -163.314 117.715 178.175,
+                          -163.222 117.956 179.237,
+                          -164.807 117.456 396.569,
+                          -163.341 117.456 177.031,
+                          -163.314 117.715 178.175,
+                          -164.77 117.717 396.271,
+                          -164.807 117.456 396.569,
+                          -163.314 117.715 178.175,
+                          -163.334 -116.508 176.007,
+                          -163.334 116.992 176.007,
+                          -163.341 117.456 177.031,
+                          -164.889 95.984 408.849,
+                          -164.907 -90.6468 411.637,
+                          -164.809 -116.511 396.925,
+                          -164.809 116.994 396.834,
+                          -164.889 95.984 408.849,
+                          -164.809 -116.511 396.925,
+                          -164.936 88.1519 415.882,
+                          -164.947 -83.6732 417.519,
+                          -164.907 -90.6468 411.637,
+                          -164.889 95.984 408.849,
+                          -164.936 88.1519 415.882,
+                          -164.907 -90.6468 411.637,
+                          -163 -116.508 126.007,
+                          -163 116.992 126.007,
+                          -163.334 116.992 176.007,
+                          -163.334 -116.508 176.007,
+                          -163 -116.508 126.007,
+                          -163.334 116.992 176.007,
+                          -43.1873 -180.016 361.072,
+                          15 -180.016 315.06,
+                          15 -180.016 360.773,
+                          15 -179.016 360.773,
+                          15 -180.016 360.773,
+                          15 -180.016 315.06,
+                          -43.1873 -179.016 361.072,
+                          -43.1873 -180.016 361.072,
+                          15 -180.016 360.773,
+                          -43.1873 -179.016 361.072,
+                          15 -180.016 360.773,
+                          15 -179.016 360.773,
+                          -48.9627 -180.016 361.033,
+                          -128.024 -180.016 312.881,
+                          15 -180.016 315.06,
+                          15 -179.016 315.06,
+                          15 -180.016 315.06,
+                          -128.024 -180.016 312.881,
+                          -43.1873 -180.016 361.072,
+                          -48.9627 -180.016 361.033,
+                          15 -180.016 315.06,
+                          15 -179.016 360.773,
+                          15 -180.016 315.06,
+                          15 -179.016 315.06,
+                          -128.614 -180.016 361.033,
+                          -128.005 -180.016 310.04,
+                          -128.024 -180.016 312.881,
+                          -128.024 -179.016 312.881,
+                          -128.024 -180.016 312.881,
+                          -128.005 -180.016 310.04,
+                          -48.9627 -180.016 361.033,
+                          -128.614 -180.016 361.033,
+                          -128.024 -180.016 312.881,
+                          -128.024 -179.016 312.881,
+                          15 -179.016 315.06,
+                          -128.024 -180.016 312.881,
+                          -128.614 -180.016 361.033,
+                          -128.307 -180.016 310.04,
+                          -128.005 -180.016 310.04,
+                          -128.273 -179.016 310.04,
+                          -128.005 -180.016 310.04,
+                          -128.307 -180.016 310.04,
+                          -128.005 -179.016 310.04,
+                          -128.024 -179.016 312.881,
+                          -128.005 -180.016 310.04,
+                          -128.273 -179.016 310.04,
+                          -128.005 -179.016 310.04,
+                          -128.005 -180.016 310.04,
+                          -88.0955 -91.2583 566,
+                          -57.0616 -94.4326 566,
+                          -57.0616 -115.008 566,
+                          -128.793 -180.008 361.044,
+                          -129.283 -179.748 311.444,
+                          -128.307 -180.016 310.04,
+                          -128.273 -179.016 310.04,
+                          -128.307 -180.016 310.04,
+                          -129.283 -179.748 311.444,
+                          -128.614 -180.016 361.033,
+                          -128.793 -180.008 361.044,
+                          -128.307 -180.016 310.04,
+                          -128.614 -179.016 361.033,
+                          -128.614 -180.016 361.033,
+                          -48.9627 -180.016 361.033,
+                          -88.0955 -91.2583 566,
+                          -57.0616 -115.008 566,
+                          -118.738 -85.3297 566,
+                          -48.9627 -179.016 361.033,
+                          -48.9627 -180.016 361.033,
+                          -43.1873 -180.016 361.072,
+                          -48.9627 -179.016 361.033,
+                          -128.614 -179.016 361.033,
+                          -48.9627 -180.016 361.033,
+                          -43.1873 -179.016 361.072,
+                          -48.9627 -179.016 361.033,
+                          -43.1873 -180.016 361.072,
+                          -128.793 -180.008 361.044,
+                          -129.662 -179.72 361.203,
+                          -129.283 -179.748 311.444,
+                          -128.783 -178.882 311.448,
+                          -128.273 -179.016 310.04,
+                          -129.283 -179.748 311.444,
+                          -129.139 -178.868 361.206,
+                          -129.662 -179.72 361.203,
+                          -128.793 -180.008 361.044,
+                          -128.614 -179.016 361.033,
+                          -128.793 -180.008 361.044,
+                          -128.614 -180.016 361.033,
+                          -57.0616 114.992 566,
+                          -57.0616 94.4165 566,
+                          -137.9 114.992 566,
+                          -88.0955 91.2422 566,
+                          -118.738 85.3136 566,
+                          -137.9 114.992 566,
+                          -129.139 -178.868 361.206,
+                          -128.793 -180.008 361.044,
+                          -128.703 -179.012 361.045,
+                          -128.614 -179.016 361.033,
+                          -128.703 -179.012 361.045,
+                          -128.793 -180.008 361.044,
+                          15 180 315.06,
+                          -43.1873 180 361.072,
+                          15 180 360.773,
+                          15 179 360.773,
+                          15 180 360.773,
+                          -43.1873 180 361.072,
+                          15 179 315.06,
+                          15 180 315.06,
+                          15 180 360.773,
+                          15 179 360.773,
+                          15 179 315.06,
+                          15 180 360.773,
+                          -128.024 180 312.864,
+                          -48.9627 180 361.033,
+                          -43.1873 180 361.072,
+                          -43.1873 179 361.072,
+                          -43.1873 180 361.072,
+                          -48.9627 180 361.033,
+                          15 180 315.06,
+                          -128.024 180 312.864,
+                          -43.1873 180 361.072,
+                          -43.1873 179 361.072,
+                          15 179 360.773,
+                          -43.1873 180 361.072,
+                          -128.024 180 312.864,
+                          -128.614 180 361.033,
+                          -48.9627 180 361.033,
+                          -48.9627 179 361.033,
+                          -48.9627 180 361.033,
+                          -128.614 180 361.033,
+                          -43.1873 179 361.072,
+                          -48.9627 180 361.033,
+                          -48.9627 179 361.033,
+                          -128.024 180 310.04,
+                          -128.307 180 310.04,
+                          -128.614 180 361.033,
+                          -129.282 179.732 311.436,
+                          -128.614 180 361.033,
+                          -128.307 180 310.04,
+                          -128.024 180 312.864,
+                          -128.024 180 310.04,
+                          -128.614 180 361.033,
+                          -129.282 179.732 311.436,
+                          -129.584 179.749 361.178,
+                          -128.614 180 361.033,
+                          -128.614 179 361.033,
+                          -128.614 180 361.033,
+                          -129.584 179.749 361.178,
+                          -128.614 179 361.033,
+                          -48.9627 179 361.033,
+                          -128.614 180 361.033,
+                          -128.024 179 310.04,
+                          -128.307 180 310.04,
+                          -128.024 180 310.04,
+                          -128.782 178.866 311.439,
+                          -129.282 179.732 311.436,
+                          -128.307 180 310.04,
+                          -128.024 179 310.04,
+                          -128.273 179 310.04,
+                          -128.307 180 310.04,
+                          -128.782 178.866 311.439,
+                          -128.307 180 310.04,
+                          -128.273 179 310.04,
+                          -128.024 179 310.04,
+                          -128.024 180 310.04,
+                          -128.024 180 312.864,
+                          -128.024 179 312.864,
+                          -128.024 180 312.864,
+                          15 180 315.06,
+                          -128.024 179 312.864,
+                          -128.024 179 310.04,
+                          -128.024 180 312.864,
+                          15 179 315.06,
+                          -128.024 179 312.864,
+                          15 180 315.06,
+                          -129.108 178.87 361.183,
+                          -128.614 179 361.033,
+                          -129.584 179.749 361.178,
+                          -43.1873 -179.016 361.072,
+                          15 -179.016 315.06,
+                          -128.024 -179.016 312.881,
+                          -43.1873 -179.016 361.072,
+                          15 -179.016 360.773,
+                          15 -179.016 315.06,
+                          -128.273 -179.016 310.04,
+                          -128.024 -179.016 312.881,
+                          -128.005 -179.016 310.04,
+                          -128.614 -179.016 361.033,
+                          -128.024 -179.016 312.881,
+                          -128.273 -179.016 310.04,
+                          -48.9627 -179.016 361.033,
+                          -128.024 -179.016 312.881,
+                          -128.614 -179.016 361.033,
+                          -43.1873 -179.016 361.072,
+                          -128.024 -179.016 312.881,
+                          -48.9627 -179.016 361.033,
+                          -128.783 -178.882 311.448,
+                          -128.614 -179.016 361.033,
+                          -128.273 -179.016 310.04,
+                          -88.0955 91.2422 566,
+                          -137.9 114.992 566,
+                          -57.0616 94.4165 566,
+                          -135.465 71.767 566,
+                          -137.9 114.992 566,
+                          -128.634 80.4326 566,
+                          -129.139 -178.868 361.206,
+                          -128.703 -179.012 361.045,
+                          -128.783 -178.882 311.448,
+                          -128.783 -178.882 311.448,
+                          -128.703 -179.012 361.045,
+                          -128.614 -179.016 361.033,
+                          -128.024 179 312.864,
+                          -48.9627 179 361.033,
+                          -128.614 179 361.033,
+                          15 179 315.06,
+                          -48.9627 179 361.033,
+                          -128.024 179 312.864,
+                          -43.1873 179 361.072,
+                          -48.9627 179 361.033,
+                          15 179 315.06,
+                          -128.024 179 310.04,
+                          -128.614 179 361.033,
+                          -128.273 179 310.04,
+                          -129.108 178.87 361.183,
+                          -128.273 179 310.04,
+                          -128.614 179 361.033,
+                          -128.024 179 312.864,
+                          -128.614 179 361.033,
+                          -128.024 179 310.04,
+                          -128.782 178.866 311.439,
+                          -128.273 179 310.04,
+                          -129.108 178.87 361.183,
+                          -43.1873 179 361.072,
+                          15 179 315.06,
+                          15 179 360.773,
+                          -137.9 -61.021 566,
+                          -137.9 -115.008 566,
+                          -138.679 -115.008 565.677,
+                          -135.465 -71.783 566,
+                          -137.9 -115.008 566,
+                          -137.9 -61.021 566,
+                          -128.634 -80.4486 566,
+                          -137.9 -115.008 566,
+                          -135.465 -71.783 566,
+                          -118.738 -85.3297 566,
+                          -137.9 -115.008 566,
+                          -128.634 -80.4486 566,
+                          -57.0616 -115.008 566,
+                          -137.9 -115.008 566,
+                          -118.738 -85.3297 566,
+                          -137.9 114.992 566,
+                          -138.679 -115.008 565.677,
+                          -138.679 114.992 565.677,
+                          -137.9 61.0049 566,
+                          -138.679 -115.008 565.677,
+                          -137.9 114.992 566,
+                          -137.9 61.0049 566,
+                          -137.9 -61.021 566,
+                          -138.679 -115.008 565.677,
+                          -135.465 71.767 566,
+                          -137.9 61.0049 566,
+                          -137.9 114.992 566,
+                          -128.634 80.4326 566,
+                          -137.9 114.992 566,
+                          -118.738 85.3136 566 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.39 0 0
+    }
+    Separator {
+        Normal {
+            vector      [ 0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.172436 0.985021 1.64021e-16,
+                          2.08251e-15 1 2.22045e-16,
+                          -0.382411 0.923222 0.0377266,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.615907 0.786231 0.0499989,
+                          -0.382411 0.923222 0.0377266,
+                          -0.706142 0.706142 0.052231,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.408683 0.912095 0.0325592,
+                          -0.172436 0.985021 1.64021e-16,
+                          -0.382411 0.923222 0.0377266,
+                          -0.615907 0.786231 0.0499989,
+                          -0.408683 0.912095 0.0325592,
+                          -0.382411 0.923222 0.0377266,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.786231 0.615907 0.0499989,
+                          -0.706142 0.706142 0.052231,
+                          -0.923222 0.382411 0.0377266,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.786231 0.615907 0.0499989,
+                          -0.615907 0.786231 0.0499989,
+                          -0.706142 0.706142 0.052231,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.912095 0.408683 0.0325592,
+                          -0.923222 0.382411 0.0377266,
+                          -1 3.67382e-16 3.17207e-17,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.912095 0.408683 0.0325592,
+                          -0.786231 0.615907 0.0499989,
+                          -0.923222 0.382411 0.0377266,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.985021 0.172436 6.9534e-17,
+                          -0.912095 0.408683 0.0325592,
+                          -1 3.67382e-16 3.17207e-17,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.985021 -0.172436 -4.01739e-17,
+                          -1 1.22461e-16 0,
+                          -0.923222 -0.382411 0.0377266,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.786231 -0.615907 0.0499989,
+                          -0.923222 -0.382411 0.0377266,
+                          -0.706142 -0.706142 0.052231,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.912095 -0.408683 0.0325592,
+                          -0.985021 -0.172436 -4.01739e-17,
+                          -0.923222 -0.382411 0.0377266,
+                          -0.786231 -0.615907 0.0499989,
+                          -0.912095 -0.408683 0.0325592,
+                          -0.923222 -0.382411 0.0377266,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.615907 -0.786231 0.0499989,
+                          -0.706142 -0.706142 0.052231,
+                          -0.382411 -0.923222 0.0377266,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.615907 -0.786231 0.0499989,
+                          -0.786231 -0.615907 0.0499989,
+                          -0.706142 -0.706142 0.052231,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.408683 -0.912095 0.0325592,
+                          -0.382411 -0.923222 0.0377266,
+                          -6.2778e-16 -1 -2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.408683 -0.912095 0.0325592,
+                          -0.615907 -0.786231 0.0499989,
+                          -0.382411 -0.923222 0.0377266,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -0.172436 -0.985021 -2.07779e-16,
+                          -0.408683 -0.912095 0.0325592,
+                          -6.2778e-16 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          0.172436 -0.985021 -4.68683e-16,
+                          -1.83691e-16 -1 -4.7581e-16,
+                          0.382411 -0.923222 0.0377266,
+                          0.615907 -0.786231 0.0499989,
+                          0.382411 -0.923222 0.0377266,
+                          0.706142 -0.706142 0.052231,
+                          0.408683 -0.912095 0.0325592,
+                          0.172436 -0.985021 -4.68683e-16,
+                          0.382411 -0.923222 0.0377266,
+                          0.615907 -0.786231 0.0499989,
+                          0.408683 -0.912095 0.0325592,
+                          0.382411 -0.923222 0.0377266,
+                          0.786231 -0.615907 0.0499989,
+                          0.706142 -0.706142 0.052231,
+                          0.923222 -0.382411 0.0377266,
+                          0.786231 -0.615907 0.0499989,
+                          0.615907 -0.786231 0.0499989,
+                          0.706142 -0.706142 0.052231,
+                          0.912095 -0.408683 0.0325592,
+                          0.923222 -0.382411 0.0377266,
+                          1 -2.02128e-15 0,
+                          0.912095 -0.408683 0.0325592,
+                          0.786231 -0.615907 0.0499989,
+                          0.923222 -0.382411 0.0377266,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          0.985021 -0.172436 -3.8102e-17,
+                          0.912095 -0.408683 0.0325592,
+                          1 -2.02128e-15 0,
+                          0.985021 0.172436 -2.11676e-16,
+                          1 -2.44921e-16 -2.53765e-16,
+                          0.923222 0.382411 0.0377266,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          0.786231 0.615907 0.0499989,
+                          0.923222 0.382411 0.0377266,
+                          0.706142 0.706142 0.052231,
+                          0.912095 0.408683 0.0325592,
+                          0.985021 0.172436 -2.11676e-16,
+                          0.923222 0.382411 0.0377266,
+                          0.786231 0.615907 0.0499989,
+                          0.912095 0.408683 0.0325592,
+                          0.923222 0.382411 0.0377266,
+                          0.615907 0.786231 0.0499989,
+                          0.706142 0.706142 0.052231,
+                          0.382411 0.923222 0.0377266,
+                          0.615907 0.786231 0.0499989,
+                          0.786231 0.615907 0.0499989,
+                          0.706142 0.706142 0.052231,
+                          0.408683 0.912095 0.0325592,
+                          0.382411 0.923222 0.0377266,
+                          2.08251e-15 1 2.22045e-16,
+                          0.408683 0.912095 0.0325592,
+                          0.615907 0.786231 0.0499989,
+                          0.382411 0.923222 0.0377266,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          0.172436 0.985021 2.40598e-16,
+                          0.408683 0.912095 0.0325592,
+                          2.08251e-15 1 2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.612718 0.789603 0.033227,
+                          -0.706578 0.706578 0.0386804,
+                          -0.707107 0.707107 -6.72897e-17,
+                          -0.612718 0.789603 0.033227,
+                          -0.707107 0.707107 -6.72897e-17,
+                          -0.549061 0.835782 1.14152e-17,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.549061 0.835782 2.55247e-16,
+                          0.707107 0.707107 2.46729e-16,
+                          0.706578 0.706578 0.0386804,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.675721 0.735452 0.0501094,
+                          0.706578 0.706578 0.0386804,
+                          0.706142 0.706142 0.052231,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.612718 0.789603 0.033227,
+                          0.706578 0.706578 0.0386804,
+                          0.675721 0.735452 0.0501094,
+                          0.549061 0.835782 2.55247e-16,
+                          0.706578 0.706578 0.0386804,
+                          0.612718 0.789603 0.033227,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.735452 0.675721 0.0501094,
+                          0.706142 0.706142 0.052231,
+                          0.706578 0.706578 0.0386804,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.675721 0.735452 0.0501094,
+                          0.706142 0.706142 0.052231,
+                          0.735452 0.675721 0.0501094,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.789603 0.612718 0.033227,
+                          0.706578 0.706578 0.0386804,
+                          0.707107 0.707107 -2.24299e-17,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.735452 0.675721 0.0501094,
+                          0.706578 0.706578 0.0386804,
+                          0.789603 0.612718 0.033227,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.789603 0.612718 0.033227,
+                          0.707107 0.707107 -2.24299e-17,
+                          0.835782 0.549061 -9.01765e-17,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.835782 -0.549061 -1.21322e-16,
+                          0.707107 -0.707107 -1.56245e-16,
+                          0.706578 -0.706578 0.0386804,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.735452 -0.675721 0.0501094,
+                          0.706578 -0.706578 0.0386804,
+                          0.706142 -0.706142 0.052231,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.789603 -0.612718 0.033227,
+                          0.706578 -0.706578 0.0386804,
+                          0.735452 -0.675721 0.0501094,
+                          0.835782 -0.549061 -1.21322e-16,
+                          0.706578 -0.706578 0.0386804,
+                          0.789603 -0.612718 0.033227,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.675721 -0.735452 0.0501094,
+                          0.706142 -0.706142 0.052231,
+                          0.706578 -0.706578 0.0386804,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.735452 -0.675721 0.0501094,
+                          0.706142 -0.706142 0.052231,
+                          0.675721 -0.735452 0.0501094,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.612718 -0.789603 0.033227,
+                          0.706578 -0.706578 0.0386804,
+                          0.707107 -0.707107 -3.36448e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.675721 -0.735452 0.0501094,
+                          0.706578 -0.706578 0.0386804,
+                          0.612718 -0.789603 0.033227,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          0.612718 -0.789603 0.033227,
+                          0.707107 -0.707107 -3.36448e-16,
+                          0.549061 -0.835782 -3.97673e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.549061 -0.835782 -1.50748e-16,
+                          -0.707107 -0.707107 -1.12149e-16,
+                          -0.706578 -0.706578 0.0386804,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.675721 -0.735452 0.0501094,
+                          -0.706578 -0.706578 0.0386804,
+                          -0.706142 -0.706142 0.052231,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.612718 -0.789603 0.033227,
+                          -0.706578 -0.706578 0.0386804,
+                          -0.675721 -0.735452 0.0501094,
+                          -0.549061 -0.835782 -1.50748e-16,
+                          -0.706578 -0.706578 0.0386804,
+                          -0.612718 -0.789603 0.033227,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.735452 -0.675721 0.0501094,
+                          -0.706142 -0.706142 0.052231,
+                          -0.706578 -0.706578 0.0386804,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.675721 -0.735452 0.0501094,
+                          -0.706142 -0.706142 0.052231,
+                          -0.735452 -0.675721 0.0501094,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.789603 -0.612718 0.033227,
+                          -0.706578 -0.706578 0.0386804,
+                          -0.707107 -0.707107 -1.64741e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.735452 -0.675721 0.0501094,
+                          -0.706578 -0.706578 0.0386804,
+                          -0.789603 -0.612718 0.033227,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.789603 -0.612718 0.033227,
+                          -0.707107 -0.707107 -1.64741e-16,
+                          -0.835782 -0.549061 -1.27919e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.835782 0.549061 1.48428e-16,
+                          -0.707107 0.707107 1.79439e-16,
+                          -0.706578 0.706578 0.0386804,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.735452 0.675721 0.0501094,
+                          -0.706578 0.706578 0.0386804,
+                          -0.706142 0.706142 0.052231,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.789603 0.612718 0.033227,
+                          -0.706578 0.706578 0.0386804,
+                          -0.735452 0.675721 0.0501094,
+                          -0.835782 0.549061 1.48428e-16,
+                          -0.706578 0.706578 0.0386804,
+                          -0.789603 0.612718 0.033227,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.675721 0.735452 0.0501094,
+                          -0.706142 0.706142 0.052231,
+                          -0.706578 0.706578 0.0386804,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.735452 0.675721 0.0501094,
+                          -0.706142 0.706142 0.052231,
+                          -0.675721 0.735452 0.0501094,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.675721 0.735452 0.0501094,
+                          -0.706578 0.706578 0.0386804,
+                          -0.612718 0.789603 0.033227,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          0.77663 -0.628752 -0.0389601,
+                          0.706543 -0.706615 -0.0386279,
+                          0.707102 -0.70711 -0.00144384,
+                          0.834264 -0.551364 -0.00112887,
+                          0.77663 -0.628752 -0.0389601,
+                          0.707102 -0.70711 -0.00144384,
+                          0.776497 0.628912 -0.0390128,
+                          0.707102 0.70711 -0.00144384,
+                          0.706542 0.706613 -0.0386815,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          0.776497 0.628912 -0.0390128,
+                          0.834264 0.551364 -0.00112887,
+                          0.707102 0.70711 -0.00144384,
+                          0.706066 0.706217 -0.052231,
+                          0.706542 0.706613 -0.0386815,
+                          0.706142 0.706142 -0.052231,
+                          0.776497 0.628912 -0.0390128,
+                          0.706542 0.706613 -0.0386815,
+                          0.706066 0.706217 -0.052231,
+                          0.706066 0.706217 -0.052231,
+                          0.706142 0.706142 -0.052231,
+                          0.706615 0.706543 -0.0386279,
+                          0.628752 0.77663 -0.0389601,
+                          0.706615 0.706543 -0.0386279,
+                          0.70711 0.707102 -0.00144384,
+                          0.706066 0.706217 -0.052231,
+                          0.706615 0.706543 -0.0386279,
+                          0.628752 0.77663 -0.0389601,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          0.551364 0.834264 -0.00112887,
+                          0.628752 0.77663 -0.0389601,
+                          0.70711 0.707102 -0.00144384,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          -0.628912 0.776497 -0.0390128,
+                          -0.70711 0.707102 -0.00144384,
+                          -0.706613 0.706542 -0.0386815,
+                          -0.628912 0.776497 -0.0390128,
+                          -0.551364 0.834264 -0.00112887,
+                          -0.70711 0.707102 -0.00144384,
+                          -0.706217 0.706066 -0.052231,
+                          -0.706613 0.706542 -0.0386815,
+                          -0.706142 0.706142 -0.052231,
+                          -0.628912 0.776497 -0.0390128,
+                          -0.706613 0.706542 -0.0386815,
+                          -0.706217 0.706066 -0.052231,
+                          -0.706217 0.706066 -0.052231,
+                          -0.706142 0.706142 -0.052231,
+                          -0.706543 0.706615 -0.0386279,
+                          -0.77663 0.628752 -0.0389601,
+                          -0.706543 0.706615 -0.0386279,
+                          -0.707102 0.70711 -0.00144384,
+                          -0.706217 0.706066 -0.052231,
+                          -0.706543 0.706615 -0.0386279,
+                          -0.77663 0.628752 -0.0389601,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -0.834264 0.551364 -0.00112887,
+                          -0.77663 0.628752 -0.0389601,
+                          -0.707102 0.70711 -0.00144384,
+                          -0.776497 -0.628912 -0.0390128,
+                          -0.707102 -0.70711 -0.00144384,
+                          -0.706542 -0.706613 -0.0386815,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -0.776497 -0.628912 -0.0390128,
+                          -0.834264 -0.551364 -0.00112887,
+                          -0.707102 -0.70711 -0.00144384,
+                          -0.706066 -0.706217 -0.052231,
+                          -0.706542 -0.706613 -0.0386815,
+                          -0.706142 -0.706142 -0.052231,
+                          -0.776497 -0.628912 -0.0390128,
+                          -0.706542 -0.706613 -0.0386815,
+                          -0.706066 -0.706217 -0.052231,
+                          -0.706066 -0.706217 -0.052231,
+                          -0.706142 -0.706142 -0.052231,
+                          -0.706615 -0.706543 -0.0386279,
+                          -0.628752 -0.77663 -0.0389601,
+                          -0.706615 -0.706543 -0.0386279,
+                          -0.70711 -0.707102 -0.00144384,
+                          -0.706066 -0.706217 -0.052231,
+                          -0.706615 -0.706543 -0.0386279,
+                          -0.628752 -0.77663 -0.0389601,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -0.551364 -0.834264 -0.00112887,
+                          -0.628752 -0.77663 -0.0389601,
+                          -0.70711 -0.707102 -0.00144384,
+                          0.628912 -0.776497 -0.0390128,
+                          0.70711 -0.707102 -0.00144384,
+                          0.706613 -0.706542 -0.0386815,
+                          0.551364 -0.834264 -0.00112887,
+                          0.70711 -0.707102 -0.00144384,
+                          0.628912 -0.776497 -0.0390128,
+                          0.706217 -0.706066 -0.052231,
+                          0.706613 -0.706542 -0.0386815,
+                          0.706142 -0.706142 -0.052231,
+                          0.628912 -0.776497 -0.0390128,
+                          0.706613 -0.706542 -0.0386815,
+                          0.706217 -0.706066 -0.052231,
+                          0.706217 -0.706066 -0.052231,
+                          0.706142 -0.706142 -0.052231,
+                          0.706543 -0.706615 -0.0386279,
+                          0.706217 -0.706066 -0.052231,
+                          0.706543 -0.706615 -0.0386279,
+                          0.77663 -0.628752 -0.0389601,
+                          -0.362716 0.9319 9.18674e-17,
+                          -0.172436 0.985021 1.64021e-16,
+                          -0.408683 0.912095 0.0325592,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          -0.511542 0.85862 0.0331191,
+                          -0.408683 0.912095 0.0325592,
+                          -0.615907 0.786231 0.0499989,
+                          -0.511542 0.85862 0.0331191,
+                          -0.362716 0.9319 9.18674e-17,
+                          -0.408683 0.912095 0.0325592,
+                          -0.645522 0.762097 0.0500912,
+                          -0.615907 0.786231 0.0499989,
+                          -0.786231 0.615907 0.0499989,
+                          -0.645522 0.762097 0.0500912,
+                          -0.511542 0.85862 0.0331191,
+                          -0.615907 0.786231 0.0499989,
+                          -0.762097 0.645522 0.0500912,
+                          -0.786231 0.615907 0.0499989,
+                          -0.912095 0.408683 0.0325592,
+                          -0.762097 0.645522 0.0500912,
+                          -0.645522 0.762097 0.0500912,
+                          -0.786231 0.615907 0.0499989,
+                          -0.85862 0.511542 0.0331191,
+                          -0.912095 0.408683 0.0325592,
+                          -0.985021 0.172436 6.9534e-17,
+                          -0.85862 0.511542 0.0331191,
+                          -0.762097 0.645522 0.0500912,
+                          -0.912095 0.408683 0.0325592,
+                          -0.9319 0.362716 1.101e-16,
+                          -0.85862 0.511542 0.0331191,
+                          -0.985021 0.172436 6.9534e-17,
+                          -0.549061 0.835782 1.14152e-17,
+                          -0.362716 0.9319 9.18674e-17,
+                          -0.511542 0.85862 0.0331191,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          -0.612718 0.789603 0.033227,
+                          -0.511542 0.85862 0.0331191,
+                          -0.645522 0.762097 0.0500912,
+                          -0.612718 0.789603 0.033227,
+                          -0.549061 0.835782 1.14152e-17,
+                          -0.511542 0.85862 0.0331191,
+                          -0.675721 0.735452 0.0501094,
+                          -0.645522 0.762097 0.0500912,
+                          -0.762097 0.645522 0.0500912,
+                          -0.675721 0.735452 0.0501094,
+                          -0.612718 0.789603 0.033227,
+                          -0.645522 0.762097 0.0500912,
+                          -0.735452 0.675721 0.0501094,
+                          -0.762097 0.645522 0.0500912,
+                          -0.85862 0.511542 0.0331191,
+                          -0.735452 0.675721 0.0501094,
+                          -0.675721 0.735452 0.0501094,
+                          -0.762097 0.645522 0.0500912,
+                          -0.789603 0.612718 0.033227,
+                          -0.85862 0.511542 0.0331191,
+                          -0.9319 0.362716 1.101e-16,
+                          -0.789603 0.612718 0.033227,
+                          -0.735452 0.675721 0.0501094,
+                          -0.85862 0.511542 0.0331191,
+                          -0.835782 0.549061 1.48428e-16,
+                          -0.789603 0.612718 0.033227,
+                          -0.9319 0.362716 1.101e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          -0.85862 -0.511542 0.0331191,
+                          -0.835782 -0.549061 -1.27919e-16,
+                          -0.9319 -0.362716 -8.45051e-17,
+                          -0.789603 -0.612718 0.033227,
+                          -0.835782 -0.549061 -1.27919e-16,
+                          -0.85862 -0.511542 0.0331191,
+                          -0.912095 -0.408683 0.0325592,
+                          -0.9319 -0.362716 -8.45051e-17,
+                          -0.985021 -0.172436 -4.01739e-17,
+                          -0.85862 -0.511542 0.0331191,
+                          -0.9319 -0.362716 -8.45051e-17,
+                          -0.912095 -0.408683 0.0325592,
+                          -0.85862 -0.511542 0.0331191,
+                          -0.912095 -0.408683 0.0325592,
+                          -0.786231 -0.615907 0.0499989,
+                          -0.762097 -0.645522 0.0500912,
+                          -0.786231 -0.615907 0.0499989,
+                          -0.615907 -0.786231 0.0499989,
+                          -0.762097 -0.645522 0.0500912,
+                          -0.85862 -0.511542 0.0331191,
+                          -0.786231 -0.615907 0.0499989,
+                          -0.645522 -0.762097 0.0500912,
+                          -0.615907 -0.786231 0.0499989,
+                          -0.408683 -0.912095 0.0325592,
+                          -0.645522 -0.762097 0.0500912,
+                          -0.762097 -0.645522 0.0500912,
+                          -0.615907 -0.786231 0.0499989,
+                          -0.511542 -0.85862 0.0331191,
+                          -0.408683 -0.912095 0.0325592,
+                          -0.172436 -0.985021 -2.07779e-16,
+                          -0.511542 -0.85862 0.0331191,
+                          -0.645522 -0.762097 0.0500912,
+                          -0.408683 -0.912095 0.0325592,
+                          -0.362716 -0.9319 -1.83912e-16,
+                          -0.511542 -0.85862 0.0331191,
+                          -0.172436 -0.985021 -2.07779e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -0.789603 -0.612718 0.033227,
+                          -0.85862 -0.511542 0.0331191,
+                          -0.762097 -0.645522 0.0500912,
+                          -0.735452 -0.675721 0.0501094,
+                          -0.762097 -0.645522 0.0500912,
+                          -0.645522 -0.762097 0.0500912,
+                          -0.735452 -0.675721 0.0501094,
+                          -0.789603 -0.612718 0.033227,
+                          -0.762097 -0.645522 0.0500912,
+                          -0.675721 -0.735452 0.0501094,
+                          -0.645522 -0.762097 0.0500912,
+                          -0.511542 -0.85862 0.0331191,
+                          -0.675721 -0.735452 0.0501094,
+                          -0.735452 -0.675721 0.0501094,
+                          -0.645522 -0.762097 0.0500912,
+                          -0.612718 -0.789603 0.033227,
+                          -0.511542 -0.85862 0.0331191,
+                          -0.362716 -0.9319 -1.83912e-16,
+                          -0.612718 -0.789603 0.033227,
+                          -0.675721 -0.735452 0.0501094,
+                          -0.511542 -0.85862 0.0331191,
+                          -0.549061 -0.835782 -1.50748e-16,
+                          -0.612718 -0.789603 0.033227,
+                          -0.362716 -0.9319 -1.83912e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          0.511542 -0.85862 0.0331191,
+                          0.549061 -0.835782 -3.97673e-16,
+                          0.362716 -0.9319 -4.43407e-16,
+                          0.612718 -0.789603 0.033227,
+                          0.549061 -0.835782 -3.97673e-16,
+                          0.511542 -0.85862 0.0331191,
+                          0.408683 -0.912095 0.0325592,
+                          0.362716 -0.9319 -4.43407e-16,
+                          0.172436 -0.985021 -4.68683e-16,
+                          0.511542 -0.85862 0.0331191,
+                          0.362716 -0.9319 -4.43407e-16,
+                          0.408683 -0.912095 0.0325592,
+                          0.511542 -0.85862 0.0331191,
+                          0.408683 -0.912095 0.0325592,
+                          0.615907 -0.786231 0.0499989,
+                          0.645522 -0.762097 0.0500912,
+                          0.615907 -0.786231 0.0499989,
+                          0.786231 -0.615907 0.0499989,
+                          0.645522 -0.762097 0.0500912,
+                          0.511542 -0.85862 0.0331191,
+                          0.615907 -0.786231 0.0499989,
+                          0.762097 -0.645522 0.0500912,
+                          0.786231 -0.615907 0.0499989,
+                          0.912095 -0.408683 0.0325592,
+                          0.762097 -0.645522 0.0500912,
+                          0.645522 -0.762097 0.0500912,
+                          0.786231 -0.615907 0.0499989,
+                          0.85862 -0.511542 0.0331191,
+                          0.912095 -0.408683 0.0325592,
+                          0.985021 -0.172436 -3.8102e-17,
+                          0.85862 -0.511542 0.0331191,
+                          0.762097 -0.645522 0.0500912,
+                          0.912095 -0.408683 0.0325592,
+                          0.9319 -0.362716 -8.01469e-17,
+                          0.85862 -0.511542 0.0331191,
+                          0.985021 -0.172436 -3.8102e-17,
+                          0.612718 -0.789603 0.033227,
+                          0.511542 -0.85862 0.0331191,
+                          0.645522 -0.762097 0.0500912,
+                          0.675721 -0.735452 0.0501094,
+                          0.645522 -0.762097 0.0500912,
+                          0.762097 -0.645522 0.0500912,
+                          0.675721 -0.735452 0.0501094,
+                          0.612718 -0.789603 0.033227,
+                          0.645522 -0.762097 0.0500912,
+                          0.735452 -0.675721 0.0501094,
+                          0.762097 -0.645522 0.0500912,
+                          0.85862 -0.511542 0.0331191,
+                          0.735452 -0.675721 0.0501094,
+                          0.675721 -0.735452 0.0501094,
+                          0.762097 -0.645522 0.0500912,
+                          0.789603 -0.612718 0.033227,
+                          0.85862 -0.511542 0.0331191,
+                          0.9319 -0.362716 -8.01469e-17,
+                          0.789603 -0.612718 0.033227,
+                          0.735452 -0.675721 0.0501094,
+                          0.85862 -0.511542 0.0331191,
+                          0.835782 -0.549061 -1.21322e-16,
+                          0.789603 -0.612718 0.033227,
+                          0.9319 -0.362716 -8.01469e-17,
+                          0.85862 0.511542 0.0331191,
+                          0.835782 0.549061 -9.01765e-17,
+                          0.9319 0.362716 -1.55945e-16,
+                          0.789603 0.612718 0.033227,
+                          0.835782 0.549061 -9.01765e-17,
+                          0.85862 0.511542 0.0331191,
+                          0.912095 0.408683 0.0325592,
+                          0.9319 0.362716 -1.55945e-16,
+                          0.985021 0.172436 -2.11676e-16,
+                          0.85862 0.511542 0.0331191,
+                          0.9319 0.362716 -1.55945e-16,
+                          0.912095 0.408683 0.0325592,
+                          0.85862 0.511542 0.0331191,
+                          0.912095 0.408683 0.0325592,
+                          0.786231 0.615907 0.0499989,
+                          0.762097 0.645522 0.0500912,
+                          0.786231 0.615907 0.0499989,
+                          0.615907 0.786231 0.0499989,
+                          0.762097 0.645522 0.0500912,
+                          0.85862 0.511542 0.0331191,
+                          0.786231 0.615907 0.0499989,
+                          0.645522 0.762097 0.0500912,
+                          0.615907 0.786231 0.0499989,
+                          0.408683 0.912095 0.0325592,
+                          0.645522 0.762097 0.0500912,
+                          0.762097 0.645522 0.0500912,
+                          0.615907 0.786231 0.0499989,
+                          0.511542 0.85862 0.0331191,
+                          0.408683 0.912095 0.0325592,
+                          0.172436 0.985021 2.40598e-16,
+                          0.511542 0.85862 0.0331191,
+                          0.645522 0.762097 0.0500912,
+                          0.408683 0.912095 0.0325592,
+                          0.362716 0.9319 2.52946e-16,
+                          0.511542 0.85862 0.0331191,
+                          0.172436 0.985021 2.40598e-16,
+                          0.789603 0.612718 0.033227,
+                          0.85862 0.511542 0.0331191,
+                          0.762097 0.645522 0.0500912,
+                          0.735452 0.675721 0.0501094,
+                          0.762097 0.645522 0.0500912,
+                          0.645522 0.762097 0.0500912,
+                          0.735452 0.675721 0.0501094,
+                          0.789603 0.612718 0.033227,
+                          0.762097 0.645522 0.0500912,
+                          0.675721 0.735452 0.0501094,
+                          0.645522 0.762097 0.0500912,
+                          0.511542 0.85862 0.0331191,
+                          0.675721 0.735452 0.0501094,
+                          0.735452 0.675721 0.0501094,
+                          0.645522 0.762097 0.0500912,
+                          0.612718 0.789603 0.033227,
+                          0.511542 0.85862 0.0331191,
+                          0.362716 0.9319 2.52946e-16,
+                          0.612718 0.789603 0.033227,
+                          0.675721 0.735452 0.0501094,
+                          0.511542 0.85862 0.0331191,
+                          0.549061 0.835782 2.55247e-16,
+                          0.612718 0.789603 0.033227,
+                          0.362716 0.9319 2.52946e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          0.177205 -0.984174 -0.000358715,
+                          0.383918 -0.922595 -0.0377441,
+                          0.00288561 -0.999996 -3.89942e-06,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.177205 -0.984174 -0.000358715,
+                          -0.00288561 -0.999996 -3.89942e-06,
+                          -0.383188 -0.922901 -0.0376879,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.464188 -0.884903 -0.0384256,
+                          -0.383188 -0.922901 -0.0376879,
+                          -0.705862 -0.706421 -0.052231,
+                          -0.177205 -0.984174 -0.000358715,
+                          -0.383188 -0.922901 -0.0376879,
+                          -0.464188 -0.884903 -0.0384256,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.884615 -0.464731 -0.0384798,
+                          -0.705862 -0.706421 -0.052231,
+                          -0.922595 -0.383918 -0.0377441,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.705926 -0.706357 -0.052231,
+                          -0.464188 -0.884903 -0.0384256,
+                          -0.705862 -0.706421 -0.052231,
+                          -0.884615 -0.464731 -0.0384798,
+                          -0.705926 -0.706357 -0.052231,
+                          -0.705862 -0.706421 -0.052231,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.984174 -0.177205 -0.000358715,
+                          -0.922595 -0.383918 -0.0377441,
+                          -0.999996 -0.00288561 -3.89942e-06,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.884615 -0.464731 -0.0384798,
+                          -0.922595 -0.383918 -0.0377441,
+                          -0.984174 -0.177205 -0.000358715,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.984174 0.177205 -0.000358715,
+                          -0.999996 0.00288561 -3.89942e-06,
+                          -0.922901 0.383188 -0.0376879,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.884903 0.464188 -0.0384256,
+                          -0.922901 0.383188 -0.0376879,
+                          -0.706421 0.705862 -0.052231,
+                          -0.984174 0.177205 -0.000358715,
+                          -0.922901 0.383188 -0.0376879,
+                          -0.884903 0.464188 -0.0384256,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.464731 0.884615 -0.0384798,
+                          -0.706421 0.705862 -0.052231,
+                          -0.383918 0.922595 -0.0377441,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.706357 0.705926 -0.052231,
+                          -0.884903 0.464188 -0.0384256,
+                          -0.706421 0.705862 -0.052231,
+                          -0.464731 0.884615 -0.0384798,
+                          -0.706357 0.705926 -0.052231,
+                          -0.706421 0.705862 -0.052231,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.177205 0.984174 -0.000358715,
+                          -0.383918 0.922595 -0.0377441,
+                          -0.00288561 0.999996 -3.89942e-06,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.464731 0.884615 -0.0384798,
+                          -0.383918 0.922595 -0.0377441,
+                          -0.177205 0.984174 -0.000358715,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          0.177205 0.984174 -0.000358715,
+                          0.00288561 0.999996 -3.89942e-06,
+                          0.383188 0.922901 -0.0376879,
+                          0.464188 0.884903 -0.0384256,
+                          0.383188 0.922901 -0.0376879,
+                          0.705862 0.706421 -0.052231,
+                          0.177205 0.984174 -0.000358715,
+                          0.383188 0.922901 -0.0376879,
+                          0.464188 0.884903 -0.0384256,
+                          0.884615 0.464731 -0.0384798,
+                          0.705862 0.706421 -0.052231,
+                          0.922595 0.383918 -0.0377441,
+                          0.705926 0.706357 -0.052231,
+                          0.464188 0.884903 -0.0384256,
+                          0.705862 0.706421 -0.052231,
+                          0.884615 0.464731 -0.0384798,
+                          0.705926 0.706357 -0.052231,
+                          0.705862 0.706421 -0.052231,
+                          0.984174 0.177205 -0.000358715,
+                          0.922595 0.383918 -0.0377441,
+                          0.999996 0.00288561 -3.89942e-06,
+                          0.884615 0.464731 -0.0384798,
+                          0.922595 0.383918 -0.0377441,
+                          0.984174 0.177205 -0.000358715,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          0.984174 -0.177205 -0.000358715,
+                          0.999996 -0.00288561 -3.89942e-06,
+                          0.922901 -0.383188 -0.0376879,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          0.884903 -0.464188 -0.0384256,
+                          0.922901 -0.383188 -0.0376879,
+                          0.706421 -0.705862 -0.052231,
+                          0.984174 -0.177205 -0.000358715,
+                          0.922901 -0.383188 -0.0376879,
+                          0.884903 -0.464188 -0.0384256,
+                          0.464731 -0.884615 -0.0384798,
+                          0.706421 -0.705862 -0.052231,
+                          0.383918 -0.922595 -0.0377441,
+                          0.706357 -0.705926 -0.052231,
+                          0.884903 -0.464188 -0.0384256,
+                          0.706421 -0.705862 -0.052231,
+                          0.464731 -0.884615 -0.0384798,
+                          0.706357 -0.705926 -0.052231,
+                          0.706421 -0.705862 -0.052231,
+                          0.177205 -0.984174 -0.000358715,
+                          0.464731 -0.884615 -0.0384798,
+                          0.383918 -0.922595 -0.0377441,
+                          0.834264 -0.551364 -0.00112887,
+                          0.836282 -0.546919 -0.0388734,
+                          0.77663 -0.628752 -0.0389601,
+                          0.706289 -0.705994 -0.052231,
+                          0.77663 -0.628752 -0.0389601,
+                          0.836282 -0.546919 -0.0388734,
+                          0.706289 -0.705994 -0.052231,
+                          0.706217 -0.706066 -0.052231,
+                          0.77663 -0.628752 -0.0389601,
+                          0.930174 -0.367118 -0.000728904,
+                          0.884903 -0.464188 -0.0384256,
+                          0.836282 -0.546919 -0.0388734,
+                          0.706357 -0.705926 -0.052231,
+                          0.836282 -0.546919 -0.0388734,
+                          0.884903 -0.464188 -0.0384256,
+                          0.834264 -0.551364 -0.00112887,
+                          0.930174 -0.367118 -0.000728904,
+                          0.836282 -0.546919 -0.0388734,
+                          0.706357 -0.705926 -0.052231,
+                          0.706289 -0.705994 -0.052231,
+                          0.836282 -0.546919 -0.0388734,
+                          0.930174 -0.367118 -0.000728904,
+                          0.984174 -0.177205 -0.000358715,
+                          0.884903 -0.464188 -0.0384256,
+                          0.628912 -0.776497 -0.0390128,
+                          0.706217 -0.706066 -0.052231,
+                          0.706289 -0.705994 -0.052231,
+                          0.547267 -0.836052 -0.0389264,
+                          0.706289 -0.705994 -0.052231,
+                          0.706357 -0.705926 -0.052231,
+                          0.547267 -0.836052 -0.0389264,
+                          0.628912 -0.776497 -0.0390128,
+                          0.706289 -0.705994 -0.052231,
+                          0.464731 -0.884615 -0.0384798,
+                          0.547267 -0.836052 -0.0389264,
+                          0.706357 -0.705926 -0.052231,
+                          0.551364 -0.834264 -0.00112887,
+                          0.628912 -0.776497 -0.0390128,
+                          0.547267 -0.836052 -0.0389264,
+                          0.367118 -0.930174 -0.000728904,
+                          0.547267 -0.836052 -0.0389264,
+                          0.464731 -0.884615 -0.0384798,
+                          0.367118 -0.930174 -0.000728904,
+                          0.551364 -0.834264 -0.00112887,
+                          0.547267 -0.836052 -0.0389264,
+                          0.177205 -0.984174 -0.000358715,
+                          0.367118 -0.930174 -0.000728904,
+                          0.464731 -0.884615 -0.0384798,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          -6.12303e-17 -1 -2.22045e-16,
+                          0.884615 0.464731 -0.0384798,
+                          0.984174 0.177205 -0.000358715,
+                          0.930174 0.367118 -0.000728904,
+                          0.836052 0.547267 -0.0389264,
+                          0.930174 0.367118 -0.000728904,
+                          0.834264 0.551364 -0.00112887,
+                          0.884615 0.464731 -0.0384798,
+                          0.930174 0.367118 -0.000728904,
+                          0.836052 0.547267 -0.0389264,
+                          0.836052 0.547267 -0.0389264,
+                          0.834264 0.551364 -0.00112887,
+                          0.776497 0.628912 -0.0390128,
+                          0.551364 0.834264 -0.00112887,
+                          0.546919 0.836282 -0.0388734,
+                          0.628752 0.77663 -0.0389601,
+                          0.705994 0.706289 -0.052231,
+                          0.628752 0.77663 -0.0389601,
+                          0.546919 0.836282 -0.0388734,
+                          0.705994 0.706289 -0.052231,
+                          0.706066 0.706217 -0.052231,
+                          0.628752 0.77663 -0.0389601,
+                          0.367118 0.930174 -0.000728904,
+                          0.464188 0.884903 -0.0384256,
+                          0.546919 0.836282 -0.0388734,
+                          0.705926 0.706357 -0.052231,
+                          0.546919 0.836282 -0.0388734,
+                          0.464188 0.884903 -0.0384256,
+                          0.551364 0.834264 -0.00112887,
+                          0.367118 0.930174 -0.000728904,
+                          0.546919 0.836282 -0.0388734,
+                          0.705926 0.706357 -0.052231,
+                          0.705994 0.706289 -0.052231,
+                          0.546919 0.836282 -0.0388734,
+                          0.367118 0.930174 -0.000728904,
+                          0.177205 0.984174 -0.000358715,
+                          0.464188 0.884903 -0.0384256,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          6.12303e-17 1 2.22045e-16,
+                          0.776497 0.628912 -0.0390128,
+                          0.706066 0.706217 -0.052231,
+                          0.705994 0.706289 -0.052231,
+                          0.836052 0.547267 -0.0389264,
+                          0.705994 0.706289 -0.052231,
+                          0.705926 0.706357 -0.052231,
+                          0.836052 0.547267 -0.0389264,
+                          0.776497 0.628912 -0.0390128,
+                          0.705994 0.706289 -0.052231,
+                          0.884615 0.464731 -0.0384798,
+                          0.836052 0.547267 -0.0389264,
+                          0.705926 0.706357 -0.052231,
+                          -0.464731 0.884615 -0.0384798,
+                          -0.177205 0.984174 -0.000358715,
+                          -0.367118 0.930174 -0.000728904,
+                          -0.547267 0.836052 -0.0389264,
+                          -0.367118 0.930174 -0.000728904,
+                          -0.551364 0.834264 -0.00112887,
+                          -0.464731 0.884615 -0.0384798,
+                          -0.367118 0.930174 -0.000728904,
+                          -0.547267 0.836052 -0.0389264,
+                          -0.547267 0.836052 -0.0389264,
+                          -0.551364 0.834264 -0.00112887,
+                          -0.628912 0.776497 -0.0390128,
+                          -0.834264 0.551364 -0.00112887,
+                          -0.836282 0.546919 -0.0388734,
+                          -0.77663 0.628752 -0.0389601,
+                          -0.706289 0.705994 -0.052231,
+                          -0.77663 0.628752 -0.0389601,
+                          -0.836282 0.546919 -0.0388734,
+                          -0.706289 0.705994 -0.052231,
+                          -0.706217 0.706066 -0.052231,
+                          -0.77663 0.628752 -0.0389601,
+                          -0.930174 0.367118 -0.000728904,
+                          -0.884903 0.464188 -0.0384256,
+                          -0.836282 0.546919 -0.0388734,
+                          -0.706357 0.705926 -0.052231,
+                          -0.836282 0.546919 -0.0388734,
+                          -0.884903 0.464188 -0.0384256,
+                          -0.834264 0.551364 -0.00112887,
+                          -0.930174 0.367118 -0.000728904,
+                          -0.836282 0.546919 -0.0388734,
+                          -0.706357 0.705926 -0.052231,
+                          -0.706289 0.705994 -0.052231,
+                          -0.836282 0.546919 -0.0388734,
+                          -0.930174 0.367118 -0.000728904,
+                          -0.984174 0.177205 -0.000358715,
+                          -0.884903 0.464188 -0.0384256,
+                          -0.628912 0.776497 -0.0390128,
+                          -0.706217 0.706066 -0.052231,
+                          -0.706289 0.705994 -0.052231,
+                          -0.547267 0.836052 -0.0389264,
+                          -0.706289 0.705994 -0.052231,
+                          -0.706357 0.705926 -0.052231,
+                          -0.547267 0.836052 -0.0389264,
+                          -0.628912 0.776497 -0.0390128,
+                          -0.706289 0.705994 -0.052231,
+                          -0.464731 0.884615 -0.0384798,
+                          -0.547267 0.836052 -0.0389264,
+                          -0.706357 0.705926 -0.052231,
+                          -0.884615 -0.464731 -0.0384798,
+                          -0.984174 -0.177205 -0.000358715,
+                          -0.930174 -0.367118 -0.000728904,
+                          -0.836052 -0.547267 -0.0389264,
+                          -0.930174 -0.367118 -0.000728904,
+                          -0.834264 -0.551364 -0.00112887,
+                          -0.884615 -0.464731 -0.0384798,
+                          -0.930174 -0.367118 -0.000728904,
+                          -0.836052 -0.547267 -0.0389264,
+                          -0.836052 -0.547267 -0.0389264,
+                          -0.834264 -0.551364 -0.00112887,
+                          -0.776497 -0.628912 -0.0390128,
+                          -0.551364 -0.834264 -0.00112887,
+                          -0.546919 -0.836282 -0.0388734,
+                          -0.628752 -0.77663 -0.0389601,
+                          -0.705994 -0.706289 -0.052231,
+                          -0.628752 -0.77663 -0.0389601,
+                          -0.546919 -0.836282 -0.0388734,
+                          -0.705994 -0.706289 -0.052231,
+                          -0.706066 -0.706217 -0.052231,
+                          -0.628752 -0.77663 -0.0389601,
+                          -0.367118 -0.930174 -0.000728904,
+                          -0.464188 -0.884903 -0.0384256,
+                          -0.546919 -0.836282 -0.0388734,
+                          -0.705926 -0.706357 -0.052231,
+                          -0.546919 -0.836282 -0.0388734,
+                          -0.464188 -0.884903 -0.0384256,
+                          -0.551364 -0.834264 -0.00112887,
+                          -0.367118 -0.930174 -0.000728904,
+                          -0.546919 -0.836282 -0.0388734,
+                          -0.705926 -0.706357 -0.052231,
+                          -0.705994 -0.706289 -0.052231,
+                          -0.546919 -0.836282 -0.0388734,
+                          -0.367118 -0.930174 -0.000728904,
+                          -0.177205 -0.984174 -0.000358715,
+                          -0.464188 -0.884903 -0.0384256,
+                          -0.776497 -0.628912 -0.0390128,
+                          -0.706066 -0.706217 -0.052231,
+                          -0.705994 -0.706289 -0.052231,
+                          -0.836052 -0.547267 -0.0389264,
+                          -0.705994 -0.706289 -0.052231,
+                          -0.705926 -0.706357 -0.052231,
+                          -0.836052 -0.547267 -0.0389264,
+                          -0.776497 -0.628912 -0.0390128,
+                          -0.705994 -0.706289 -0.052231,
+                          -0.884615 -0.464731 -0.0384798,
+                          -0.836052 -0.547267 -0.0389264,
+                          -0.705926 -0.706357 -0.052231 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 58.3073 173.955 131,
+                          -128.307 173.955 131,
+                          -113 177 131,
+                          -113 177 187,
+                          -113 177 131,
+                          -128.307 173.955 131,
+                          43 177 131,
+                          58.3073 173.955 131,
+                          -113 177 131,
+                          -113 177 187,
+                          43 177 131,
+                          -113 177 131,
+                          71.2843 165.284 131,
+                          -141.284 165.284 131,
+                          -128.307 173.955 131,
+                          -134.634 167.271 187,
+                          -128.307 173.955 131,
+                          -141.284 165.284 131,
+                          58.3073 173.955 131,
+                          71.2843 165.284 131,
+                          -128.307 173.955 131,
+                          -124.271 173.532 187,
+                          -113 177 187,
+                          -128.307 173.955 131,
+                          -134.634 167.271 187,
+                          -124.271 173.532 187,
+                          -128.307 173.955 131,
+                          79.9552 152.307 131,
+                          -149.955 152.307 131,
+                          -141.284 165.284 131,
+                          -143.271 158.634 187,
+                          -141.284 165.284 131,
+                          -149.955 152.307 131,
+                          71.2843 165.284 131,
+                          79.9552 152.307 131,
+                          -141.284 165.284 131,
+                          -143.271 158.634 187,
+                          -134.634 167.271 187,
+                          -141.284 165.284 131,
+                          83 137 131,
+                          -153 137 131,
+                          -149.955 152.307 131,
+                          -149.532 148.271 187,
+                          -149.955 152.307 131,
+                          -153 137 131,
+                          79.9552 152.307 131,
+                          83 137 131,
+                          -149.955 152.307 131,
+                          -149.532 148.271 187,
+                          -143.271 158.634 187,
+                          -149.955 152.307 131,
+                          83 -137 131,
+                          -153 -137 131,
+                          -153 137 131,
+                          -153 137 187,
+                          -153 137 131,
+                          -153 -137 131,
+                          83 137 131,
+                          83 -137 131,
+                          -153 137 131,
+                          -153 137 187,
+                          -149.532 148.271 187,
+                          -153 137 131,
+                          79.9552 -152.307 131,
+                          -149.955 -152.307 131,
+                          -153 -137 131,
+                          -153 -137 187,
+                          -153 -137 131,
+                          -149.955 -152.307 131,
+                          83 -137 131,
+                          79.9552 -152.307 131,
+                          -153 -137 131,
+                          -153 137 299.112,
+                          -153 -137 131,
+                          -153 137 355,
+                          -153 -137 187,
+                          -153 137 355,
+                          -153 -137 131,
+                          -153 137 243.056,
+                          -153 137 187,
+                          -153 -137 131,
+                          -153 137 299.112,
+                          -153 137 243.056,
+                          -153 -137 131,
+                          71.2843 -165.284 131,
+                          -141.284 -165.284 131,
+                          -149.955 -152.307 131,
+                          -143.271 -158.634 187,
+                          -149.955 -152.307 131,
+                          -141.284 -165.284 131,
+                          79.9552 -152.307 131,
+                          71.2843 -165.284 131,
+                          -149.955 -152.307 131,
+                          -149.532 -148.271 187,
+                          -153 -137 187,
+                          -149.955 -152.307 131,
+                          -143.271 -158.634 187,
+                          -149.532 -148.271 187,
+                          -149.955 -152.307 131,
+                          58.3073 -173.955 131,
+                          -128.307 -173.955 131,
+                          -141.284 -165.284 131,
+                          -134.634 -167.271 187,
+                          -141.284 -165.284 131,
+                          -128.307 -173.955 131,
+                          71.2843 -165.284 131,
+                          58.3073 -173.955 131,
+                          -141.284 -165.284 131,
+                          -134.634 -167.271 187,
+                          -143.271 -158.634 187,
+                          -141.284 -165.284 131,
+                          43 -177 131,
+                          -113 -177 131,
+                          -128.307 -173.955 131,
+                          -124.271 -173.532 187,
+                          -128.307 -173.955 131,
+                          -113 -177 131,
+                          58.3073 -173.955 131,
+                          43 -177 131,
+                          -128.307 -173.955 131,
+                          -124.271 -173.532 187,
+                          -134.634 -167.271 187,
+                          -128.307 -173.955 131,
+                          43 -177 187,
+                          -113 -177 131,
+                          43 -177 131,
+                          -113 -177 187,
+                          -124.271 -173.532 187,
+                          -113 -177 131,
+                          43 -177 187,
+                          -113 -177 187,
+                          -113 -177 131,
+                          43 -177 187,
+                          43 -177 131,
+                          58.3073 -173.955 131,
+                          64.6336 -167.271 187,
+                          58.3073 -173.955 131,
+                          71.2843 -165.284 131,
+                          54.2705 -173.532 187,
+                          43 -177 187,
+                          58.3073 -173.955 131,
+                          64.6336 -167.271 187,
+                          54.2705 -173.532 187,
+                          58.3073 -173.955 131,
+                          73.2705 -158.634 187,
+                          71.2843 -165.284 131,
+                          79.9552 -152.307 131,
+                          73.2705 -158.634 187,
+                          64.6336 -167.271 187,
+                          71.2843 -165.284 131,
+                          79.5317 -148.271 187,
+                          79.9552 -152.307 131,
+                          83 -137 131,
+                          79.5317 -148.271 187,
+                          73.2705 -158.634 187,
+                          79.9552 -152.307 131,
+                          83 -137 187,
+                          83 -137 131,
+                          83 137 131,
+                          83 -137 187,
+                          79.5317 -148.271 187,
+                          83 -137 131,
+                          83 137 187,
+                          83 137 131,
+                          79.9552 152.307 131,
+                          83 -137 299.112,
+                          83 137 131,
+                          83 -137 355,
+                          83 137 187,
+                          83 -137 355,
+                          83 137 131,
+                          83 -137 243.056,
+                          83 -137 187,
+                          83 137 131,
+                          83 -137 299.112,
+                          83 -137 243.056,
+                          83 137 131,
+                          73.2705 158.634 187,
+                          79.9552 152.307 131,
+                          71.2843 165.284 131,
+                          79.5317 148.271 187,
+                          83 137 187,
+                          79.9552 152.307 131,
+                          73.2705 158.634 187,
+                          79.5317 148.271 187,
+                          79.9552 152.307 131,
+                          64.6336 167.271 187,
+                          71.2843 165.284 131,
+                          58.3073 173.955 131,
+                          64.6336 167.271 187,
+                          73.2705 158.634 187,
+                          71.2843 165.284 131,
+                          54.2705 173.532 187,
+                          58.3073 173.955 131,
+                          43 177 131,
+                          54.2705 173.532 187,
+                          64.6336 167.271 187,
+                          58.3073 173.955 131,
+                          43 177 187,
+                          43 177 131,
+                          -113 177 187,
+                          43 177 187,
+                          54.2705 173.532 187,
+                          43 177 131,
+                          -112.586 176 355,
+                          43 177 355,
+                          -113 177 355,
+                          43 177 299.112,
+                          -113 177 355,
+                          43 177 355,
+                          -112.586 176 355,
+                          -113 177 355,
+                          -123 167 355,
+                          -122.088 170.508 299.112,
+                          -123 167 355,
+                          -113 177 355,
+                          -122.088 170.508 299.112,
+                          -113 177 355,
+                          -113 177 299.112,
+                          43 177 299.112,
+                          -113 177 299.112,
+                          -113 177 355,
+                          42.5858 176 355,
+                          53 167 355,
+                          43 177 355,
+                          43 177 299.112,
+                          43 177 355,
+                          53 167 355,
+                          -112.586 176 355,
+                          42.5858 176 355,
+                          43 177 355,
+                          52.2727 166.312 355,
+                          63 157 355,
+                          53 167 355,
+                          60.8741 163.086 299.112,
+                          53 167 355,
+                          63 157 355,
+                          42.5858 176 355,
+                          52.2727 166.312 355,
+                          53 167 355,
+                          52.088 170.508 299.112,
+                          53 167 355,
+                          60.8741 163.086 299.112,
+                          43 177 299.112,
+                          53 167 355,
+                          52.088 170.508 299.112,
+                          62.282 156.302 355,
+                          73 147 355,
+                          63 157 355,
+                          69.086 154.874 299.112,
+                          63 157 355,
+                          73 147 355,
+                          52.2727 166.312 355,
+                          62.282 156.302 355,
+                          63 157 355,
+                          60.8741 163.086 299.112,
+                          63 157 355,
+                          69.086 154.874 299.112,
+                          72.2917 146.293 355,
+                          83 137 355,
+                          73 147 355,
+                          76.5075 146.088 299.112,
+                          73 147 355,
+                          83 137 355,
+                          62.282 156.302 355,
+                          72.2917 146.293 355,
+                          73 147 355,
+                          69.086 154.874 299.112,
+                          73 147 355,
+                          76.5075 146.088 299.112,
+                          82 -136.586 355,
+                          83 -137 355,
+                          83 137 355,
+                          83 137 299.112,
+                          83 137 355,
+                          83 -137 355,
+                          82 136.586 355,
+                          82 -136.586 355,
+                          83 137 355,
+                          72.2917 146.293 355,
+                          82 136.586 355,
+                          83 137 355,
+                          76.5075 146.088 299.112,
+                          83 137 355,
+                          83 137 299.112,
+                          72.3118 -146.273 355,
+                          73 -147 355,
+                          83 -137 355,
+                          83 -137 299.112,
+                          83 -137 355,
+                          73 -147 355,
+                          82 -136.586 355,
+                          72.3118 -146.273 355,
+                          83 -137 355,
+                          83 137 243.056,
+                          83 137 299.112,
+                          83 -137 355,
+                          83 137 187,
+                          83 137 243.056,
+                          83 -137 355,
+                          62.302 -156.282 355,
+                          63 -157 355,
+                          73 -147 355,
+                          69.086 -154.874 299.112,
+                          73 -147 355,
+                          63 -157 355,
+                          72.3118 -146.273 355,
+                          62.302 -156.282 355,
+                          73 -147 355,
+                          76.5075 -146.088 299.112,
+                          73 -147 355,
+                          69.086 -154.874 299.112,
+                          83 -137 299.112,
+                          73 -147 355,
+                          76.5075 -146.088 299.112,
+                          52.2928 -166.292 355,
+                          53 -167 355,
+                          63 -157 355,
+                          60.8741 -163.086 299.112,
+                          63 -157 355,
+                          53 -167 355,
+                          62.302 -156.282 355,
+                          52.2928 -166.292 355,
+                          63 -157 355,
+                          69.086 -154.874 299.112,
+                          63 -157 355,
+                          60.8741 -163.086 299.112,
+                          42.5858 -176 355,
+                          43 -177 355,
+                          53 -167 355,
+                          52.088 -170.508 299.112,
+                          53 -167 355,
+                          43 -177 355,
+                          52.2928 -166.292 355,
+                          42.5858 -176 355,
+                          53 -167 355,
+                          60.8741 -163.086 299.112,
+                          53 -167 355,
+                          52.088 -170.508 299.112,
+                          42.5858 -176 355,
+                          -113 -177 355,
+                          43 -177 355,
+                          -113 -177 299.112,
+                          43 -177 355,
+                          -113 -177 355,
+                          43 -177 299.112,
+                          43 -177 355,
+                          -113 -177 299.112,
+                          52.088 -170.508 299.112,
+                          43 -177 355,
+                          43 -177 299.112,
+                          -112.586 -176 355,
+                          -123 -167 355,
+                          -113 -177 355,
+                          -113 -177 299.112,
+                          -113 -177 355,
+                          -123 -167 355,
+                          42.5858 -176 355,
+                          -112.586 -176 355,
+                          -113 -177 355,
+                          -122.273 -166.312 355,
+                          -133 -157 355,
+                          -123 -167 355,
+                          -130.874 -163.086 299.112,
+                          -123 -167 355,
+                          -133 -157 355,
+                          -112.586 -176 355,
+                          -122.273 -166.312 355,
+                          -123 -167 355,
+                          -122.088 -170.508 299.112,
+                          -123 -167 355,
+                          -130.874 -163.086 299.112,
+                          -113 -177 299.112,
+                          -123 -167 355,
+                          -122.088 -170.508 299.112,
+                          -132.282 -156.302 355,
+                          -143 -147 355,
+                          -133 -157 355,
+                          -139.086 -154.874 299.112,
+                          -133 -157 355,
+                          -143 -147 355,
+                          -122.273 -166.312 355,
+                          -132.282 -156.302 355,
+                          -133 -157 355,
+                          -130.874 -163.086 299.112,
+                          -133 -157 355,
+                          -139.086 -154.874 299.112,
+                          -142.292 -146.293 355,
+                          -153 -137 355,
+                          -143 -147 355,
+                          -146.508 -146.088 299.112,
+                          -143 -147 355,
+                          -153 -137 355,
+                          -132.282 -156.302 355,
+                          -142.292 -146.293 355,
+                          -143 -147 355,
+                          -139.086 -154.874 299.112,
+                          -143 -147 355,
+                          -146.508 -146.088 299.112,
+                          -152 136.586 355,
+                          -153 137 355,
+                          -153 -137 355,
+                          -153 -137 299.112,
+                          -153 -137 355,
+                          -153 137 355,
+                          -152 -136.586 355,
+                          -152 136.586 355,
+                          -153 -137 355,
+                          -142.292 -146.293 355,
+                          -152 -136.586 355,
+                          -153 -137 355,
+                          -146.508 -146.088 299.112,
+                          -153 -137 355,
+                          -153 -137 299.112,
+                          -142.312 146.273 355,
+                          -143 147 355,
+                          -153 137 355,
+                          -153 137 299.112,
+                          -153 137 355,
+                          -143 147 355,
+                          -142.312 146.273 355,
+                          -153 137 355,
+                          -152 136.586 355,
+                          -153 -137 243.056,
+                          -153 -137 299.112,
+                          -153 137 355,
+                          -153 -137 187,
+                          -153 -137 243.056,
+                          -153 137 355,
+                          -132.302 156.282 355,
+                          -133 157 355,
+                          -143 147 355,
+                          -139.086 154.874 299.112,
+                          -143 147 355,
+                          -133 157 355,
+                          -142.312 146.273 355,
+                          -132.302 156.282 355,
+                          -143 147 355,
+                          -146.508 146.088 299.112,
+                          -143 147 355,
+                          -139.086 154.874 299.112,
+                          -153 137 299.112,
+                          -143 147 355,
+                          -146.508 146.088 299.112,
+                          -122.293 166.292 355,
+                          -123 167 355,
+                          -133 157 355,
+                          -130.874 163.086 299.112,
+                          -133 157 355,
+                          -123 167 355,
+                          -132.302 156.282 355,
+                          -122.293 166.292 355,
+                          -133 157 355,
+                          -139.086 154.874 299.112,
+                          -133 157 355,
+                          -130.874 163.086 299.112,
+                          -122.293 166.292 355,
+                          -112.586 176 355,
+                          -123 167 355,
+                          -130.874 163.086 299.112,
+                          -123 167 355,
+                          -122.088 170.508 299.112,
+                          -152 136.689 299.25,
+                          -152 136.586 355,
+                          -152 -136.586 355,
+                          -143.971 147.67 299.24,
+                          -142.312 146.273 355,
+                          -152 136.586 355,
+                          -152 136.689 299.25,
+                          -143.971 147.67 299.24,
+                          -152 136.586 355,
+                          -143.953 -147.692 299.24,
+                          -152 -136.586 355,
+                          -142.292 -146.293 355,
+                          -152 136.895 187.75,
+                          -152 -136.586 355,
+                          -152 136.999 132,
+                          -152 -136.689 299.25,
+                          -152 136.999 132,
+                          -152 -136.586 355,
+                          -152 136.792 243.5,
+                          -152 -136.586 355,
+                          -152 136.895 187.75,
+                          -152 136.689 299.25,
+                          -152 -136.586 355,
+                          -152 136.792 243.5,
+                          -143.953 -147.692 299.24,
+                          -152 -136.689 299.25,
+                          -152 -136.586 355,
+                          -134.344 -158.364 299.25,
+                          -142.292 -146.293 355,
+                          -132.282 -156.302 355,
+                          -143.953 -147.692 299.24,
+                          -142.292 -146.293 355,
+                          -134.344 -158.364 299.25,
+                          -134.344 -158.364 299.25,
+                          -132.282 -156.302 355,
+                          -122.273 -166.312 355,
+                          -123.67 -167.971 299.24,
+                          -122.273 -166.312 355,
+                          -112.586 -176 355,
+                          -134.344 -158.364 299.25,
+                          -122.273 -166.312 355,
+                          -123.67 -167.971 299.24,
+                          42.689 -176 299.25,
+                          -112.586 -176 355,
+                          42.5858 -176 355,
+                          -112.689 -176 299.25,
+                          -123.67 -167.971 299.24,
+                          -112.586 -176 355,
+                          42.689 -176 299.25,
+                          -112.689 -176 299.25,
+                          -112.586 -176 355,
+                          53.6919 -167.953 299.24,
+                          42.5858 -176 355,
+                          52.2928 -166.292 355,
+                          53.6919 -167.953 299.24,
+                          42.689 -176 299.25,
+                          42.5858 -176 355,
+                          64.364 -158.344 299.25,
+                          52.2928 -166.292 355,
+                          62.302 -156.282 355,
+                          53.6919 -167.953 299.24,
+                          52.2928 -166.292 355,
+                          64.364 -158.344 299.25,
+                          64.364 -158.344 299.25,
+                          62.302 -156.282 355,
+                          72.3118 -146.273 355,
+                          73.9711 -147.67 299.24,
+                          72.3118 -146.273 355,
+                          82 -136.586 355,
+                          64.364 -158.344 299.25,
+                          72.3118 -146.273 355,
+                          73.9711 -147.67 299.24,
+                          82 -136.689 299.25,
+                          82 -136.586 355,
+                          82 136.586 355,
+                          82 -136.689 299.25,
+                          73.9711 -147.67 299.24,
+                          82 -136.586 355,
+                          73.9532 147.692 299.24,
+                          82 136.586 355,
+                          72.2917 146.293 355,
+                          82 -136.895 187.75,
+                          82 136.586 355,
+                          82 -136.999 132,
+                          82 136.689 299.25,
+                          82 -136.999 132,
+                          82 136.586 355,
+                          82 -136.792 243.5,
+                          82 136.586 355,
+                          82 -136.895 187.75,
+                          82 -136.689 299.25,
+                          82 136.586 355,
+                          82 -136.792 243.5,
+                          73.9532 147.692 299.24,
+                          82 136.689 299.25,
+                          82 136.586 355,
+                          64.3436 158.364 299.25,
+                          72.2917 146.293 355,
+                          62.282 156.302 355,
+                          73.9532 147.692 299.24,
+                          72.2917 146.293 355,
+                          64.3436 158.364 299.25,
+                          64.3436 158.364 299.25,
+                          62.282 156.302 355,
+                          52.2727 166.312 355,
+                          53.6698 167.971 299.24,
+                          52.2727 166.312 355,
+                          42.5858 176 355,
+                          64.3436 158.364 299.25,
+                          52.2727 166.312 355,
+                          53.6698 167.971 299.24,
+                          -112.689 176 299.25,
+                          42.5858 176 355,
+                          -112.586 176 355,
+                          42.689 176 299.25,
+                          42.5858 176 355,
+                          -112.689 176 299.25,
+                          42.689 176 299.25,
+                          53.6698 167.971 299.24,
+                          42.5858 176 355,
+                          -123.692 167.953 299.24,
+                          -112.586 176 355,
+                          -122.293 166.292 355,
+                          -112.689 176 299.25,
+                          -112.586 176 355,
+                          -123.692 167.953 299.24,
+                          -134.364 158.344 299.25,
+                          -122.293 166.292 355,
+                          -132.302 156.282 355,
+                          -123.692 167.953 299.24,
+                          -122.293 166.292 355,
+                          -134.364 158.344 299.25,
+                          -134.364 158.344 299.25,
+                          -132.302 156.282 355,
+                          -142.312 146.273 355,
+                          -134.364 158.344 299.25,
+                          -142.312 146.273 355,
+                          -143.971 147.67 299.24,
+                          -113 177 243.056,
+                          -113 177 187,
+                          -124.271 173.532 187,
+                          43 177 187,
+                          -113 177 187,
+                          -113 177 243.056,
+                          -123.179 172.02 243.056,
+                          -124.271 173.532 187,
+                          -134.634 167.271 187,
+                          -123.179 172.02 243.056,
+                          -113 177 243.056,
+                          -124.271 173.532 187,
+                          -132.754 165.178 243.056,
+                          -134.634 167.271 187,
+                          -143.271 158.634 187,
+                          -132.754 165.178 243.056,
+                          -123.179 172.02 243.056,
+                          -134.634 167.271 187,
+                          -141.178 156.754 243.056,
+                          -143.271 158.634 187,
+                          -149.532 148.271 187,
+                          -141.178 156.754 243.056,
+                          -132.754 165.178 243.056,
+                          -143.271 158.634 187,
+                          -148.02 147.179 243.056,
+                          -149.532 148.271 187,
+                          -153 137 187,
+                          -148.02 147.179 243.056,
+                          -141.178 156.754 243.056,
+                          -149.532 148.271 187,
+                          -153 137 243.056,
+                          -148.02 147.179 243.056,
+                          -153 137 187,
+                          -113 177 299.112,
+                          -113 177 243.056,
+                          -123.179 172.02 243.056,
+                          43 177 243.056,
+                          -113 177 243.056,
+                          -113 177 299.112,
+                          43 177 243.056,
+                          43 177 187,
+                          -113 177 243.056,
+                          -122.088 170.508 299.112,
+                          -123.179 172.02 243.056,
+                          -132.754 165.178 243.056,
+                          -122.088 170.508 299.112,
+                          -113 177 299.112,
+                          -123.179 172.02 243.056,
+                          -130.874 163.086 299.112,
+                          -132.754 165.178 243.056,
+                          -141.178 156.754 243.056,
+                          -130.874 163.086 299.112,
+                          -122.088 170.508 299.112,
+                          -132.754 165.178 243.056,
+                          -139.086 154.874 299.112,
+                          -141.178 156.754 243.056,
+                          -148.02 147.179 243.056,
+                          -139.086 154.874 299.112,
+                          -130.874 163.086 299.112,
+                          -141.178 156.754 243.056,
+                          -146.508 146.088 299.112,
+                          -148.02 147.179 243.056,
+                          -153 137 243.056,
+                          -146.508 146.088 299.112,
+                          -139.086 154.874 299.112,
+                          -148.02 147.179 243.056,
+                          -153 137 299.112,
+                          -146.508 146.088 299.112,
+                          -153 137 243.056,
+                          43 177 299.112,
+                          43 177 243.056,
+                          -113 177 299.112,
+                          -148.02 -147.179 243.056,
+                          -153 -137 299.112,
+                          -153 -137 243.056,
+                          -146.508 -146.088 299.112,
+                          -153 -137 299.112,
+                          -148.02 -147.179 243.056,
+                          -149.532 -148.271 187,
+                          -153 -137 243.056,
+                          -153 -137 187,
+                          -148.02 -147.179 243.056,
+                          -153 -137 243.056,
+                          -149.532 -148.271 187,
+                          -148.02 -147.179 243.056,
+                          -149.532 -148.271 187,
+                          -143.271 -158.634 187,
+                          -141.178 -156.754 243.056,
+                          -143.271 -158.634 187,
+                          -134.634 -167.271 187,
+                          -141.178 -156.754 243.056,
+                          -148.02 -147.179 243.056,
+                          -143.271 -158.634 187,
+                          -132.754 -165.178 243.056,
+                          -134.634 -167.271 187,
+                          -124.271 -173.532 187,
+                          -132.754 -165.178 243.056,
+                          -141.178 -156.754 243.056,
+                          -134.634 -167.271 187,
+                          -123.179 -172.02 243.056,
+                          -124.271 -173.532 187,
+                          -113 -177 187,
+                          -123.179 -172.02 243.056,
+                          -132.754 -165.178 243.056,
+                          -124.271 -173.532 187,
+                          -113 -177 243.056,
+                          -123.179 -172.02 243.056,
+                          -113 -177 187,
+                          43 -177 243.056,
+                          -113 -177 243.056,
+                          -113 -177 187,
+                          43 -177 187,
+                          43 -177 243.056,
+                          -113 -177 187,
+                          -146.508 -146.088 299.112,
+                          -148.02 -147.179 243.056,
+                          -141.178 -156.754 243.056,
+                          -139.086 -154.874 299.112,
+                          -141.178 -156.754 243.056,
+                          -132.754 -165.178 243.056,
+                          -139.086 -154.874 299.112,
+                          -146.508 -146.088 299.112,
+                          -141.178 -156.754 243.056,
+                          -130.874 -163.086 299.112,
+                          -132.754 -165.178 243.056,
+                          -123.179 -172.02 243.056,
+                          -130.874 -163.086 299.112,
+                          -139.086 -154.874 299.112,
+                          -132.754 -165.178 243.056,
+                          -122.088 -170.508 299.112,
+                          -123.179 -172.02 243.056,
+                          -113 -177 243.056,
+                          -122.088 -170.508 299.112,
+                          -130.874 -163.086 299.112,
+                          -123.179 -172.02 243.056,
+                          -113 -177 299.112,
+                          -122.088 -170.508 299.112,
+                          -113 -177 243.056,
+                          43 -177 299.112,
+                          -113 -177 299.112,
+                          -113 -177 243.056,
+                          43 -177 243.056,
+                          43 -177 299.112,
+                          -113 -177 243.056,
+                          53.1792 -172.02 243.056,
+                          43 -177 299.112,
+                          43 -177 243.056,
+                          52.088 -170.508 299.112,
+                          43 -177 299.112,
+                          53.1792 -172.02 243.056,
+                          54.2705 -173.532 187,
+                          43 -177 243.056,
+                          43 -177 187,
+                          53.1792 -172.02 243.056,
+                          43 -177 243.056,
+                          54.2705 -173.532 187,
+                          53.1792 -172.02 243.056,
+                          54.2705 -173.532 187,
+                          64.6336 -167.271 187,
+                          62.7538 -165.178 243.056,
+                          64.6336 -167.271 187,
+                          73.2705 -158.634 187,
+                          62.7538 -165.178 243.056,
+                          53.1792 -172.02 243.056,
+                          64.6336 -167.271 187,
+                          71.1783 -156.754 243.056,
+                          73.2705 -158.634 187,
+                          79.5317 -148.271 187,
+                          71.1783 -156.754 243.056,
+                          62.7538 -165.178 243.056,
+                          73.2705 -158.634 187,
+                          78.0196 -147.179 243.056,
+                          79.5317 -148.271 187,
+                          83 -137 187,
+                          78.0196 -147.179 243.056,
+                          71.1783 -156.754 243.056,
+                          79.5317 -148.271 187,
+                          83 -137 243.056,
+                          78.0196 -147.179 243.056,
+                          83 -137 187,
+                          52.088 -170.508 299.112,
+                          53.1792 -172.02 243.056,
+                          62.7538 -165.178 243.056,
+                          60.8741 -163.086 299.112,
+                          62.7538 -165.178 243.056,
+                          71.1783 -156.754 243.056,
+                          60.8741 -163.086 299.112,
+                          52.088 -170.508 299.112,
+                          62.7538 -165.178 243.056,
+                          69.086 -154.874 299.112,
+                          71.1783 -156.754 243.056,
+                          78.0196 -147.179 243.056,
+                          69.086 -154.874 299.112,
+                          60.8741 -163.086 299.112,
+                          71.1783 -156.754 243.056,
+                          76.5075 -146.088 299.112,
+                          78.0196 -147.179 243.056,
+                          83 -137 243.056,
+                          76.5075 -146.088 299.112,
+                          69.086 -154.874 299.112,
+                          78.0196 -147.179 243.056,
+                          83 -137 299.112,
+                          76.5075 -146.088 299.112,
+                          83 -137 243.056,
+                          78.0196 147.179 243.056,
+                          83 137 299.112,
+                          83 137 243.056,
+                          76.5075 146.088 299.112,
+                          83 137 299.112,
+                          78.0196 147.179 243.056,
+                          79.5317 148.271 187,
+                          83 137 243.056,
+                          83 137 187,
+                          78.0196 147.179 243.056,
+                          83 137 243.056,
+                          79.5317 148.271 187,
+                          78.0196 147.179 243.056,
+                          79.5317 148.271 187,
+                          73.2705 158.634 187,
+                          71.1783 156.754 243.056,
+                          73.2705 158.634 187,
+                          64.6336 167.271 187,
+                          71.1783 156.754 243.056,
+                          78.0196 147.179 243.056,
+                          73.2705 158.634 187,
+                          62.7538 165.178 243.056,
+                          64.6336 167.271 187,
+                          54.2705 173.532 187,
+                          62.7538 165.178 243.056,
+                          71.1783 156.754 243.056,
+                          64.6336 167.271 187,
+                          53.1792 172.02 243.056,
+                          54.2705 173.532 187,
+                          43 177 187,
+                          53.1792 172.02 243.056,
+                          62.7538 165.178 243.056,
+                          54.2705 173.532 187,
+                          43 177 243.056,
+                          53.1792 172.02 243.056,
+                          43 177 187,
+                          76.5075 146.088 299.112,
+                          78.0196 147.179 243.056,
+                          71.1783 156.754 243.056,
+                          69.086 154.874 299.112,
+                          71.1783 156.754 243.056,
+                          62.7538 165.178 243.056,
+                          69.086 154.874 299.112,
+                          76.5075 146.088 299.112,
+                          71.1783 156.754 243.056,
+                          60.8741 163.086 299.112,
+                          62.7538 165.178 243.056,
+                          53.1792 172.02 243.056,
+                          60.8741 163.086 299.112,
+                          69.086 154.874 299.112,
+                          62.7538 165.178 243.056,
+                          52.088 170.508 299.112,
+                          53.1792 172.02 243.056,
+                          43 177 243.056,
+                          52.088 170.508 299.112,
+                          60.8741 163.086 299.112,
+                          53.1792 172.02 243.056,
+                          43 177 299.112,
+                          52.088 170.508 299.112,
+                          43 177 243.056,
+                          -127.9 173 132,
+                          42.9987 176 132,
+                          -112.999 176 132,
+                          42.8954 176 187.75,
+                          -112.999 176 132,
+                          42.9987 176 132,
+                          -112.895 176 187.75,
+                          -127.9 173 132,
+                          -112.999 176 132,
+                          42.8954 176 187.75,
+                          -112.895 176 187.75,
+                          -112.999 176 132,
+                          -127.9 173 132,
+                          57.8715 173.012 132,
+                          42.9987 176 132,
+                          42.8954 176 187.75,
+                          42.9987 176 132,
+                          57.8715 173.012 132,
+                          -127.9 173 132,
+                          70.5285 164.55 132,
+                          57.8715 173.012 132,
+                          56.4716 171.321 187.746,
+                          57.8715 173.012 132,
+                          70.5285 164.55 132,
+                          42.8954 176 187.75,
+                          57.8715 173.012 132,
+                          56.4716 171.321 187.746,
+                          -140.55 164.528 132,
+                          79.0001 151.9 132,
+                          70.5285 164.55 132,
+                          77.3071 150.498 187.746,
+                          70.5285 164.55 132,
+                          79.0001 151.9 132,
+                          -127.9 173 132,
+                          -140.55 164.528 132,
+                          70.5285 164.55 132,
+                          68.4668 162.488 187.75,
+                          56.4716 171.321 187.746,
+                          70.5285 164.55 132,
+                          77.3071 150.498 187.746,
+                          68.4668 162.488 187.75,
+                          70.5285 164.55 132,
+                          -152 136.999 132,
+                          82 136.999 132,
+                          79.0001 151.9 132,
+                          82 136.895 187.75,
+                          79.0001 151.9 132,
+                          82 136.999 132,
+                          -149.012 151.871 132,
+                          -152 136.999 132,
+                          79.0001 151.9 132,
+                          -140.55 164.528 132,
+                          -149.012 151.871 132,
+                          79.0001 151.9 132,
+                          77.3071 150.498 187.746,
+                          79.0001 151.9 132,
+                          82 136.895 187.75,
+                          -152 -136.999 132,
+                          82 -136.999 132,
+                          82 136.999 132,
+                          82 136.895 187.75,
+                          82 136.999 132,
+                          82 -136.999 132,
+                          -152 136.999 132,
+                          -152 -136.999 132,
+                          82 136.999 132,
+                          -149 -151.9 132,
+                          79.0117 -151.871 132,
+                          82 -136.999 132,
+                          82 -136.895 187.75,
+                          82 -136.999 132,
+                          79.0117 -151.871 132,
+                          -152 -136.999 132,
+                          -149 -151.9 132,
+                          82 -136.999 132,
+                          82 136.792 243.5,
+                          82 136.895 187.75,
+                          82 -136.999 132,
+                          82 136.689 299.25,
+                          82 136.792 243.5,
+                          82 -136.999 132,
+                          -149 -151.9 132,
+                          70.55 -164.528 132,
+                          79.0117 -151.871 132,
+                          77.3208 -150.472 187.746,
+                          79.0117 -151.871 132,
+                          70.55 -164.528 132,
+                          82 -136.895 187.75,
+                          79.0117 -151.871 132,
+                          77.3208 -150.472 187.746,
+                          -140.528 -164.55 132,
+                          57.8995 -173 132,
+                          70.55 -164.528 132,
+                          56.4978 -171.307 187.746,
+                          70.55 -164.528 132,
+                          57.8995 -173 132,
+                          -149 -151.9 132,
+                          -140.528 -164.55 132,
+                          70.55 -164.528 132,
+                          68.488 -162.467 187.75,
+                          77.3208 -150.472 187.746,
+                          70.55 -164.528 132,
+                          56.4978 -171.307 187.746,
+                          68.488 -162.467 187.75,
+                          70.55 -164.528 132,
+                          -112.999 -176 132,
+                          42.9987 -176 132,
+                          57.8995 -173 132,
+                          42.8954 -176 187.75,
+                          57.8995 -173 132,
+                          42.9987 -176 132,
+                          -127.871 -173.012 132,
+                          -112.999 -176 132,
+                          57.8995 -173 132,
+                          -140.528 -164.55 132,
+                          -127.871 -173.012 132,
+                          57.8995 -173 132,
+                          56.4978 -171.307 187.746,
+                          57.8995 -173 132,
+                          42.8954 -176 187.75,
+                          -112.895 -176 187.75,
+                          42.9987 -176 132,
+                          -112.999 -176 132,
+                          42.8954 -176 187.75,
+                          42.9987 -176 132,
+                          -112.895 -176 187.75,
+                          -112.895 -176 187.75,
+                          -112.999 -176 132,
+                          -127.871 -173.012 132,
+                          -126.472 -171.321 187.746,
+                          -127.871 -173.012 132,
+                          -140.528 -164.55 132,
+                          -112.895 -176 187.75,
+                          -127.871 -173.012 132,
+                          -126.472 -171.321 187.746,
+                          -147.307 -150.498 187.746,
+                          -140.528 -164.55 132,
+                          -149 -151.9 132,
+                          -138.467 -162.488 187.75,
+                          -126.472 -171.321 187.746,
+                          -140.528 -164.55 132,
+                          -147.307 -150.498 187.746,
+                          -138.467 -162.488 187.75,
+                          -140.528 -164.55 132,
+                          -152 -136.895 187.75,
+                          -149 -151.9 132,
+                          -152 -136.999 132,
+                          -147.307 -150.498 187.746,
+                          -149 -151.9 132,
+                          -152 -136.895 187.75,
+                          -152 -136.895 187.75,
+                          -152 -136.999 132,
+                          -152 136.999 132,
+                          -152 136.895 187.75,
+                          -152 136.999 132,
+                          -149.012 151.871 132,
+                          -152 -136.792 243.5,
+                          -152 -136.895 187.75,
+                          -152 136.999 132,
+                          -152 -136.689 299.25,
+                          -152 -136.792 243.5,
+                          -152 136.999 132,
+                          -147.321 150.472 187.746,
+                          -149.012 151.871 132,
+                          -140.55 164.528 132,
+                          -152 136.895 187.75,
+                          -149.012 151.871 132,
+                          -147.321 150.472 187.746,
+                          -126.498 171.307 187.746,
+                          -140.55 164.528 132,
+                          -127.9 173 132,
+                          -138.488 162.467 187.75,
+                          -147.321 150.472 187.746,
+                          -140.55 164.528 132,
+                          -126.498 171.307 187.746,
+                          -138.488 162.467 187.75,
+                          -140.55 164.528 132,
+                          -112.895 176 187.75,
+                          -126.498 171.307 187.746,
+                          -127.9 173 132,
+                          -152 136.689 299.25,
+                          -145.64 149.07 243.493,
+                          -143.971 147.67 299.24,
+                          -136.426 160.405 243.5,
+                          -143.971 147.67 299.24,
+                          -145.64 149.07 243.493,
+                          -136.426 160.405 243.5,
+                          -134.364 158.344 299.25,
+                          -143.971 147.67 299.24,
+                          -152 136.792 243.5,
+                          -147.321 150.472 187.746,
+                          -145.64 149.07 243.493,
+                          -138.488 162.467 187.75,
+                          -145.64 149.07 243.493,
+                          -147.321 150.472 187.746,
+                          -152 136.689 299.25,
+                          -152 136.792 243.5,
+                          -145.64 149.07 243.493,
+                          -138.488 162.467 187.75,
+                          -136.426 160.405 243.5,
+                          -145.64 149.07 243.493,
+                          -152 136.792 243.5,
+                          -152 136.895 187.75,
+                          -147.321 150.472 187.746,
+                          -123.692 167.953 299.24,
+                          -134.364 158.344 299.25,
+                          -136.426 160.405 243.5,
+                          -125.094 169.625 243.493,
+                          -136.426 160.405 243.5,
+                          -138.488 162.467 187.75,
+                          -125.094 169.625 243.493,
+                          -123.692 167.953 299.24,
+                          -136.426 160.405 243.5,
+                          -126.498 171.307 187.746,
+                          -125.094 169.625 243.493,
+                          -138.488 162.467 187.75,
+                          -112.689 176 299.25,
+                          -123.692 167.953 299.24,
+                          -125.094 169.625 243.493,
+                          -112.792 176 243.5,
+                          -125.094 169.625 243.493,
+                          -126.498 171.307 187.746,
+                          -112.792 176 243.5,
+                          -112.689 176 299.25,
+                          -125.094 169.625 243.493,
+                          -112.895 176 187.75,
+                          -112.792 176 243.5,
+                          -126.498 171.307 187.746,
+                          42.689 176 299.25,
+                          -112.689 176 299.25,
+                          -112.792 176 243.5,
+                          42.7922 176 243.5,
+                          -112.792 176 243.5,
+                          -112.895 176 187.75,
+                          42.689 176 299.25,
+                          -112.792 176 243.5,
+                          42.7922 176 243.5,
+                          42.7922 176 243.5,
+                          -112.895 176 187.75,
+                          42.8954 176 187.75,
+                          -147.307 -150.498 187.746,
+                          -152 -136.895 187.75,
+                          -152 -136.792 243.5,
+                          -145.625 -149.094 243.493,
+                          -152 -136.792 243.5,
+                          -152 -136.689 299.25,
+                          -147.307 -150.498 187.746,
+                          -152 -136.792 243.5,
+                          -145.625 -149.094 243.493,
+                          -145.625 -149.094 243.493,
+                          -152 -136.689 299.25,
+                          -143.953 -147.692 299.24,
+                          -112.689 -176 299.25,
+                          -125.07 -169.64 243.493,
+                          -123.67 -167.971 299.24,
+                          -136.405 -160.426 243.5,
+                          -123.67 -167.971 299.24,
+                          -125.07 -169.64 243.493,
+                          -136.405 -160.426 243.5,
+                          -134.344 -158.364 299.25,
+                          -123.67 -167.971 299.24,
+                          -112.792 -176 243.5,
+                          -126.472 -171.321 187.746,
+                          -125.07 -169.64 243.493,
+                          -138.467 -162.488 187.75,
+                          -125.07 -169.64 243.493,
+                          -126.472 -171.321 187.746,
+                          -112.689 -176 299.25,
+                          -112.792 -176 243.5,
+                          -125.07 -169.64 243.493,
+                          -138.467 -162.488 187.75,
+                          -136.405 -160.426 243.5,
+                          -125.07 -169.64 243.493,
+                          -112.792 -176 243.5,
+                          -112.895 -176 187.75,
+                          -126.472 -171.321 187.746,
+                          42.8954 -176 187.75,
+                          -112.895 -176 187.75,
+                          -112.792 -176 243.5,
+                          42.7922 -176 243.5,
+                          -112.792 -176 243.5,
+                          -112.689 -176 299.25,
+                          42.7922 -176 243.5,
+                          42.8954 -176 187.75,
+                          -112.792 -176 243.5,
+                          42.689 -176 299.25,
+                          42.7922 -176 243.5,
+                          -112.689 -176 299.25,
+                          -143.953 -147.692 299.24,
+                          -134.344 -158.364 299.25,
+                          -136.405 -160.426 243.5,
+                          -145.625 -149.094 243.493,
+                          -136.405 -160.426 243.5,
+                          -138.467 -162.488 187.75,
+                          -145.625 -149.094 243.493,
+                          -143.953 -147.692 299.24,
+                          -136.405 -160.426 243.5,
+                          -147.307 -150.498 187.746,
+                          -145.625 -149.094 243.493,
+                          -138.467 -162.488 187.75,
+                          56.4978 -171.307 187.746,
+                          42.8954 -176 187.75,
+                          42.7922 -176 243.5,
+                          55.0944 -169.625 243.493,
+                          42.7922 -176 243.5,
+                          42.689 -176 299.25,
+                          56.4978 -171.307 187.746,
+                          42.7922 -176 243.5,
+                          55.0944 -169.625 243.493,
+                          55.0944 -169.625 243.493,
+                          42.689 -176 299.25,
+                          53.6919 -167.953 299.24,
+                          82 -136.689 299.25,
+                          75.6404 -149.07 243.493,
+                          73.9711 -147.67 299.24,
+                          66.426 -160.405 243.5,
+                          73.9711 -147.67 299.24,
+                          75.6404 -149.07 243.493,
+                          66.426 -160.405 243.5,
+                          64.364 -158.344 299.25,
+                          73.9711 -147.67 299.24,
+                          82 -136.792 243.5,
+                          77.3208 -150.472 187.746,
+                          75.6404 -149.07 243.493,
+                          68.488 -162.467 187.75,
+                          75.6404 -149.07 243.493,
+                          77.3208 -150.472 187.746,
+                          82 -136.689 299.25,
+                          82 -136.792 243.5,
+                          75.6404 -149.07 243.493,
+                          68.488 -162.467 187.75,
+                          66.426 -160.405 243.5,
+                          75.6404 -149.07 243.493,
+                          82 -136.792 243.5,
+                          82 -136.895 187.75,
+                          77.3208 -150.472 187.746,
+                          53.6919 -167.953 299.24,
+                          64.364 -158.344 299.25,
+                          66.426 -160.405 243.5,
+                          55.0944 -169.625 243.493,
+                          66.426 -160.405 243.5,
+                          68.488 -162.467 187.75,
+                          55.0944 -169.625 243.493,
+                          53.6919 -167.953 299.24,
+                          66.426 -160.405 243.5,
+                          56.4978 -171.307 187.746,
+                          55.0944 -169.625 243.493,
+                          68.488 -162.467 187.75,
+                          77.3071 150.498 187.746,
+                          82 136.895 187.75,
+                          82 136.792 243.5,
+                          75.6246 149.094 243.493,
+                          82 136.792 243.5,
+                          82 136.689 299.25,
+                          77.3071 150.498 187.746,
+                          82 136.792 243.5,
+                          75.6246 149.094 243.493,
+                          75.6246 149.094 243.493,
+                          82 136.689 299.25,
+                          73.9532 147.692 299.24,
+                          42.689 176 299.25,
+                          55.0703 169.64 243.493,
+                          53.6698 167.971 299.24,
+                          66.4052 160.426 243.5,
+                          53.6698 167.971 299.24,
+                          55.0703 169.64 243.493,
+                          66.4052 160.426 243.5,
+                          64.3436 158.364 299.25,
+                          53.6698 167.971 299.24,
+                          42.7922 176 243.5,
+                          56.4716 171.321 187.746,
+                          55.0703 169.64 243.493,
+                          68.4668 162.488 187.75,
+                          55.0703 169.64 243.493,
+                          56.4716 171.321 187.746,
+                          42.689 176 299.25,
+                          42.7922 176 243.5,
+                          55.0703 169.64 243.493,
+                          68.4668 162.488 187.75,
+                          66.4052 160.426 243.5,
+                          55.0703 169.64 243.493,
+                          42.7922 176 243.5,
+                          42.8954 176 187.75,
+                          56.4716 171.321 187.746,
+                          73.9532 147.692 299.24,
+                          64.3436 158.364 299.25,
+                          66.4052 160.426 243.5,
+                          75.6246 149.094 243.493,
+                          66.4052 160.426 243.5,
+                          68.4668 162.488 187.75,
+                          75.6246 149.094 243.493,
+                          73.9532 147.692 299.24,
+                          66.4052 160.426 243.5,
+                          77.3071 150.498 187.746,
+                          75.6246 149.094 243.493,
+                          68.4668 162.488 187.75 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.70202 0.529276 0.260944
+    }
+    Separator {
+        Normal {
+            vector      [ -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          0.707107 1.21323e-16 0.707107,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -0.707107 -3.09974e-16 0.707107,
+                          -0.707107 -3.09974e-16 0.707107,
+                          4.44089e-16 -1.33397e-16 1,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          4.44089e-16 -1.33397e-16 1,
+                          -0.707107 -3.09974e-16 0.707107,
+                          4.44089e-16 -1.33397e-16 1,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          0.707107 1.21323e-16 0.707107,
+                          0.707107 1.21323e-16 0.707107,
+                          1 3.04973e-16 -3.82859e-16,
+                          0.707107 1.21323e-16 0.707107,
+                          4.44089e-16 -1.33397e-16 1,
+                          0.707107 1.21323e-16 0.707107,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          1 3.04973e-16 -3.82859e-16,
+                          1 3.04973e-16 -3.82859e-16,
+                          0.707107 3.09974e-16 -0.707107,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          0.707107 1.21323e-16 0.707107,
+                          1 3.04973e-16 -3.82859e-16,
+                          1 3.04973e-16 -3.82859e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          0.707107 3.09974e-16 -0.707107,
+                          0.707107 3.09974e-16 -0.707107,
+                          -3.21629e-16 1.33397e-16 -1,
+                          1 3.04973e-16 -3.82859e-16,
+                          0.707107 3.09974e-16 -0.707107,
+                          0.707107 3.09974e-16 -0.707107,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -5.6655e-16 1.33397e-16 -1,
+                          -5.6655e-16 1.33397e-16 -1,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          0.707107 3.09974e-16 -0.707107,
+                          -3.21629e-16 1.33397e-16 -1,
+                          -3.21629e-16 1.33397e-16 -1,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          -1 -3.04973e-16 5.0532e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          -5.6655e-16 1.33397e-16 -1,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -1 -3.04973e-16 5.0532e-16,
+                          -1 -3.04973e-16 5.0532e-16,
+                          -0.707107 -3.09974e-16 0.707107,
+                          -1 -3.04973e-16 5.0532e-16,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          -1 -3.04973e-16 5.0532e-16,
+                          -0.707107 -3.09974e-16 0.707107,
+                          -1 -3.04973e-16 5.0532e-16,
+                          -0.707107 -3.09974e-16 0.707107,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          0.707107 1.21323e-16 0.707107,
+                          0.707107 1.21323e-16 0.707107,
+                          0.707107 1.21323e-16 0.707107,
+                          0.707107 1.21323e-16 0.707107,
+                          0.707107 1.21323e-16 0.707107,
+                          0.707107 1.21323e-16 0.707107,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          -0.707107 -3.09974e-16 0.707107,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          0.707107 1.21323e-16 0.707107,
+                          0.707107 1.21323e-16 0.707107,
+                          4.44089e-16 -1.33397e-16 1,
+                          0.707107 1.21323e-16 0.707107,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          -0.707107 -3.09974e-16 0.707107,
+                          -0.707107 -3.09974e-16 0.707107,
+                          -1 -3.04973e-16 -1.60814e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          -0.707107 -3.09974e-16 0.707107,
+                          4.44089e-16 -1.33397e-16 1,
+                          -0.707107 -3.09974e-16 0.707107,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          -1 -3.04973e-16 5.0532e-16,
+                          -1 -3.04973e-16 -1.60814e-16,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          -0.707107 -3.09974e-16 0.707107,
+                          -1 -3.04973e-16 -1.60814e-16,
+                          -1 -3.04973e-16 5.0532e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          -5.6655e-16 1.33397e-16 -1,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          -1 -3.04973e-16 5.0532e-16,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          -3.21629e-16 1.33397e-16 -1,
+                          -3.21629e-16 1.33397e-16 -1,
+                          0.707107 3.09974e-16 -0.707107,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          -5.6655e-16 1.33397e-16 -1,
+                          -5.6655e-16 1.33397e-16 -1,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          0.707107 3.09974e-16 -0.707107,
+                          0.707107 3.09974e-16 -0.707107,
+                          1 3.04973e-16 6.12303e-17,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          -3.21629e-16 1.33397e-16 -1,
+                          0.707107 3.09974e-16 -0.707107,
+                          0.707107 3.09974e-16 -0.707107,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          1 3.04973e-16 -3.82859e-16,
+                          1 3.04973e-16 6.12303e-17,
+                          0.707107 1.21323e-16 0.707107,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          0.707107 3.09974e-16 -0.707107,
+                          1 3.04973e-16 6.12303e-17,
+                          1 3.04973e-16 -3.82859e-16,
+                          1 3.04973e-16 -3.82859e-16,
+                          0.707107 1.21323e-16 0.707107,
+                          0.707107 1.21323e-16 0.707107,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -47 -36.5 583.5,
+                          -40.0097 -36.5 596.989,
+                          -34 -36.5 594.5,
+                          -34 -37.5 594.5,
+                          -34 -36.5 594.5,
+                          -40.0097 -36.5 596.989,
+                          4.26326e-14 -36.5 548,
+                          -34 -36.5 594.5,
+                          -27.9903 -36.5 596.989,
+                          -27.9896 -37.5 596.99,
+                          -27.9903 -36.5 596.989,
+                          -34 -36.5 594.5,
+                          4.26326e-14 -36.5 548,
+                          -47 -36.5 583.5,
+                          -34 -36.5 594.5,
+                          -34 -37.5 594.5,
+                          -27.9896 -37.5 596.99,
+                          -34 -36.5 594.5,
+                          -47 -36.5 583.5,
+                          -42.4998 -36.5 603,
+                          -40.0097 -36.5 596.989,
+                          -40.0104 -37.5 596.99,
+                          -40.0097 -36.5 596.989,
+                          -42.4998 -36.5 603,
+                          -40.0104 -37.5 596.99,
+                          -34 -37.5 594.5,
+                          -40.0097 -36.5 596.989,
+                          -47 -36.5 616,
+                          -40.0097 -36.5 609.011,
+                          -42.4998 -36.5 603,
+                          -42.5 -37.5 603,
+                          -42.4998 -36.5 603,
+                          -40.0097 -36.5 609.011,
+                          -47 -36.5 583.5,
+                          -47 -36.5 616,
+                          -42.4998 -36.5 603,
+                          -40.0104 -37.5 596.99,
+                          -42.4998 -36.5 603,
+                          -42.5 -37.5 603,
+                          -47 -36.5 616,
+                          -34 -36.5 611.5,
+                          -40.0097 -36.5 609.011,
+                          -40.0104 -37.5 609.01,
+                          -40.0097 -36.5 609.011,
+                          -34 -36.5 611.5,
+                          -42.5 -37.5 603,
+                          -40.0097 -36.5 609.011,
+                          -40.0104 -37.5 609.01,
+                          -22 -36.5 611,
+                          -27.9903 -36.5 609.011,
+                          -34 -36.5 611.5,
+                          -34 -37.5 611.5,
+                          -34 -36.5 611.5,
+                          -27.9903 -36.5 609.011,
+                          -22 -36.5 611,
+                          -34 -36.5 611.5,
+                          -47 -36.5 616,
+                          -40.0104 -37.5 609.01,
+                          -34 -36.5 611.5,
+                          -34 -37.5 611.5,
+                          4.26326e-14 -36.5 548,
+                          -25.5002 -36.5 603,
+                          -27.9903 -36.5 609.011,
+                          -27.9896 -37.5 609.01,
+                          -27.9903 -36.5 609.011,
+                          -25.5002 -36.5 603,
+                          -22 -36.5 611,
+                          4.26326e-14 -36.5 548,
+                          -27.9903 -36.5 609.011,
+                          -27.9896 -37.5 609.01,
+                          -34 -37.5 611.5,
+                          -27.9903 -36.5 609.011,
+                          4.26326e-14 -36.5 548,
+                          -27.9903 -36.5 596.989,
+                          -25.5002 -36.5 603,
+                          -25.5 -37.5 603,
+                          -25.5002 -36.5 603,
+                          -27.9903 -36.5 596.989,
+                          -25.5 -37.5 603,
+                          -27.9896 -37.5 609.01,
+                          -25.5002 -36.5 603,
+                          -27.9896 -37.5 596.99,
+                          -25.5 -37.5 603,
+                          -27.9903 -36.5 596.989,
+                          -22 -36.5 611,
+                          -47 -36.5 616,
+                          -27 -36.5 616,
+                          -27 -42.5 616,
+                          -27 -36.5 616,
+                          -47 -36.5 616,
+                          -22 -42.5 611,
+                          -22 -36.5 611,
+                          -27 -36.5 616,
+                          -22 -42.5 611,
+                          -27 -36.5 616,
+                          -27 -42.5 616,
+                          -47 -42.5 616,
+                          -47 -36.5 616,
+                          -47 -36.5 583.5,
+                          -47 -42.5 616,
+                          -27 -42.5 616,
+                          -47 -36.5 616,
+                          4.26326e-14 -36.5 548,
+                          -56 -36.5 583.5,
+                          -47 -36.5 583.5,
+                          -47 -42.5 583.5,
+                          -47 -36.5 583.5,
+                          -56 -36.5 583.5,
+                          -47 -42.5 616,
+                          -47 -36.5 583.5,
+                          -47 -42.5 583.5,
+                          -47 -36.5 577.5,
+                          -56 -36.5 577.5,
+                          -56 -36.5 583.5,
+                          -56 -42.5 577.5,
+                          -56 -36.5 583.5,
+                          -56 -36.5 577.5,
+                          4.26326e-14 -36.5 548,
+                          -47 -36.5 577.5,
+                          -56 -36.5 583.5,
+                          -56 -42.5 583.5,
+                          -56 -36.5 583.5,
+                          -56 -42.5 577.5,
+                          -47 -42.5 583.5,
+                          -56 -36.5 583.5,
+                          -56 -42.5 583.5,
+                          -56 -42.5 577.5,
+                          -56 -36.5 577.5,
+                          -47 -36.5 577.5,
+                          4.26326e-14 -36.5 548,
+                          -47 -36.5 548,
+                          -47 -36.5 577.5,
+                          -47 -42.5 577.5,
+                          -47 -36.5 577.5,
+                          -47 -36.5 548,
+                          -56 -42.5 577.5,
+                          -47 -36.5 577.5,
+                          -47 -42.5 577.5,
+                          -47 -42.5 548,
+                          -47 -36.5 548,
+                          4.26326e-14 -36.5 548,
+                          -47 -42.5 577.5,
+                          -47 -36.5 548,
+                          -47 -42.5 548,
+                          -22 -36.5 611,
+                          7.10543e-14 -36.5 611,
+                          4.26326e-14 -36.5 548,
+                          4.9738e-14 -42.5 548,
+                          4.26326e-14 -36.5 548,
+                          7.10543e-14 -36.5 611,
+                          -47 -42.5 548,
+                          4.26326e-14 -36.5 548,
+                          4.9738e-14 -42.5 548,
+                          7.81597e-14 -42.5 611,
+                          7.10543e-14 -36.5 611,
+                          -22 -36.5 611,
+                          4.9738e-14 -42.5 548,
+                          7.10543e-14 -36.5 611,
+                          7.81597e-14 -42.5 611,
+                          7.81597e-14 -42.5 611,
+                          -22 -36.5 611,
+                          -22 -42.5 611,
+                          -47 -42.5 583.5,
+                          -27.2833 -42.5 596.282,
+                          -34 -42.5 593.5,
+                          -34 -37.5 593.5,
+                          -34 -42.5 593.5,
+                          -27.2833 -42.5 596.282,
+                          -47 -42.5 583.5,
+                          -34 -42.5 593.5,
+                          -40.7167 -42.5 596.282,
+                          -40.7175 -37.5 596.282,
+                          -40.7167 -42.5 596.282,
+                          -34 -42.5 593.5,
+                          -40.7175 -37.5 596.282,
+                          -34 -42.5 593.5,
+                          -34 -37.5 593.5,
+                          7.81597e-14 -42.5 611,
+                          -24.5003 -42.5 603,
+                          -27.2833 -42.5 596.282,
+                          -27.2825 -37.5 596.282,
+                          -27.2833 -42.5 596.282,
+                          -24.5003 -42.5 603,
+                          -47 -42.5 583.5,
+                          7.81597e-14 -42.5 611,
+                          -27.2833 -42.5 596.282,
+                          -27.2825 -37.5 596.282,
+                          -34 -37.5 593.5,
+                          -27.2833 -42.5 596.282,
+                          7.81597e-14 -42.5 611,
+                          -27.2833 -42.5 609.718,
+                          -24.5003 -42.5 603,
+                          -24.5 -37.5 603,
+                          -24.5003 -42.5 603,
+                          -27.2833 -42.5 609.718,
+                          -27.2825 -37.5 596.282,
+                          -24.5003 -42.5 603,
+                          -24.5 -37.5 603,
+                          -22 -42.5 611,
+                          -34 -42.5 612.5,
+                          -27.2833 -42.5 609.718,
+                          -27.2825 -37.5 609.718,
+                          -27.2833 -42.5 609.718,
+                          -34 -42.5 612.5,
+                          7.81597e-14 -42.5 611,
+                          -22 -42.5 611,
+                          -27.2833 -42.5 609.718,
+                          -24.5 -37.5 603,
+                          -27.2833 -42.5 609.718,
+                          -27.2825 -37.5 609.718,
+                          -27 -42.5 616,
+                          -40.7167 -42.5 609.718,
+                          -34 -42.5 612.5,
+                          -34 -37.5 612.5,
+                          -34 -42.5 612.5,
+                          -40.7167 -42.5 609.718,
+                          -22 -42.5 611,
+                          -27 -42.5 616,
+                          -34 -42.5 612.5,
+                          -27.2825 -37.5 609.718,
+                          -34 -42.5 612.5,
+                          -34 -37.5 612.5,
+                          -47 -42.5 616,
+                          -43.4997 -42.5 603,
+                          -40.7167 -42.5 609.718,
+                          -40.7175 -37.5 609.718,
+                          -40.7167 -42.5 609.718,
+                          -43.4997 -42.5 603,
+                          -47 -42.5 616,
+                          -40.7167 -42.5 609.718,
+                          -27 -42.5 616,
+                          -34 -37.5 612.5,
+                          -40.7167 -42.5 609.718,
+                          -40.7175 -37.5 609.718,
+                          -47 -42.5 583.5,
+                          -40.7167 -42.5 596.282,
+                          -43.4997 -42.5 603,
+                          -43.5 -37.5 603,
+                          -43.4997 -42.5 603,
+                          -40.7167 -42.5 596.282,
+                          -47 -42.5 616,
+                          -47 -42.5 583.5,
+                          -43.4997 -42.5 603,
+                          -40.7175 -37.5 609.718,
+                          -43.4997 -42.5 603,
+                          -43.5 -37.5 603,
+                          -43.5 -37.5 603,
+                          -40.7167 -42.5 596.282,
+                          -40.7175 -37.5 596.282,
+                          -47 -42.5 548,
+                          4.9738e-14 -42.5 548,
+                          7.81597e-14 -42.5 611,
+                          -47 -42.5 577.5,
+                          -47 -42.5 548,
+                          7.81597e-14 -42.5 611,
+                          -56 -42.5 577.5,
+                          -47 -42.5 577.5,
+                          7.81597e-14 -42.5 611,
+                          -47 -42.5 583.5,
+                          -56 -42.5 577.5,
+                          7.81597e-14 -42.5 611,
+                          -47 -42.5 583.5,
+                          -56 -42.5 583.5,
+                          -56 -42.5 577.5,
+                          -34 -37.5 612.5,
+                          -34 -37.5 611.5,
+                          -27.9896 -37.5 609.01,
+                          -40.7175 -37.5 609.718,
+                          -40.0104 -37.5 609.01,
+                          -34 -37.5 611.5,
+                          -34 -37.5 612.5,
+                          -40.7175 -37.5 609.718,
+                          -34 -37.5 611.5,
+                          -27.2825 -37.5 609.718,
+                          -27.9896 -37.5 609.01,
+                          -25.5 -37.5 603,
+                          -27.2825 -37.5 609.718,
+                          -34 -37.5 612.5,
+                          -27.9896 -37.5 609.01,
+                          -27.2825 -37.5 596.282,
+                          -25.5 -37.5 603,
+                          -27.9896 -37.5 596.99,
+                          -24.5 -37.5 603,
+                          -27.2825 -37.5 609.718,
+                          -25.5 -37.5 603,
+                          -27.2825 -37.5 596.282,
+                          -24.5 -37.5 603,
+                          -25.5 -37.5 603,
+                          -27.2825 -37.5 596.282,
+                          -27.9896 -37.5 596.99,
+                          -34 -37.5 594.5,
+                          -34 -37.5 593.5,
+                          -34 -37.5 594.5,
+                          -40.0104 -37.5 596.99,
+                          -27.2825 -37.5 596.282,
+                          -34 -37.5 594.5,
+                          -34 -37.5 593.5,
+                          -40.7175 -37.5 609.718,
+                          -42.5 -37.5 603,
+                          -40.0104 -37.5 609.01,
+                          -40.7175 -37.5 596.282,
+                          -40.0104 -37.5 596.99,
+                          -42.5 -37.5 603,
+                          -43.5 -37.5 603,
+                          -40.7175 -37.5 596.282,
+                          -42.5 -37.5 603,
+                          -40.7175 -37.5 609.718,
+                          -43.5 -37.5 603,
+                          -42.5 -37.5 603,
+                          -40.7175 -37.5 596.282,
+                          -34 -37.5 593.5,
+                          -40.0104 -37.5 596.99 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+    Separator {
+        Normal {
+            vector      [ 3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          0.707107 3.09974e-16 -0.707107,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          -4.44089e-16 1.33397e-16 -1,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          0.707107 3.09974e-16 -0.707107,
+                          0.707107 3.09974e-16 -0.707107,
+                          1 3.04973e-16 -5.0532e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          0.707107 3.09974e-16 -0.707107,
+                          -4.44089e-16 1.33397e-16 -1,
+                          0.707107 3.09974e-16 -0.707107,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          1 3.04973e-16 -5.0532e-16,
+                          1 3.04973e-16 -5.0532e-16,
+                          0.707107 1.21323e-16 0.707107,
+                          0.707107 3.09974e-16 -0.707107,
+                          1 3.04973e-16 -5.0532e-16,
+                          1 3.04973e-16 -5.0532e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          0.707107 1.21323e-16 0.707107,
+                          0.707107 1.21323e-16 0.707107,
+                          5.6655e-16 -1.33397e-16 1,
+                          1 3.04973e-16 -5.0532e-16,
+                          0.707107 1.21323e-16 0.707107,
+                          0.707107 1.21323e-16 0.707107,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.21629e-16 -1.33397e-16 1,
+                          3.21629e-16 -1.33397e-16 1,
+                          -0.707107 -3.09974e-16 0.707107,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          0.707107 1.21323e-16 0.707107,
+                          5.6655e-16 -1.33397e-16 1,
+                          5.6655e-16 -1.33397e-16 1,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          -0.707107 -3.09974e-16 0.707107,
+                          -0.707107 -3.09974e-16 0.707107,
+                          -1 -3.04973e-16 3.82859e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.21629e-16 -1.33397e-16 1,
+                          -0.707107 -3.09974e-16 0.707107,
+                          -0.707107 -3.09974e-16 0.707107,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          -1 -3.04973e-16 3.82859e-16,
+                          -1 -3.04973e-16 3.82859e-16,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          -0.707107 -3.09974e-16 0.707107,
+                          -1 -3.04973e-16 3.82859e-16,
+                          -1 -3.04973e-16 3.82859e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          -1 -3.04973e-16 3.82859e-16,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          -0.707107 -3.09974e-16 0.707107,
+                          -0.707107 -3.09974e-16 0.707107,
+                          -0.707107 -3.09974e-16 0.707107,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          -0.707107 -3.09974e-16 0.707107,
+                          -0.707107 -3.09974e-16 0.707107,
+                          -0.707107 -3.09974e-16 0.707107,
+                          0.707107 1.21323e-16 0.707107,
+                          0.707107 1.21323e-16 0.707107,
+                          0.707107 1.21323e-16 0.707107,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          0.707107 1.21323e-16 0.707107,
+                          0.707107 1.21323e-16 0.707107,
+                          0.707107 1.21323e-16 0.707107,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          0.707107 3.09974e-16 -0.707107,
+                          0.707107 3.09974e-16 -0.707107,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          0.707107 3.09974e-16 -0.707107,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          -1 -3.04973e-16 8.26948e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -1 -3.04973e-16 3.82859e-16,
+                          -1 -3.04973e-16 8.26948e-16,
+                          -0.707107 -3.09974e-16 0.707107,
+                          -0.707107 -1.21323e-16 -0.707107,
+                          -1 -3.04973e-16 8.26948e-16,
+                          -1 -3.04973e-16 3.82859e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -0.707107 -3.09974e-16 0.707107,
+                          -0.707107 -3.09974e-16 0.707107,
+                          3.21629e-16 -1.33397e-16 1,
+                          -1 -3.04973e-16 3.82859e-16,
+                          -0.707107 -3.09974e-16 0.707107,
+                          -0.707107 -3.09974e-16 0.707107,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          5.6655e-16 -1.33397e-16 1,
+                          5.6655e-16 -1.33397e-16 1,
+                          0.707107 1.21323e-16 0.707107,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -0.707107 -3.09974e-16 0.707107,
+                          3.21629e-16 -1.33397e-16 1,
+                          3.21629e-16 -1.33397e-16 1,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          0.707107 1.21323e-16 0.707107,
+                          0.707107 1.21323e-16 0.707107,
+                          1 3.04973e-16 -9.49409e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          5.6655e-16 -1.33397e-16 1,
+                          0.707107 1.21323e-16 0.707107,
+                          0.707107 1.21323e-16 0.707107,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          1 3.04973e-16 -5.0532e-16,
+                          1 3.04973e-16 -9.49409e-16,
+                          0.707107 3.09974e-16 -0.707107,
+                          0.707107 1.21323e-16 0.707107,
+                          1 3.04973e-16 -9.49409e-16,
+                          1 3.04973e-16 -5.0532e-16,
+                          1 3.04973e-16 -5.0532e-16,
+                          0.707107 3.09974e-16 -0.707107,
+                          0.707107 3.09974e-16 -0.707107,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -47 36.5 610,
+                          -40.0097 36.5 609.011,
+                          -34 36.5 611.5,
+                          -34 37.5 611.5,
+                          -34 36.5 611.5,
+                          -40.0097 36.5 609.011,
+                          -22 36.5 611,
+                          -34 36.5 611.5,
+                          -27.9903 36.5 609.011,
+                          -27.9896 37.5 609.01,
+                          -27.9903 36.5 609.011,
+                          -34 36.5 611.5,
+                          -27 36.5 616,
+                          -47 36.5 610,
+                          -34 36.5 611.5,
+                          -22 36.5 611,
+                          -27 36.5 616,
+                          -34 36.5 611.5,
+                          -27.9896 37.5 609.01,
+                          -34 36.5 611.5,
+                          -34 37.5 611.5,
+                          -47 36.5 596,
+                          -42.4998 36.5 603,
+                          -40.0097 36.5 609.011,
+                          -40.0104 37.5 609.01,
+                          -40.0097 36.5 609.011,
+                          -42.4998 36.5 603,
+                          -47 36.5 610,
+                          -47 36.5 596,
+                          -40.0097 36.5 609.011,
+                          -40.0104 37.5 609.01,
+                          -34 37.5 611.5,
+                          -40.0097 36.5 609.011,
+                          -47 36.5 596,
+                          -40.0097 36.5 596.989,
+                          -42.4998 36.5 603,
+                          -42.5 37.5 603,
+                          -42.4998 36.5 603,
+                          -40.0097 36.5 596.989,
+                          -40.0104 37.5 609.01,
+                          -42.4998 36.5 603,
+                          -42.5 37.5 603,
+                          -47 36.5 596,
+                          -34 36.5 594.5,
+                          -40.0097 36.5 596.989,
+                          -40.0104 37.5 596.99,
+                          -40.0097 36.5 596.989,
+                          -34 36.5 594.5,
+                          -42.5 37.5 603,
+                          -40.0097 36.5 596.989,
+                          -40.0104 37.5 596.99,
+                          -30 36.5 579,
+                          -27.9903 36.5 596.989,
+                          -34 36.5 594.5,
+                          -34 37.5 594.5,
+                          -34 36.5 594.5,
+                          -27.9903 36.5 596.989,
+                          -47 36.5 596,
+                          -30 36.5 579,
+                          -34 36.5 594.5,
+                          -40.0104 37.5 596.99,
+                          -34 36.5 594.5,
+                          -34 37.5 594.5,
+                          4.9738e-14 36.5 611,
+                          -25.5002 36.5 603,
+                          -27.9903 36.5 596.989,
+                          -27.9896 37.5 596.99,
+                          -27.9903 36.5 596.989,
+                          -25.5002 36.5 603,
+                          4.9738e-14 36.5 611,
+                          -27.9903 36.5 596.989,
+                          -30 36.5 579,
+                          -34 37.5 594.5,
+                          -27.9903 36.5 596.989,
+                          -27.9896 37.5 596.99,
+                          4.9738e-14 36.5 611,
+                          -27.9903 36.5 609.011,
+                          -25.5002 36.5 603,
+                          -25.5 37.5 603,
+                          -25.5002 36.5 603,
+                          -27.9903 36.5 609.011,
+                          -27.9896 37.5 596.99,
+                          -25.5002 36.5 603,
+                          -25.5 37.5 603,
+                          4.9738e-14 36.5 611,
+                          -22 36.5 611,
+                          -27.9903 36.5 609.011,
+                          -25.5 37.5 603,
+                          -27.9903 36.5 609.011,
+                          -27.9896 37.5 609.01,
+                          4.9738e-14 36.5 611,
+                          -30 36.5 548,
+                          2.13163e-14 36.5 548,
+                          1.42109e-14 42.5 548,
+                          2.13163e-14 36.5 548,
+                          -30 36.5 548,
+                          4.26326e-14 42.5 611,
+                          4.9738e-14 36.5 611,
+                          2.13163e-14 36.5 548,
+                          1.42109e-14 42.5 548,
+                          4.26326e-14 42.5 611,
+                          2.13163e-14 36.5 548,
+                          4.9738e-14 36.5 611,
+                          -30 36.5 579,
+                          -30 36.5 548,
+                          -30 42.5 548,
+                          -30 36.5 548,
+                          -30 36.5 579,
+                          1.42109e-14 42.5 548,
+                          -30 36.5 548,
+                          -30 42.5 548,
+                          -30 42.5 579,
+                          -30 36.5 579,
+                          -47 36.5 596,
+                          -30 42.5 548,
+                          -30 36.5 579,
+                          -30 42.5 579,
+                          -47 42.5 596,
+                          -47 36.5 596,
+                          -47 36.5 610,
+                          -30 42.5 579,
+                          -47 36.5 596,
+                          -47 42.5 596,
+                          -27 36.5 616,
+                          -41 36.5 616,
+                          -47 36.5 610,
+                          -47 42.5 610,
+                          -47 36.5 610,
+                          -41 36.5 616,
+                          -47 42.5 596,
+                          -47 36.5 610,
+                          -47 42.5 610,
+                          -41 42.5 616,
+                          -41 36.5 616,
+                          -27 36.5 616,
+                          -47 42.5 610,
+                          -41 36.5 616,
+                          -41 42.5 616,
+                          -27 42.5 616,
+                          -27 36.5 616,
+                          -22 36.5 611,
+                          -41 42.5 616,
+                          -27 36.5 616,
+                          -27 42.5 616,
+                          -22 42.5 611,
+                          -22 36.5 611,
+                          4.9738e-14 36.5 611,
+                          -27 42.5 616,
+                          -22 36.5 611,
+                          -22 42.5 611,
+                          -22 42.5 611,
+                          4.9738e-14 36.5 611,
+                          4.26326e-14 42.5 611,
+                          -22 42.5 611,
+                          -27.2826 42.5 609.717,
+                          -34 42.5 612.5,
+                          -34 37.5 612.5,
+                          -34 42.5 612.5,
+                          -27.2826 42.5 609.717,
+                          -47 42.5 610,
+                          -34 42.5 612.5,
+                          -40.7174 42.5 609.717,
+                          -40.7167 37.5 609.718,
+                          -40.7174 42.5 609.717,
+                          -34 42.5 612.5,
+                          -41 42.5 616,
+                          -22 42.5 611,
+                          -34 42.5 612.5,
+                          -47 42.5 610,
+                          -41 42.5 616,
+                          -34 42.5 612.5,
+                          -40.7167 37.5 609.718,
+                          -34 42.5 612.5,
+                          -34 37.5 612.5,
+                          1.42109e-14 42.5 548,
+                          -24.5 42.5 603,
+                          -27.2826 42.5 609.717,
+                          -27.2833 37.5 609.718,
+                          -27.2826 42.5 609.717,
+                          -24.5 42.5 603,
+                          1.42109e-14 42.5 548,
+                          -27.2826 42.5 609.717,
+                          -22 42.5 611,
+                          -27.2833 37.5 609.718,
+                          -34 37.5 612.5,
+                          -27.2826 42.5 609.717,
+                          1.42109e-14 42.5 548,
+                          -27.2826 42.5 596.283,
+                          -24.5 42.5 603,
+                          -24.5003 37.5 603,
+                          -24.5 42.5 603,
+                          -27.2826 42.5 596.283,
+                          -27.2833 37.5 609.718,
+                          -24.5 42.5 603,
+                          -24.5003 37.5 603,
+                          1.42109e-14 42.5 548,
+                          -34 42.5 593.5,
+                          -27.2826 42.5 596.283,
+                          -27.2833 37.5 596.282,
+                          -27.2826 42.5 596.283,
+                          -34 42.5 593.5,
+                          -24.5003 37.5 603,
+                          -27.2826 42.5 596.283,
+                          -27.2833 37.5 596.282,
+                          -47 42.5 596,
+                          -40.7174 42.5 596.283,
+                          -34 42.5 593.5,
+                          -34 37.5 593.5,
+                          -34 42.5 593.5,
+                          -40.7174 42.5 596.283,
+                          -30 42.5 579,
+                          -47 42.5 596,
+                          -34 42.5 593.5,
+                          1.42109e-14 42.5 548,
+                          -30 42.5 579,
+                          -34 42.5 593.5,
+                          -27.2833 37.5 596.282,
+                          -34 42.5 593.5,
+                          -34 37.5 593.5,
+                          -47 42.5 610,
+                          -43.5 42.5 603,
+                          -40.7174 42.5 596.283,
+                          -40.7167 37.5 596.282,
+                          -40.7174 42.5 596.283,
+                          -43.5 42.5 603,
+                          -47 42.5 596,
+                          -47 42.5 610,
+                          -40.7174 42.5 596.283,
+                          -34 37.5 593.5,
+                          -40.7174 42.5 596.283,
+                          -40.7167 37.5 596.282,
+                          -47 42.5 610,
+                          -40.7174 42.5 609.717,
+                          -43.5 42.5 603,
+                          -43.4997 37.5 603,
+                          -43.5 42.5 603,
+                          -40.7174 42.5 609.717,
+                          -40.7167 37.5 596.282,
+                          -43.5 42.5 603,
+                          -43.4997 37.5 603,
+                          -43.4997 37.5 603,
+                          -40.7174 42.5 609.717,
+                          -40.7167 37.5 609.718,
+                          1.42109e-14 42.5 548,
+                          -22 42.5 611,
+                          4.26326e-14 42.5 611,
+                          -41 42.5 616,
+                          -27 42.5 616,
+                          -22 42.5 611,
+                          1.42109e-14 42.5 548,
+                          -30 42.5 548,
+                          -30 42.5 579,
+                          -27.2833 37.5 609.718,
+                          -27.9896 37.5 609.01,
+                          -34 37.5 611.5,
+                          -34 37.5 612.5,
+                          -34 37.5 611.5,
+                          -40.0104 37.5 609.01,
+                          -27.2833 37.5 609.718,
+                          -34 37.5 611.5,
+                          -34 37.5 612.5,
+                          -27.2833 37.5 609.718,
+                          -25.5 37.5 603,
+                          -27.9896 37.5 609.01,
+                          -27.2833 37.5 596.282,
+                          -27.9896 37.5 596.99,
+                          -25.5 37.5 603,
+                          -24.5003 37.5 603,
+                          -27.2833 37.5 596.282,
+                          -25.5 37.5 603,
+                          -27.2833 37.5 609.718,
+                          -24.5003 37.5 603,
+                          -25.5 37.5 603,
+                          -34 37.5 593.5,
+                          -34 37.5 594.5,
+                          -27.9896 37.5 596.99,
+                          -27.2833 37.5 596.282,
+                          -34 37.5 593.5,
+                          -27.9896 37.5 596.99,
+                          -40.7167 37.5 596.282,
+                          -40.0104 37.5 596.99,
+                          -34 37.5 594.5,
+                          -34 37.5 593.5,
+                          -40.7167 37.5 596.282,
+                          -34 37.5 594.5,
+                          -40.7167 37.5 596.282,
+                          -42.5 37.5 603,
+                          -40.0104 37.5 596.99,
+                          -40.7167 37.5 609.718,
+                          -40.0104 37.5 609.01,
+                          -42.5 37.5 603,
+                          -43.4997 37.5 603,
+                          -40.7167 37.5 609.718,
+                          -42.5 37.5 603,
+                          -40.7167 37.5 596.282,
+                          -43.4997 37.5 603,
+                          -42.5 37.5 603,
+                          -40.7167 37.5 609.718,
+                          -34 37.5 612.5,
+                          -40.0104 37.5 609.01 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.8784 0.949 1
+    }
+    Separator {
+        Normal {
+            vector      [ 4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          0.649345 0.760494 -1.8692e-16,
+                          0.649345 0.760494 -1.8692e-16,
+                          0.649345 0.760494 -1.8692e-16,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          -3.04973e-16 1 1.33397e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          0.649345 0.760494 -1.8692e-16,
+                          0.649345 0.760494 -1.8692e-16,
+                          0.649345 0.760494 -1.8692e-16,
+                          0.649345 -0.760494 -3.89814e-16,
+                          0.649345 -0.760494 -3.89814e-16,
+                          0.649345 -0.760494 -3.89814e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          1 3.04973e-16 -4.44089e-16,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          0.649345 -0.760494 -3.89814e-16,
+                          0.649345 -0.760494 -3.89814e-16,
+                          0.649345 -0.760494 -3.89814e-16,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          -0.427094 -0.904207 6.90494e-17,
+                          -0.427094 -0.904207 6.90494e-17,
+                          -0.427094 -0.904207 6.90494e-17,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          4.44089e-16 -1.33397e-16 1,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          3.04973e-16 -1 -1.33397e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -0.427094 -0.904207 6.90494e-17,
+                          -0.427094 -0.904207 6.90494e-17,
+                          -0.427094 -0.904207 6.90494e-17,
+                          -0.327719 0.944775 2.71566e-16,
+                          -0.327719 0.944775 2.71566e-16,
+                          -0.327719 0.944775 2.71566e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -1 -3.04973e-16 4.44089e-16,
+                          -0.327719 0.944775 2.71566e-16,
+                          -0.327719 0.944775 2.71566e-16,
+                          -0.327719 0.944775 2.71566e-16,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1,
+                          -4.44089e-16 1.33397e-16 -1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ 26 -20 548,
+                          26 20 548,
+                          1.42109e-14 42.2 548,
+                          1.42109e-14 42.2 540,
+                          1.42109e-14 42.2 548,
+                          26 20 548,
+                          4.26326e-14 -42.2 548,
+                          26 -20 548,
+                          1.42109e-14 42.2 548,
+                          -30 42.2 548,
+                          4.26326e-14 -42.2 548,
+                          1.42109e-14 42.2 548,
+                          -30 42.2 540,
+                          -30 42.2 548,
+                          1.42109e-14 42.2 548,
+                          -30 42.2 540,
+                          1.42109e-14 42.2 548,
+                          1.42109e-14 42.2 540,
+                          26 20 540,
+                          26 20 548,
+                          26 -20 548,
+                          26 20 540,
+                          1.42109e-14 42.2 540,
+                          26 20 548,
+                          26 -20 540,
+                          26 -20 548,
+                          4.26326e-14 -42.2 548,
+                          26 20 540,
+                          26 -20 548,
+                          26 -20 540,
+                          -30 42.2 548,
+                          -47 -42.2 548,
+                          4.26326e-14 -42.2 548,
+                          4.26326e-14 -42.2 540,
+                          4.26326e-14 -42.2 548,
+                          -47 -42.2 548,
+                          26 -20 540,
+                          4.26326e-14 -42.2 548,
+                          4.26326e-14 -42.2 540,
+                          -94 20 548,
+                          -94 -20 548,
+                          -47 -42.2 548,
+                          -47 -42.2 540,
+                          -47 -42.2 548,
+                          -94 -20 548,
+                          -30 42.2 548,
+                          -94 20 548,
+                          -47 -42.2 548,
+                          4.26326e-14 -42.2 540,
+                          -47 -42.2 548,
+                          -47 -42.2 540,
+                          -94 -20 540,
+                          -94 -20 548,
+                          -94 20 548,
+                          -47 -42.2 540,
+                          -94 -20 548,
+                          -94 -20 540,
+                          -94 20 540,
+                          -94 20 548,
+                          -30 42.2 548,
+                          -94 -20 540,
+                          -94 20 548,
+                          -94 20 540,
+                          -94 20 540,
+                          -30 42.2 548,
+                          -30 42.2 540,
+                          -47 -42.2 540,
+                          -30 42.2 540,
+                          1.42109e-14 42.2 540,
+                          4.26326e-14 -42.2 540,
+                          -47 -42.2 540,
+                          1.42109e-14 42.2 540,
+                          26 20 540,
+                          4.26326e-14 -42.2 540,
+                          1.42109e-14 42.2 540,
+                          -94 -20 540,
+                          -94 20 540,
+                          -30 42.2 540,
+                          -47 -42.2 540,
+                          -94 -20 540,
+                          -30 42.2 540,
+                          26 20 540,
+                          26 -20 540,
+                          4.26326e-14 -42.2 540 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3 ]
+        }
+    }
+    Material {
+        diffuseColor    0.39 0 0
+    }
+    Separator {
+        Normal {
+            vector      [ 0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          1 -1.83691e-16 0,
+                          1 -1.83691e-16 0,
+                          0.951057 0.309017 6.86156e-17,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.951057 -0.309017 -6.86156e-17,
+                          0.951057 -0.309017 -6.86156e-17,
+                          1 -1.83691e-16 0,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          1 -1.83691e-16 0,
+                          0.951057 -0.309017 -6.86156e-17,
+                          1 -1.83691e-16 0,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.951057 0.309017 6.86156e-17,
+                          0.951057 0.309017 6.86156e-17,
+                          0.809017 0.587785 1.30515e-16,
+                          0.951057 0.309017 6.86156e-17,
+                          1 -1.83691e-16 0,
+                          0.951057 0.309017 6.86156e-17,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.809017 0.587785 1.30515e-16,
+                          0.809017 0.587785 1.30515e-16,
+                          0.587785 0.809017 1.79638e-16,
+                          0.809017 0.587785 1.30515e-16,
+                          0.951057 0.309017 6.86156e-17,
+                          0.809017 0.587785 1.30515e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.587785 0.809017 1.79638e-16,
+                          0.587785 0.809017 1.79638e-16,
+                          0.309017 0.951057 2.11177e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.587785 0.809017 1.79638e-16,
+                          0.809017 0.587785 1.30515e-16,
+                          0.587785 0.809017 1.79638e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.309017 0.951057 2.11177e-16,
+                          0.309017 0.951057 2.11177e-16,
+                          2.44921e-16 1 2.22045e-16,
+                          0.309017 0.951057 2.11177e-16,
+                          0.587785 0.809017 1.79638e-16,
+                          0.309017 0.951057 2.11177e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          2.44921e-16 1 2.22045e-16,
+                          2.44921e-16 1 2.22045e-16,
+                          -0.309017 0.951057 2.11177e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          2.44921e-16 1 2.22045e-16,
+                          0.309017 0.951057 2.11177e-16,
+                          2.44921e-16 1 2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.309017 0.951057 2.11177e-16,
+                          -0.309017 0.951057 2.11177e-16,
+                          -0.587785 0.809017 1.79638e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.309017 0.951057 2.11177e-16,
+                          2.44921e-16 1 2.22045e-16,
+                          -0.309017 0.951057 2.11177e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.587785 0.809017 1.79638e-16,
+                          -0.587785 0.809017 1.79638e-16,
+                          -0.809017 0.587785 1.30515e-16,
+                          -0.587785 0.809017 1.79638e-16,
+                          -0.309017 0.951057 2.11177e-16,
+                          -0.587785 0.809017 1.79638e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.809017 0.587785 1.30515e-16,
+                          -0.809017 0.587785 1.30515e-16,
+                          -0.951057 0.309017 6.86156e-17,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.809017 0.587785 1.30515e-16,
+                          -0.587785 0.809017 1.79638e-16,
+                          -0.809017 0.587785 1.30515e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.951057 0.309017 6.86156e-17,
+                          -0.951057 0.309017 6.86156e-17,
+                          -1 3.06152e-16 0,
+                          -0.951057 0.309017 6.86156e-17,
+                          -0.809017 0.587785 1.30515e-16,
+                          -0.951057 0.309017 6.86156e-17,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -0.951057 -0.309017 -6.86156e-17,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.951057 0.309017 6.86156e-17,
+                          -1 3.06152e-16 0,
+                          -1 3.06152e-16 0,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.951057 -0.309017 -6.86156e-17,
+                          -0.951057 -0.309017 -6.86156e-17,
+                          -0.809017 -0.587785 -1.30515e-16,
+                          -0.951057 -0.309017 -6.86156e-17,
+                          -1 6.12303e-17 0,
+                          -0.951057 -0.309017 -6.86156e-17,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.809017 -0.587785 -1.30515e-16,
+                          -0.809017 -0.587785 -1.30515e-16,
+                          -0.587785 -0.809017 -1.79638e-16,
+                          -0.809017 -0.587785 -1.30515e-16,
+                          -0.951057 -0.309017 -6.86156e-17,
+                          -0.809017 -0.587785 -1.30515e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.587785 -0.809017 -1.79638e-16,
+                          -0.587785 -0.809017 -1.79638e-16,
+                          -0.309017 -0.951057 -2.11177e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.587785 -0.809017 -1.79638e-16,
+                          -0.809017 -0.587785 -1.30515e-16,
+                          -0.587785 -0.809017 -1.79638e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.309017 -0.951057 -2.11177e-16,
+                          -0.309017 -0.951057 -2.11177e-16,
+                          -1.22461e-16 -1 -2.22045e-16,
+                          -0.309017 -0.951057 -2.11177e-16,
+                          -0.587785 -0.809017 -1.79638e-16,
+                          -0.309017 -0.951057 -2.11177e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -1.22461e-16 -1 -2.22045e-16,
+                          -1.22461e-16 -1 -2.22045e-16,
+                          0.309017 -0.951057 -2.11177e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -1.22461e-16 -1 -2.22045e-16,
+                          -0.309017 -0.951057 -2.11177e-16,
+                          -1.22461e-16 -1 -2.22045e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.309017 -0.951057 -2.11177e-16,
+                          0.309017 -0.951057 -2.11177e-16,
+                          0.587785 -0.809017 -1.79638e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.309017 -0.951057 -2.11177e-16,
+                          -1.22461e-16 -1 -2.22045e-16,
+                          0.309017 -0.951057 -2.11177e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.587785 -0.809017 -1.79638e-16,
+                          0.587785 -0.809017 -1.79638e-16,
+                          0.809017 -0.587785 -1.30515e-16,
+                          0.587785 -0.809017 -1.79638e-16,
+                          0.309017 -0.951057 -2.11177e-16,
+                          0.587785 -0.809017 -1.79638e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.809017 -0.587785 -1.30515e-16,
+                          0.809017 -0.587785 -1.30515e-16,
+                          0.951057 -0.309017 -6.86156e-17,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.809017 -0.587785 -1.30515e-16,
+                          0.587785 -0.809017 -1.79638e-16,
+                          0.809017 -0.587785 -1.30515e-16,
+                          0.951057 -0.309017 -6.86156e-17,
+                          0.809017 -0.587785 -1.30515e-16,
+                          0.951057 -0.309017 -6.86156e-17,
+                          -1 1.83691e-16 0,
+                          -1 1.83691e-16 0,
+                          -0.866025 0.5 1.11022e-16,
+                          -0.866025 -0.5 -1.11022e-16,
+                          -0.866025 -0.5 -1.11022e-16,
+                          -1 1.83691e-16 0,
+                          -0.866025 -0.5 -1.11022e-16,
+                          -1 1.83691e-16 0,
+                          -1 1.83691e-16 0,
+                          -0.866025 0.5 1.11022e-16,
+                          -0.866025 0.5 1.11022e-16,
+                          -0.5 0.866025 1.92296e-16,
+                          -0.866025 0.5 1.11022e-16,
+                          -1 1.83691e-16 0,
+                          -0.866025 0.5 1.11022e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          -0.5 0.866025 1.92296e-16,
+                          -0.5 0.866025 1.92296e-16,
+                          1.22461e-16 1 2.22045e-16,
+                          -0.866025 0.5 1.11022e-16,
+                          -0.5 0.866025 1.92296e-16,
+                          -0.5 0.866025 1.92296e-16,
+                          1.22461e-16 1 2.22045e-16,
+                          1.22461e-16 1 2.22045e-16,
+                          0.5 0.866025 1.92296e-16,
+                          -0.5 0.866025 1.92296e-16,
+                          1.22461e-16 1 2.22045e-16,
+                          1.22461e-16 1 2.22045e-16,
+                          0.5 0.866025 1.92296e-16,
+                          0.5 0.866025 1.92296e-16,
+                          0.866025 0.5 1.11022e-16,
+                          1.22461e-16 1 2.22045e-16,
+                          0.5 0.866025 1.92296e-16,
+                          0.5 0.866025 1.92296e-16,
+                          0.866025 0.5 1.11022e-16,
+                          0.866025 0.5 1.11022e-16,
+                          1 -6.12303e-17 0,
+                          0.5 0.866025 1.92296e-16,
+                          0.866025 0.5 1.11022e-16,
+                          0.866025 0.5 1.11022e-16,
+                          1 -3.06152e-16 0,
+                          1 -3.06152e-16 0,
+                          0.866025 -0.5 -1.11022e-16,
+                          0.866025 0.5 1.11022e-16,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          0.866025 -0.5 -1.11022e-16,
+                          0.866025 -0.5 -1.11022e-16,
+                          0.5 -0.866025 -1.92296e-16,
+                          1 -3.06152e-16 0,
+                          0.866025 -0.5 -1.11022e-16,
+                          0.866025 -0.5 -1.11022e-16,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0.5 -0.866025 -1.92296e-16,
+                          0.5 -0.866025 -1.92296e-16,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          0.866025 -0.5 -1.11022e-16,
+                          0.5 -0.866025 -1.92296e-16,
+                          0.5 -0.866025 -1.92296e-16,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          -0.5 -0.866025 -1.92296e-16,
+                          0.5 -0.866025 -1.92296e-16,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          -0.5 -0.866025 -1.92296e-16,
+                          -0.5 -0.866025 -1.92296e-16,
+                          -0.866025 -0.5 -1.11022e-16,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          -0.5 -0.866025 -1.92296e-16,
+                          -0.5 -0.866025 -1.92296e-16,
+                          -0.5 -0.866025 -1.92296e-16,
+                          -0.866025 -0.5 -1.11022e-16,
+                          -0.866025 -0.5 -1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -1 1.83691e-16 0,
+                          -1 1.83691e-16 0,
+                          -0.866025 -0.5 -1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.866025 0.5 1.11022e-16,
+                          -0.866025 0.5 1.11022e-16,
+                          -1 1.83691e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.866025 0.5 1.11022e-16,
+                          -1 1.83691e-16 0,
+                          -1 1.83691e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.866025 -0.5 -1.11022e-16,
+                          -0.866025 -0.5 -1.11022e-16,
+                          -0.5 -0.866025 -1.92296e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.866025 -0.5 -1.11022e-16,
+                          -1 1.83691e-16 0,
+                          -0.866025 -0.5 -1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.5 -0.866025 -1.92296e-16,
+                          -0.5 -0.866025 -1.92296e-16,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.866025 -0.5 -1.11022e-16,
+                          -0.5 -0.866025 -1.92296e-16,
+                          -0.5 -0.866025 -1.92296e-16,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          0.5 -0.866025 -1.92296e-16,
+                          -0.5 -0.866025 -1.92296e-16,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.5 -0.866025 -1.92296e-16,
+                          0.5 -0.866025 -1.92296e-16,
+                          0.866025 -0.5 -1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          0.5 -0.866025 -1.92296e-16,
+                          0.5 -0.866025 -1.92296e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.866025 -0.5 -1.11022e-16,
+                          0.866025 -0.5 -1.11022e-16,
+                          1 -3.06152e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.5 -0.866025 -1.92296e-16,
+                          0.866025 -0.5 -1.11022e-16,
+                          0.866025 -0.5 -1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          0.866025 0.5 1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.866025 -0.5 -1.11022e-16,
+                          1 -3.06152e-16 0,
+                          1 -3.06152e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.866025 0.5 1.11022e-16,
+                          0.866025 0.5 1.11022e-16,
+                          0.5 0.866025 1.92296e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1 -6.12303e-17 0,
+                          0.866025 0.5 1.11022e-16,
+                          0.866025 0.5 1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.5 0.866025 1.92296e-16,
+                          0.5 0.866025 1.92296e-16,
+                          1.22461e-16 1 2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.866025 0.5 1.11022e-16,
+                          0.5 0.866025 1.92296e-16,
+                          0.5 0.866025 1.92296e-16,
+                          1.22461e-16 1 2.22045e-16,
+                          1.22461e-16 1 2.22045e-16,
+                          -0.5 0.866025 1.92296e-16,
+                          0.5 0.866025 1.92296e-16,
+                          1.22461e-16 1 2.22045e-16,
+                          1.22461e-16 1 2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.5 0.866025 1.92296e-16,
+                          -0.5 0.866025 1.92296e-16,
+                          -0.866025 0.5 1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1.22461e-16 1 2.22045e-16,
+                          -0.5 0.866025 1.92296e-16,
+                          -0.5 0.866025 1.92296e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.5 0.866025 1.92296e-16,
+                          -0.866025 0.5 1.11022e-16,
+                          -0.866025 0.5 1.11022e-16,
+                          1 -1.83691e-16 0,
+                          1 -1.83691e-16 0,
+                          0.951057 -0.309017 -6.86156e-17,
+                          0.951057 0.309017 6.86156e-17,
+                          0.951057 0.309017 6.86156e-17,
+                          1 -1.83691e-16 0,
+                          0.951057 0.309017 6.86156e-17,
+                          1 -1.83691e-16 0,
+                          1 -1.83691e-16 0,
+                          0.951057 -0.309017 -6.86156e-17,
+                          0.951057 -0.309017 -6.86156e-17,
+                          0.809017 -0.587785 -1.30515e-16,
+                          1 -1.83691e-16 0,
+                          0.951057 -0.309017 -6.86156e-17,
+                          0.951057 -0.309017 -6.86156e-17,
+                          0.809017 -0.587785 -1.30515e-16,
+                          0.809017 -0.587785 -1.30515e-16,
+                          0.587785 -0.809017 -1.79638e-16,
+                          0.951057 -0.309017 -6.86156e-17,
+                          0.809017 -0.587785 -1.30515e-16,
+                          0.809017 -0.587785 -1.30515e-16,
+                          0.587785 -0.809017 -1.79638e-16,
+                          0.587785 -0.809017 -1.79638e-16,
+                          0.309017 -0.951057 -2.11177e-16,
+                          0.809017 -0.587785 -1.30515e-16,
+                          0.587785 -0.809017 -1.79638e-16,
+                          0.587785 -0.809017 -1.79638e-16,
+                          0.309017 -0.951057 -2.11177e-16,
+                          0.309017 -0.951057 -2.11177e-16,
+                          -1.22461e-16 -1 -2.22045e-16,
+                          0.587785 -0.809017 -1.79638e-16,
+                          0.309017 -0.951057 -2.11177e-16,
+                          0.309017 -0.951057 -2.11177e-16,
+                          -1.22461e-16 -1 -2.22045e-16,
+                          -1.22461e-16 -1 -2.22045e-16,
+                          -0.309017 -0.951057 -2.11177e-16,
+                          0.309017 -0.951057 -2.11177e-16,
+                          -1.22461e-16 -1 -2.22045e-16,
+                          -1.22461e-16 -1 -2.22045e-16,
+                          -0.309017 -0.951057 -2.11177e-16,
+                          -0.309017 -0.951057 -2.11177e-16,
+                          -0.587785 -0.809017 -1.79638e-16,
+                          -1.22461e-16 -1 -2.22045e-16,
+                          -0.309017 -0.951057 -2.11177e-16,
+                          -0.309017 -0.951057 -2.11177e-16,
+                          -0.587785 -0.809017 -1.79638e-16,
+                          -0.587785 -0.809017 -1.79638e-16,
+                          -0.809017 -0.587785 -1.30515e-16,
+                          -0.309017 -0.951057 -2.11177e-16,
+                          -0.587785 -0.809017 -1.79638e-16,
+                          -0.587785 -0.809017 -1.79638e-16,
+                          -0.809017 -0.587785 -1.30515e-16,
+                          -0.809017 -0.587785 -1.30515e-16,
+                          -0.951057 -0.309017 -6.86156e-17,
+                          -0.587785 -0.809017 -1.79638e-16,
+                          -0.809017 -0.587785 -1.30515e-16,
+                          -0.809017 -0.587785 -1.30515e-16,
+                          -0.951057 -0.309017 -6.86156e-17,
+                          -0.951057 -0.309017 -6.86156e-17,
+                          -1 6.12303e-17 0,
+                          -0.809017 -0.587785 -1.30515e-16,
+                          -0.951057 -0.309017 -6.86156e-17,
+                          -0.951057 -0.309017 -6.86156e-17,
+                          -1 3.06152e-16 0,
+                          -1 3.06152e-16 0,
+                          -0.951057 0.309017 6.86156e-17,
+                          -0.951057 -0.309017 -6.86156e-17,
+                          -1 6.12303e-17 0,
+                          -1 6.12303e-17 0,
+                          -0.951057 0.309017 6.86156e-17,
+                          -0.951057 0.309017 6.86156e-17,
+                          -0.809017 0.587785 1.30515e-16,
+                          -0.951057 0.309017 6.86156e-17,
+                          -1 3.06152e-16 0,
+                          -0.951057 0.309017 6.86156e-17,
+                          -0.809017 0.587785 1.30515e-16,
+                          -0.809017 0.587785 1.30515e-16,
+                          -0.587785 0.809017 1.79638e-16,
+                          -0.951057 0.309017 6.86156e-17,
+                          -0.809017 0.587785 1.30515e-16,
+                          -0.809017 0.587785 1.30515e-16,
+                          -0.587785 0.809017 1.79638e-16,
+                          -0.587785 0.809017 1.79638e-16,
+                          -0.309017 0.951057 2.11177e-16,
+                          -0.809017 0.587785 1.30515e-16,
+                          -0.587785 0.809017 1.79638e-16,
+                          -0.587785 0.809017 1.79638e-16,
+                          -0.309017 0.951057 2.11177e-16,
+                          -0.309017 0.951057 2.11177e-16,
+                          2.44921e-16 1 2.22045e-16,
+                          -0.587785 0.809017 1.79638e-16,
+                          -0.309017 0.951057 2.11177e-16,
+                          -0.309017 0.951057 2.11177e-16,
+                          2.44921e-16 1 2.22045e-16,
+                          2.44921e-16 1 2.22045e-16,
+                          0.309017 0.951057 2.11177e-16,
+                          -0.309017 0.951057 2.11177e-16,
+                          2.44921e-16 1 2.22045e-16,
+                          2.44921e-16 1 2.22045e-16,
+                          0.309017 0.951057 2.11177e-16,
+                          0.309017 0.951057 2.11177e-16,
+                          0.587785 0.809017 1.79638e-16,
+                          2.44921e-16 1 2.22045e-16,
+                          0.309017 0.951057 2.11177e-16,
+                          0.309017 0.951057 2.11177e-16,
+                          0.587785 0.809017 1.79638e-16,
+                          0.587785 0.809017 1.79638e-16,
+                          0.809017 0.587785 1.30515e-16,
+                          0.309017 0.951057 2.11177e-16,
+                          0.587785 0.809017 1.79638e-16,
+                          0.587785 0.809017 1.79638e-16,
+                          0.809017 0.587785 1.30515e-16,
+                          0.809017 0.587785 1.30515e-16,
+                          0.951057 0.309017 6.86156e-17,
+                          0.587785 0.809017 1.79638e-16,
+                          0.809017 0.587785 1.30515e-16,
+                          0.809017 0.587785 1.30515e-16,
+                          0.809017 0.587785 1.30515e-16,
+                          0.951057 0.309017 6.86156e-17,
+                          0.951057 0.309017 6.86156e-17,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -1 1.83691e-16 0,
+                          -1 1.83691e-16 0,
+                          -0.866025 -0.5 -1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.866025 0.5 1.11022e-16,
+                          -0.866025 0.5 1.11022e-16,
+                          -1 1.83691e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.866025 0.5 1.11022e-16,
+                          -1 1.83691e-16 0,
+                          -1 1.83691e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.866025 -0.5 -1.11022e-16,
+                          -0.866025 -0.5 -1.11022e-16,
+                          -0.5 -0.866025 -1.92296e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.866025 -0.5 -1.11022e-16,
+                          -1 1.83691e-16 0,
+                          -0.866025 -0.5 -1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.5 -0.866025 -1.92296e-16,
+                          -0.5 -0.866025 -1.92296e-16,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.866025 -0.5 -1.11022e-16,
+                          -0.5 -0.866025 -1.92296e-16,
+                          -0.5 -0.866025 -1.92296e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          0.5 -0.866025 -1.92296e-16,
+                          -0.5 -0.866025 -1.92296e-16,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.5 -0.866025 -1.92296e-16,
+                          0.5 -0.866025 -1.92296e-16,
+                          0.866025 -0.5 -1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          0.5 -0.866025 -1.92296e-16,
+                          0.5 -0.866025 -1.92296e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.866025 -0.5 -1.11022e-16,
+                          0.866025 -0.5 -1.11022e-16,
+                          1 -3.06152e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.5 -0.866025 -1.92296e-16,
+                          0.866025 -0.5 -1.11022e-16,
+                          0.866025 -0.5 -1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          0.866025 0.5 1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.866025 -0.5 -1.11022e-16,
+                          1 -3.06152e-16 0,
+                          1 -3.06152e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.866025 0.5 1.11022e-16,
+                          0.866025 0.5 1.11022e-16,
+                          0.5 0.866025 1.92296e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1 -6.12303e-17 0,
+                          0.866025 0.5 1.11022e-16,
+                          0.866025 0.5 1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.5 0.866025 1.92296e-16,
+                          0.5 0.866025 1.92296e-16,
+                          1.22461e-16 1 2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.866025 0.5 1.11022e-16,
+                          0.5 0.866025 1.92296e-16,
+                          0.5 0.866025 1.92296e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1.22461e-16 1 2.22045e-16,
+                          1.22461e-16 1 2.22045e-16,
+                          -0.5 0.866025 1.92296e-16,
+                          0.5 0.866025 1.92296e-16,
+                          1.22461e-16 1 2.22045e-16,
+                          1.22461e-16 1 2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.5 0.866025 1.92296e-16,
+                          -0.5 0.866025 1.92296e-16,
+                          -0.866025 0.5 1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1.22461e-16 1 2.22045e-16,
+                          -0.5 0.866025 1.92296e-16,
+                          -0.5 0.866025 1.92296e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.5 0.866025 1.92296e-16,
+                          -0.866025 0.5 1.11022e-16,
+                          -0.866025 0.5 1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -1 1.83691e-16 0,
+                          -1 1.83691e-16 0,
+                          -0.866025 -0.5 -1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.866025 0.5 1.11022e-16,
+                          -0.866025 0.5 1.11022e-16,
+                          -1 1.83691e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.866025 0.5 1.11022e-16,
+                          -1 1.83691e-16 0,
+                          -1 1.83691e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.866025 -0.5 -1.11022e-16,
+                          -0.866025 -0.5 -1.11022e-16,
+                          -0.5 -0.866025 -1.92296e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.866025 -0.5 -1.11022e-16,
+                          -1 1.83691e-16 0,
+                          -0.866025 -0.5 -1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.5 -0.866025 -1.92296e-16,
+                          -0.5 -0.866025 -1.92296e-16,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.866025 -0.5 -1.11022e-16,
+                          -0.5 -0.866025 -1.92296e-16,
+                          -0.5 -0.866025 -1.92296e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          0.5 -0.866025 -1.92296e-16,
+                          -0.5 -0.866025 -1.92296e-16,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.5 -0.866025 -1.92296e-16,
+                          0.5 -0.866025 -1.92296e-16,
+                          0.866025 -0.5 -1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          0.5 -0.866025 -1.92296e-16,
+                          0.5 -0.866025 -1.92296e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.866025 -0.5 -1.11022e-16,
+                          0.866025 -0.5 -1.11022e-16,
+                          1 -3.06152e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.5 -0.866025 -1.92296e-16,
+                          0.866025 -0.5 -1.11022e-16,
+                          0.866025 -0.5 -1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          0.866025 0.5 1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.866025 -0.5 -1.11022e-16,
+                          1 -3.06152e-16 0,
+                          1 -3.06152e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.866025 0.5 1.11022e-16,
+                          0.866025 0.5 1.11022e-16,
+                          0.5 0.866025 1.92296e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1 -6.12303e-17 0,
+                          0.866025 0.5 1.11022e-16,
+                          0.866025 0.5 1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.5 0.866025 1.92296e-16,
+                          0.5 0.866025 1.92296e-16,
+                          1.22461e-16 1 2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.866025 0.5 1.11022e-16,
+                          0.5 0.866025 1.92296e-16,
+                          0.5 0.866025 1.92296e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1.22461e-16 1 2.22045e-16,
+                          1.22461e-16 1 2.22045e-16,
+                          -0.5 0.866025 1.92296e-16,
+                          0.5 0.866025 1.92296e-16,
+                          1.22461e-16 1 2.22045e-16,
+                          1.22461e-16 1 2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.5 0.866025 1.92296e-16,
+                          -0.5 0.866025 1.92296e-16,
+                          -0.866025 0.5 1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1.22461e-16 1 2.22045e-16,
+                          -0.5 0.866025 1.92296e-16,
+                          -0.5 0.866025 1.92296e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.5 0.866025 1.92296e-16,
+                          -0.866025 0.5 1.11022e-16,
+                          -0.866025 0.5 1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -1 1.83691e-16 0,
+                          -1 1.83691e-16 0,
+                          -0.866025 -0.5 -1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.866025 0.5 1.11022e-16,
+                          -0.866025 0.5 1.11022e-16,
+                          -1 1.83691e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.866025 0.5 1.11022e-16,
+                          -1 1.83691e-16 0,
+                          -1 1.83691e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.866025 -0.5 -1.11022e-16,
+                          -0.866025 -0.5 -1.11022e-16,
+                          -0.5 -0.866025 -1.92296e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.866025 -0.5 -1.11022e-16,
+                          -1 1.83691e-16 0,
+                          -0.866025 -0.5 -1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.5 -0.866025 -1.92296e-16,
+                          -0.5 -0.866025 -1.92296e-16,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.866025 -0.5 -1.11022e-16,
+                          -0.5 -0.866025 -1.92296e-16,
+                          -0.5 -0.866025 -1.92296e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          0.5 -0.866025 -1.92296e-16,
+                          -0.5 -0.866025 -1.92296e-16,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.5 -0.866025 -1.92296e-16,
+                          0.5 -0.866025 -1.92296e-16,
+                          0.866025 -0.5 -1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          0.5 -0.866025 -1.92296e-16,
+                          0.5 -0.866025 -1.92296e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.866025 -0.5 -1.11022e-16,
+                          0.866025 -0.5 -1.11022e-16,
+                          1 -3.06152e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.5 -0.866025 -1.92296e-16,
+                          0.866025 -0.5 -1.11022e-16,
+                          0.866025 -0.5 -1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          0.866025 0.5 1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.866025 -0.5 -1.11022e-16,
+                          1 -3.06152e-16 0,
+                          1 -3.06152e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.866025 0.5 1.11022e-16,
+                          0.866025 0.5 1.11022e-16,
+                          0.5 0.866025 1.92296e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1 -6.12303e-17 0,
+                          0.866025 0.5 1.11022e-16,
+                          0.866025 0.5 1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.5 0.866025 1.92296e-16,
+                          0.5 0.866025 1.92296e-16,
+                          1.22461e-16 1 2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.866025 0.5 1.11022e-16,
+                          0.5 0.866025 1.92296e-16,
+                          0.5 0.866025 1.92296e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1.22461e-16 1 2.22045e-16,
+                          1.22461e-16 1 2.22045e-16,
+                          -0.5 0.866025 1.92296e-16,
+                          0.5 0.866025 1.92296e-16,
+                          1.22461e-16 1 2.22045e-16,
+                          1.22461e-16 1 2.22045e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.5 0.866025 1.92296e-16,
+                          -0.5 0.866025 1.92296e-16,
+                          -0.866025 0.5 1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1.22461e-16 1 2.22045e-16,
+                          -0.5 0.866025 1.92296e-16,
+                          -0.5 0.866025 1.92296e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.5 0.866025 1.92296e-16,
+                          -0.866025 0.5 1.11022e-16,
+                          -0.866025 0.5 1.11022e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -1 1.83691e-16 0,
+                          -1 1.83691e-16 0,
+                          -0.900969 -0.433884 -9.63415e-17,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.900969 0.433884 9.63415e-17,
+                          -0.900969 0.433884 9.63415e-17,
+                          -1 1.83691e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.900969 0.433884 9.63415e-17,
+                          -1 1.83691e-16 0,
+                          -1 1.83691e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.900969 -0.433884 -9.63415e-17,
+                          -0.900969 -0.433884 -9.63415e-17,
+                          -0.62349 -0.781832 -1.73601e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.900969 -0.433884 -9.63415e-17,
+                          -1 1.83691e-16 0,
+                          -0.900969 -0.433884 -9.63415e-17,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.62349 -0.781832 -1.73601e-16,
+                          -0.62349 -0.781832 -1.73601e-16,
+                          -0.222521 -0.974928 -2.16477e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.900969 -0.433884 -9.63415e-17,
+                          -0.62349 -0.781832 -1.73601e-16,
+                          -0.62349 -0.781832 -1.73601e-16,
+                          -0.222521 -0.974928 -2.16477e-16,
+                          -0.222521 -0.974928 -2.16477e-16,
+                          0.222521 -0.974928 -2.16477e-16,
+                          -0.62349 -0.781832 -1.73601e-16,
+                          -0.222521 -0.974928 -2.16477e-16,
+                          -0.222521 -0.974928 -2.16477e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.222521 -0.974928 -2.16477e-16,
+                          0.222521 -0.974928 -2.16477e-16,
+                          0.62349 -0.781832 -1.73601e-16,
+                          -0.222521 -0.974928 -2.16477e-16,
+                          0.222521 -0.974928 -2.16477e-16,
+                          0.222521 -0.974928 -2.16477e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.62349 -0.781832 -1.73601e-16,
+                          0.62349 -0.781832 -1.73601e-16,
+                          0.900969 -0.433884 -9.63415e-17,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.222521 -0.974928 -2.16477e-16,
+                          0.62349 -0.781832 -1.73601e-16,
+                          0.62349 -0.781832 -1.73601e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.900969 -0.433884 -9.63415e-17,
+                          0.900969 -0.433884 -9.63415e-17,
+                          1 -3.06152e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.62349 -0.781832 -1.73601e-16,
+                          0.900969 -0.433884 -9.63415e-17,
+                          0.900969 -0.433884 -9.63415e-17,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          0.900969 0.433884 9.63415e-17,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.900969 -0.433884 -9.63415e-17,
+                          1 -3.06152e-16 0,
+                          1 -3.06152e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.900969 0.433884 9.63415e-17,
+                          0.900969 0.433884 9.63415e-17,
+                          0.62349 0.781832 1.73601e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1 -6.12303e-17 0,
+                          0.900969 0.433884 9.63415e-17,
+                          0.900969 0.433884 9.63415e-17,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.62349 0.781832 1.73601e-16,
+                          0.62349 0.781832 1.73601e-16,
+                          0.222521 0.974928 2.16477e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.900969 0.433884 9.63415e-17,
+                          0.62349 0.781832 1.73601e-16,
+                          0.62349 0.781832 1.73601e-16,
+                          0.222521 0.974928 2.16477e-16,
+                          0.222521 0.974928 2.16477e-16,
+                          -0.222521 0.974928 2.16477e-16,
+                          0.62349 0.781832 1.73601e-16,
+                          0.222521 0.974928 2.16477e-16,
+                          0.222521 0.974928 2.16477e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.222521 0.974928 2.16477e-16,
+                          -0.222521 0.974928 2.16477e-16,
+                          -0.62349 0.781832 1.73601e-16,
+                          0.222521 0.974928 2.16477e-16,
+                          -0.222521 0.974928 2.16477e-16,
+                          -0.222521 0.974928 2.16477e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.62349 0.781832 1.73601e-16,
+                          -0.62349 0.781832 1.73601e-16,
+                          -0.900969 0.433884 9.63415e-17,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.222521 0.974928 2.16477e-16,
+                          -0.62349 0.781832 1.73601e-16,
+                          -0.62349 0.781832 1.73601e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.62349 0.781832 1.73601e-16,
+                          -0.900969 0.433884 9.63415e-17,
+                          -0.900969 0.433884 9.63415e-17,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -1 1.83691e-16 0,
+                          -1 1.83691e-16 0,
+                          -0.92388 -0.382683 -8.49728e-17,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.92388 0.382683 8.49728e-17,
+                          -0.92388 0.382683 8.49728e-17,
+                          -1 1.83691e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.92388 0.382683 8.49728e-17,
+                          -1 1.83691e-16 0,
+                          -1 1.83691e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.92388 -0.382683 -8.49728e-17,
+                          -0.92388 -0.382683 -8.49728e-17,
+                          -0.707107 -0.707107 -1.57009e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.92388 -0.382683 -8.49728e-17,
+                          -1 1.83691e-16 0,
+                          -0.92388 -0.382683 -8.49728e-17,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.707107 -0.707107 -1.57009e-16,
+                          -0.707107 -0.707107 -1.57009e-16,
+                          -0.382683 -0.92388 -2.05142e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.92388 -0.382683 -8.49728e-17,
+                          -0.707107 -0.707107 -1.57009e-16,
+                          -0.707107 -0.707107 -1.57009e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.382683 -0.92388 -2.05142e-16,
+                          -0.382683 -0.92388 -2.05142e-16,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          -0.707107 -0.707107 -1.57009e-16,
+                          -0.382683 -0.92388 -2.05142e-16,
+                          -0.382683 -0.92388 -2.05142e-16,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          0.382683 -0.92388 -2.05142e-16,
+                          -0.382683 -0.92388 -2.05142e-16,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          0.382683 -0.92388 -2.05142e-16,
+                          0.382683 -0.92388 -2.05142e-16,
+                          0.707107 -0.707107 -1.57009e-16,
+                          -2.44921e-16 -1 -2.22045e-16,
+                          0.382683 -0.92388 -2.05142e-16,
+                          0.382683 -0.92388 -2.05142e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.707107 -0.707107 -1.57009e-16,
+                          0.707107 -0.707107 -1.57009e-16,
+                          0.92388 -0.382683 -8.49728e-17,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.382683 -0.92388 -2.05142e-16,
+                          0.707107 -0.707107 -1.57009e-16,
+                          0.707107 -0.707107 -1.57009e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.92388 -0.382683 -8.49728e-17,
+                          0.92388 -0.382683 -8.49728e-17,
+                          1 -3.06152e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.707107 -0.707107 -1.57009e-16,
+                          0.92388 -0.382683 -8.49728e-17,
+                          0.92388 -0.382683 -8.49728e-17,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1 -6.12303e-17 0,
+                          1 -6.12303e-17 0,
+                          0.92388 0.382683 8.49728e-17,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.92388 -0.382683 -8.49728e-17,
+                          1 -3.06152e-16 0,
+                          1 -3.06152e-16 0,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.92388 0.382683 8.49728e-17,
+                          0.92388 0.382683 8.49728e-17,
+                          0.707107 0.707107 1.57009e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          1 -6.12303e-17 0,
+                          0.92388 0.382683 8.49728e-17,
+                          0.92388 0.382683 8.49728e-17,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.707107 0.707107 1.57009e-16,
+                          0.707107 0.707107 1.57009e-16,
+                          0.382683 0.92388 2.05142e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.92388 0.382683 8.49728e-17,
+                          0.707107 0.707107 1.57009e-16,
+                          0.707107 0.707107 1.57009e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0.382683 0.92388 2.05142e-16,
+                          0.382683 0.92388 2.05142e-16,
+                          1.22461e-16 1 2.22045e-16,
+                          0.707107 0.707107 1.57009e-16,
+                          0.382683 0.92388 2.05142e-16,
+                          0.382683 0.92388 2.05142e-16,
+                          1.22461e-16 1 2.22045e-16,
+                          1.22461e-16 1 2.22045e-16,
+                          -0.382683 0.92388 2.05142e-16,
+                          0.382683 0.92388 2.05142e-16,
+                          1.22461e-16 1 2.22045e-16,
+                          1.22461e-16 1 2.22045e-16,
+                          -0.382683 0.92388 2.05142e-16,
+                          -0.382683 0.92388 2.05142e-16,
+                          -0.707107 0.707107 1.57009e-16,
+                          1.22461e-16 1 2.22045e-16,
+                          -0.382683 0.92388 2.05142e-16,
+                          -0.382683 0.92388 2.05142e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.707107 0.707107 1.57009e-16,
+                          -0.707107 0.707107 1.57009e-16,
+                          -0.92388 0.382683 8.49728e-17,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.382683 0.92388 2.05142e-16,
+                          -0.707107 0.707107 1.57009e-16,
+                          -0.707107 0.707107 1.57009e-16,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          0 2.22045e-16 -1,
+                          -0.707107 0.707107 1.57009e-16,
+                          -0.92388 0.382683 8.49728e-17,
+                          -0.92388 0.382683 8.49728e-17,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1,
+                          0 -2.22045e-16 1 ]
+        }
+        NormalBinding {
+            value       PER_VERTEX
+        }
+        Coordinate3 {
+            point       [ -20.7853 -11.9985 132,
+                          -19.0208 -6.18136 132,
+                          -20 -2.80853e-14 132,
+                          -20 -6.98432e-15 48,
+                          -20 -2.80853e-14 132,
+                          -19.0208 -6.18136 132,
+                          -24 -2.78404e-14 132,
+                          -20 -2.80853e-14 132,
+                          -19.0208 6.18136 132,
+                          -19.0211 6.18034 48,
+                          -19.0208 6.18136 132,
+                          -20 -2.80853e-14 132,
+                          -20.7853 -11.9985 132,
+                          -20 -2.80853e-14 132,
+                          -24 -2.78404e-14 132,
+                          -20 -6.98432e-15 48,
+                          -19.0211 6.18034 48,
+                          -20 -2.80853e-14 132,
+                          -20.7853 -11.9985 132,
+                          -16.1794 -11.7568 132,
+                          -19.0208 -6.18136 132,
+                          -19.0211 -6.18034 48,
+                          -19.0208 -6.18136 132,
+                          -16.1794 -11.7568 132,
+                          -19.0211 -6.18034 48,
+                          -20 -6.98432e-15 48,
+                          -19.0208 -6.18136 132,
+                          -20.7853 -11.9985 132,
+                          -11.7545 -16.1809 132,
+                          -16.1794 -11.7568 132,
+                          -16.1803 -11.7557 48,
+                          -16.1794 -11.7568 132,
+                          -11.7545 -16.1809 132,
+                          -16.1803 -11.7557 48,
+                          -19.0211 -6.18034 48,
+                          -16.1794 -11.7568 132,
+                          -12.001 -20.7837 132,
+                          -6.17955 -19.021 132,
+                          -11.7545 -16.1809 132,
+                          -11.7557 -16.1803 48,
+                          -11.7545 -16.1809 132,
+                          -6.17955 -19.021 132,
+                          -20.7853 -11.9985 132,
+                          -12.001 -20.7837 132,
+                          -11.7545 -16.1809 132,
+                          -11.7557 -16.1803 48,
+                          -16.1803 -11.7557 48,
+                          -11.7545 -16.1809 132,
+                          -12.001 -20.7837 132,
+                          -2.44583e-15 -19.9997 132,
+                          -6.17955 -19.021 132,
+                          -6.18034 -19.0211 48,
+                          -6.17955 -19.021 132,
+                          -2.44583e-15 -19.9997 132,
+                          -6.18034 -19.0211 48,
+                          -11.7557 -16.1803 48,
+                          -6.17955 -19.021 132,
+                          12.001 -20.7837 132,
+                          6.17955 -19.021 132,
+                          -2.44583e-15 -19.9997 132,
+                          -4.89843e-15 -20 48,
+                          -2.44583e-15 -19.9997 132,
+                          6.17955 -19.021 132,
+                          -12.001 -20.7837 132,
+                          12.001 -20.7837 132,
+                          -2.44583e-15 -19.9997 132,
+                          -4.89843e-15 -20 48,
+                          -6.18034 -19.0211 48,
+                          -2.44583e-15 -19.9997 132,
+                          20.7853 -11.9985 132,
+                          11.7545 -16.1809 132,
+                          6.17955 -19.021 132,
+                          6.18034 -19.0211 48,
+                          6.17955 -19.021 132,
+                          11.7545 -16.1809 132,
+                          12.001 -20.7837 132,
+                          20.7853 -11.9985 132,
+                          6.17955 -19.021 132,
+                          6.18034 -19.0211 48,
+                          -4.89843e-15 -20 48,
+                          6.17955 -19.021 132,
+                          20.7853 -11.9985 132,
+                          16.1794 -11.7568 132,
+                          11.7545 -16.1809 132,
+                          11.7557 -16.1803 48,
+                          11.7545 -16.1809 132,
+                          16.1794 -11.7568 132,
+                          11.7557 -16.1803 48,
+                          6.18034 -19.0211 48,
+                          11.7545 -16.1809 132,
+                          24 -3.07794e-14 132,
+                          19.0208 -6.18136 132,
+                          16.1794 -11.7568 132,
+                          16.1803 -11.7557 48,
+                          16.1794 -11.7568 132,
+                          19.0208 -6.18136 132,
+                          20.7853 -11.9985 132,
+                          24 -3.07794e-14 132,
+                          16.1794 -11.7568 132,
+                          16.1803 -11.7557 48,
+                          11.7557 -16.1803 48,
+                          16.1794 -11.7568 132,
+                          24 -3.07794e-14 132,
+                          20 -3.05345e-14 132,
+                          19.0208 -6.18136 132,
+                          19.0211 -6.18034 48,
+                          19.0208 -6.18136 132,
+                          20 -3.05345e-14 132,
+                          19.0211 -6.18034 48,
+                          16.1803 -11.7557 48,
+                          19.0208 -6.18136 132,
+                          20.7853 11.9985 132,
+                          19.0208 6.18136 132,
+                          20 -3.05345e-14 132,
+                          20 -1.18827e-14 48,
+                          20 -3.05345e-14 132,
+                          19.0208 6.18136 132,
+                          24 -3.07794e-14 132,
+                          20.7853 11.9985 132,
+                          20 -3.05345e-14 132,
+                          19.0211 -6.18034 48,
+                          20 -3.05345e-14 132,
+                          20 -1.18827e-14 48,
+                          20.7853 11.9985 132,
+                          16.1794 11.7568 132,
+                          19.0208 6.18136 132,
+                          19.0211 6.18034 48,
+                          19.0208 6.18136 132,
+                          16.1794 11.7568 132,
+                          19.0211 6.18034 48,
+                          20 -1.18827e-14 48,
+                          19.0208 6.18136 132,
+                          20.7853 11.9985 132,
+                          11.7545 16.1809 132,
+                          16.1794 11.7568 132,
+                          16.1803 11.7557 48,
+                          16.1794 11.7568 132,
+                          11.7545 16.1809 132,
+                          16.1803 11.7557 48,
+                          19.0211 6.18034 48,
+                          16.1794 11.7568 132,
+                          12.001 20.7837 132,
+                          6.17955 19.021 132,
+                          11.7545 16.1809 132,
+                          11.7557 16.1803 48,
+                          11.7545 16.1809 132,
+                          6.17955 19.021 132,
+                          20.7853 11.9985 132,
+                          12.001 20.7837 132,
+                          11.7545 16.1809 132,
+                          11.7557 16.1803 48,
+                          16.1803 11.7557 48,
+                          11.7545 16.1809 132,
+                          12.001 20.7837 132,
+                          3.33575e-18 19.9997 132,
+                          6.17955 19.021 132,
+                          6.18034 19.0211 48,
+                          6.17955 19.021 132,
+                          3.33575e-18 19.9997 132,
+                          6.18034 19.0211 48,
+                          11.7557 16.1803 48,
+                          6.17955 19.021 132,
+                          -12.001 20.7837 132,
+                          -6.17955 19.021 132,
+                          3.33575e-18 19.9997 132,
+                          2.44921e-15 20 48,
+                          3.33575e-18 19.9997 132,
+                          -6.17955 19.021 132,
+                          12.001 20.7837 132,
+                          -12.001 20.7837 132,
+                          3.33575e-18 19.9997 132,
+                          2.44921e-15 20 48,
+                          6.18034 19.0211 48,
+                          3.33575e-18 19.9997 132,
+                          -20.7853 11.9985 132,
+                          -11.7545 16.1809 132,
+                          -6.17955 19.021 132,
+                          -6.18034 19.0211 48,
+                          -6.17955 19.021 132,
+                          -11.7545 16.1809 132,
+                          -12.001 20.7837 132,
+                          -20.7853 11.9985 132,
+                          -6.17955 19.021 132,
+                          -6.18034 19.0211 48,
+                          2.44921e-15 20 48,
+                          -6.17955 19.021 132,
+                          -20.7853 11.9985 132,
+                          -16.1794 11.7568 132,
+                          -11.7545 16.1809 132,
+                          -11.7557 16.1803 48,
+                          -11.7545 16.1809 132,
+                          -16.1794 11.7568 132,
+                          -11.7557 16.1803 48,
+                          -6.18034 19.0211 48,
+                          -11.7545 16.1809 132,
+                          -24 -2.78404e-14 132,
+                          -19.0208 6.18136 132,
+                          -16.1794 11.7568 132,
+                          -16.1803 11.7557 48,
+                          -16.1794 11.7568 132,
+                          -19.0208 6.18136 132,
+                          -20.7853 11.9985 132,
+                          -24 -2.78404e-14 132,
+                          -16.1794 11.7568 132,
+                          -16.1803 11.7557 48,
+                          -11.7557 16.1803 48,
+                          -16.1794 11.7568 132,
+                          -19.0211 6.18034 48,
+                          -16.1803 11.7557 48,
+                          -19.0208 6.18136 132,
+                          -24 -2.67301e-14 127,
+                          -24 -2.78404e-14 132,
+                          -20.7853 11.9985 132,
+                          -20.7853 -11.9985 127,
+                          -20.7853 -11.9985 132,
+                          -24 -2.78404e-14 132,
+                          -20.7853 -11.9985 127,
+                          -24 -2.78404e-14 132,
+                          -24 -2.67301e-14 127,
+                          -20.7853 11.9985 127,
+                          -20.7853 11.9985 132,
+                          -12.001 20.7837 132,
+                          -20.7853 11.9985 127,
+                          -24 -2.67301e-14 127,
+                          -20.7853 11.9985 132,
+                          12.001 20.7837 132,
+                          2.62081e-17 23.9996 132,
+                          -12.001 20.7837 132,
+                          -12.001 20.7837 127,
+                          -12.001 20.7837 132,
+                          2.62081e-17 23.9996 132,
+                          -20.7853 11.9985 127,
+                          -12.001 20.7837 132,
+                          -12.001 20.7837 127,
+                          2.62081e-17 23.9996 127,
+                          2.62081e-17 23.9996 132,
+                          12.001 20.7837 132,
+                          -12.001 20.7837 127,
+                          2.62081e-17 23.9996 132,
+                          2.62081e-17 23.9996 127,
+                          12.001 20.7837 127,
+                          12.001 20.7837 132,
+                          20.7853 11.9985 132,
+                          2.62081e-17 23.9996 127,
+                          12.001 20.7837 132,
+                          12.001 20.7837 127,
+                          20.7853 11.9985 127,
+                          20.7853 11.9985 132,
+                          24 -3.07794e-14 132,
+                          12.001 20.7837 127,
+                          20.7853 11.9985 132,
+                          20.7853 11.9985 127,
+                          24 -2.96692e-14 127,
+                          24 -3.07794e-14 132,
+                          20.7853 -11.9985 132,
+                          20.7853 11.9985 127,
+                          24 -3.07794e-14 132,
+                          24 -2.96692e-14 127,
+                          20.7853 -11.9985 127,
+                          20.7853 -11.9985 132,
+                          12.001 -20.7837 132,
+                          24 -2.96692e-14 127,
+                          20.7853 -11.9985 132,
+                          20.7853 -11.9985 127,
+                          -12.001 -20.7837 132,
+                          -2.9128e-15 -23.9996 132,
+                          12.001 -20.7837 132,
+                          12.001 -20.7837 127,
+                          12.001 -20.7837 132,
+                          -2.9128e-15 -23.9996 132,
+                          20.7853 -11.9985 127,
+                          12.001 -20.7837 132,
+                          12.001 -20.7837 127,
+                          -2.9128e-15 -23.9996 127,
+                          -2.9128e-15 -23.9996 132,
+                          -12.001 -20.7837 132,
+                          12.001 -20.7837 127,
+                          -2.9128e-15 -23.9996 132,
+                          -2.9128e-15 -23.9996 127,
+                          -12.001 -20.7837 127,
+                          -12.001 -20.7837 132,
+                          -20.7853 -11.9985 132,
+                          -2.9128e-15 -23.9996 127,
+                          -12.001 -20.7837 132,
+                          -12.001 -20.7837 127,
+                          -12.001 -20.7837 127,
+                          -20.7853 -11.9985 132,
+                          -20.7853 -11.9985 127,
+                          -16.1794 -11.7568 36,
+                          -20.7853 -11.9985 36,
+                          -24 -6.52407e-15 36,
+                          -24 -9.18861e-15 48,
+                          -24 -6.52407e-15 36,
+                          -20.7853 -11.9985 36,
+                          -20 -6.76899e-15 36,
+                          -24 -6.52407e-15 36,
+                          -20.7853 11.9985 36,
+                          -20.7853 11.9985 48,
+                          -20.7853 11.9985 36,
+                          -24 -6.52407e-15 36,
+                          -19.0208 -6.18136 36,
+                          -24 -6.52407e-15 36,
+                          -20 -6.76899e-15 36,
+                          -19.0208 -6.18136 36,
+                          -16.1794 -11.7568 36,
+                          -24 -6.52407e-15 36,
+                          -20.7853 11.9985 48,
+                          -24 -6.52407e-15 36,
+                          -24 -9.18861e-15 48,
+                          -6.17955 -19.021 36,
+                          -12.001 -20.7837 36,
+                          -20.7853 -11.9985 36,
+                          -20.7853 -11.9985 48,
+                          -20.7853 -11.9985 36,
+                          -12.001 -20.7837 36,
+                          -11.7545 -16.1809 36,
+                          -6.17955 -19.021 36,
+                          -20.7853 -11.9985 36,
+                          -16.1794 -11.7568 36,
+                          -11.7545 -16.1809 36,
+                          -20.7853 -11.9985 36,
+                          -20.7853 -11.9985 48,
+                          -24 -9.18861e-15 48,
+                          -20.7853 -11.9985 36,
+                          12.001 -20.7837 36,
+                          -2.9128e-15 -23.9996 36,
+                          -12.001 -20.7837 36,
+                          -12.001 -20.7837 48,
+                          -12.001 -20.7837 36,
+                          -2.9128e-15 -23.9996 36,
+                          -2.44583e-15 -19.9997 36,
+                          12.001 -20.7837 36,
+                          -12.001 -20.7837 36,
+                          -6.17955 -19.021 36,
+                          -2.44583e-15 -19.9997 36,
+                          -12.001 -20.7837 36,
+                          -20.7853 -11.9985 48,
+                          -12.001 -20.7837 36,
+                          -12.001 -20.7837 48,
+                          -2.9128e-15 -23.9996 48,
+                          -2.9128e-15 -23.9996 36,
+                          12.001 -20.7837 36,
+                          -12.001 -20.7837 48,
+                          -2.9128e-15 -23.9996 36,
+                          -2.9128e-15 -23.9996 48,
+                          11.7545 -16.1809 36,
+                          20.7853 -11.9985 36,
+                          12.001 -20.7837 36,
+                          12.001 -20.7837 48,
+                          12.001 -20.7837 36,
+                          20.7853 -11.9985 36,
+                          6.17955 -19.021 36,
+                          11.7545 -16.1809 36,
+                          12.001 -20.7837 36,
+                          -2.44583e-15 -19.9997 36,
+                          6.17955 -19.021 36,
+                          12.001 -20.7837 36,
+                          -2.9128e-15 -23.9996 48,
+                          12.001 -20.7837 36,
+                          12.001 -20.7837 48,
+                          20 -9.21821e-15 36,
+                          24 -9.46313e-15 36,
+                          20.7853 -11.9985 36,
+                          20.7853 -11.9985 48,
+                          20.7853 -11.9985 36,
+                          24 -9.46313e-15 36,
+                          19.0208 -6.18136 36,
+                          20 -9.21821e-15 36,
+                          20.7853 -11.9985 36,
+                          16.1794 -11.7568 36,
+                          19.0208 -6.18136 36,
+                          20.7853 -11.9985 36,
+                          11.7545 -16.1809 36,
+                          16.1794 -11.7568 36,
+                          20.7853 -11.9985 36,
+                          12.001 -20.7837 48,
+                          20.7853 -11.9985 36,
+                          20.7853 -11.9985 48,
+                          16.1794 11.7568 36,
+                          20.7853 11.9985 36,
+                          24 -9.46313e-15 36,
+                          24 -1.21277e-14 48,
+                          24 -9.46313e-15 36,
+                          20.7853 11.9985 36,
+                          19.0208 6.18136 36,
+                          16.1794 11.7568 36,
+                          24 -9.46313e-15 36,
+                          20 -9.21821e-15 36,
+                          19.0208 6.18136 36,
+                          24 -9.46313e-15 36,
+                          20.7853 -11.9985 48,
+                          24 -9.46313e-15 36,
+                          24 -1.21277e-14 48,
+                          6.17955 19.021 36,
+                          12.001 20.7837 36,
+                          20.7853 11.9985 36,
+                          20.7853 11.9985 48,
+                          20.7853 11.9985 36,
+                          12.001 20.7837 36,
+                          11.7545 16.1809 36,
+                          6.17955 19.021 36,
+                          20.7853 11.9985 36,
+                          16.1794 11.7568 36,
+                          11.7545 16.1809 36,
+                          20.7853 11.9985 36,
+                          24 -1.21277e-14 48,
+                          20.7853 11.9985 36,
+                          20.7853 11.9985 48,
+                          -12.001 20.7837 36,
+                          2.62081e-17 23.9996 36,
+                          12.001 20.7837 36,
+                          12.001 20.7837 48,
+                          12.001 20.7837 36,
+                          2.62081e-17 23.9996 36,
+                          3.33575e-18 19.9997 36,
+                          -12.001 20.7837 36,
+                          12.001 20.7837 36,
+                          6.17955 19.021 36,
+                          3.33575e-18 19.9997 36,
+                          12.001 20.7837 36,
+                          20.7853 11.9985 48,
+                          12.001 20.7837 36,
+                          12.001 20.7837 48,
+                          2.62081e-17 23.9996 48,
+                          2.62081e-17 23.9996 36,
+                          -12.001 20.7837 36,
+                          12.001 20.7837 48,
+                          2.62081e-17 23.9996 36,
+                          2.62081e-17 23.9996 48,
+                          -11.7545 16.1809 36,
+                          -20.7853 11.9985 36,
+                          -12.001 20.7837 36,
+                          -12.001 20.7837 48,
+                          -12.001 20.7837 36,
+                          -20.7853 11.9985 36,
+                          -6.17955 19.021 36,
+                          -11.7545 16.1809 36,
+                          -12.001 20.7837 36,
+                          3.33575e-18 19.9997 36,
+                          -6.17955 19.021 36,
+                          -12.001 20.7837 36,
+                          2.62081e-17 23.9996 48,
+                          -12.001 20.7837 36,
+                          -12.001 20.7837 48,
+                          -19.0208 6.18136 36,
+                          -20 -6.76899e-15 36,
+                          -20.7853 11.9985 36,
+                          -16.1794 11.7568 36,
+                          -19.0208 6.18136 36,
+                          -20.7853 11.9985 36,
+                          -11.7545 16.1809 36,
+                          -16.1794 11.7568 36,
+                          -20.7853 11.9985 36,
+                          -12.001 20.7837 48,
+                          -20.7853 11.9985 36,
+                          -20.7853 11.9985 48,
+                          -20 -6.98432e-15 48,
+                          -20 -6.76899e-15 36,
+                          -19.0208 6.18136 36,
+                          -19.0211 -6.18034 48,
+                          -19.0208 -6.18136 36,
+                          -20 -6.76899e-15 36,
+                          -19.0211 -6.18034 48,
+                          -20 -6.76899e-15 36,
+                          -20 -6.98432e-15 48,
+                          -19.0211 6.18034 48,
+                          -19.0208 6.18136 36,
+                          -16.1794 11.7568 36,
+                          -20 -6.98432e-15 48,
+                          -19.0208 6.18136 36,
+                          -19.0211 6.18034 48,
+                          -16.1803 11.7557 48,
+                          -16.1794 11.7568 36,
+                          -11.7545 16.1809 36,
+                          -19.0211 6.18034 48,
+                          -16.1794 11.7568 36,
+                          -16.1803 11.7557 48,
+                          -11.7557 16.1803 48,
+                          -11.7545 16.1809 36,
+                          -6.17955 19.021 36,
+                          -16.1803 11.7557 48,
+                          -11.7545 16.1809 36,
+                          -11.7557 16.1803 48,
+                          -6.18034 19.0211 48,
+                          -6.17955 19.021 36,
+                          3.33575e-18 19.9997 36,
+                          -11.7557 16.1803 48,
+                          -6.17955 19.021 36,
+                          -6.18034 19.0211 48,
+                          2.44921e-15 20 48,
+                          3.33575e-18 19.9997 36,
+                          6.17955 19.021 36,
+                          -6.18034 19.0211 48,
+                          3.33575e-18 19.9997 36,
+                          2.44921e-15 20 48,
+                          6.18034 19.0211 48,
+                          6.17955 19.021 36,
+                          11.7545 16.1809 36,
+                          2.44921e-15 20 48,
+                          6.17955 19.021 36,
+                          6.18034 19.0211 48,
+                          11.7557 16.1803 48,
+                          11.7545 16.1809 36,
+                          16.1794 11.7568 36,
+                          6.18034 19.0211 48,
+                          11.7545 16.1809 36,
+                          11.7557 16.1803 48,
+                          16.1803 11.7557 48,
+                          16.1794 11.7568 36,
+                          19.0208 6.18136 36,
+                          11.7557 16.1803 48,
+                          16.1794 11.7568 36,
+                          16.1803 11.7557 48,
+                          19.0211 6.18034 48,
+                          19.0208 6.18136 36,
+                          20 -9.21821e-15 36,
+                          16.1803 11.7557 48,
+                          19.0208 6.18136 36,
+                          19.0211 6.18034 48,
+                          20 -1.18827e-14 48,
+                          20 -9.21821e-15 36,
+                          19.0208 -6.18136 36,
+                          19.0211 6.18034 48,
+                          20 -9.21821e-15 36,
+                          20 -1.18827e-14 48,
+                          19.0211 -6.18034 48,
+                          19.0208 -6.18136 36,
+                          16.1794 -11.7568 36,
+                          19.0211 -6.18034 48,
+                          20 -1.18827e-14 48,
+                          19.0208 -6.18136 36,
+                          16.1803 -11.7557 48,
+                          16.1794 -11.7568 36,
+                          11.7545 -16.1809 36,
+                          19.0211 -6.18034 48,
+                          16.1794 -11.7568 36,
+                          16.1803 -11.7557 48,
+                          11.7557 -16.1803 48,
+                          11.7545 -16.1809 36,
+                          6.17955 -19.021 36,
+                          16.1803 -11.7557 48,
+                          11.7545 -16.1809 36,
+                          11.7557 -16.1803 48,
+                          6.18034 -19.0211 48,
+                          6.17955 -19.021 36,
+                          -2.44583e-15 -19.9997 36,
+                          11.7557 -16.1803 48,
+                          6.17955 -19.021 36,
+                          6.18034 -19.0211 48,
+                          -4.89843e-15 -20 48,
+                          -2.44583e-15 -19.9997 36,
+                          -6.17955 -19.021 36,
+                          6.18034 -19.0211 48,
+                          -2.44583e-15 -19.9997 36,
+                          -4.89843e-15 -20 48,
+                          -6.18034 -19.0211 48,
+                          -6.17955 -19.021 36,
+                          -11.7545 -16.1809 36,
+                          -4.89843e-15 -20 48,
+                          -6.17955 -19.021 36,
+                          -6.18034 -19.0211 48,
+                          -11.7557 -16.1803 48,
+                          -11.7545 -16.1809 36,
+                          -16.1794 -11.7568 36,
+                          -6.18034 -19.0211 48,
+                          -11.7545 -16.1809 36,
+                          -11.7557 -16.1803 48,
+                          -16.1803 -11.7557 48,
+                          -16.1794 -11.7568 36,
+                          -19.0208 -6.18136 36,
+                          -11.7557 -16.1803 48,
+                          -16.1794 -11.7568 36,
+                          -16.1803 -11.7557 48,
+                          -16.1803 -11.7557 48,
+                          -19.0208 -6.18136 36,
+                          -19.0211 -6.18034 48,
+                          -20.7853 -11.9985 48,
+                          -21.651 -12.4988 48,
+                          -25 -9.12738e-15 48,
+                          -25 -1.37903e-14 69,
+                          -25 -9.12738e-15 48,
+                          -21.651 -12.4988 48,
+                          -24 -9.18861e-15 48,
+                          -25 -9.12738e-15 48,
+                          -21.651 12.4988 48,
+                          -21.651 12.4988 69,
+                          -21.651 12.4988 48,
+                          -25 -9.12738e-15 48,
+                          -20.7853 -11.9985 48,
+                          -25 -9.12738e-15 48,
+                          -24 -9.18861e-15 48,
+                          -21.651 12.4988 69,
+                          -25 -9.12738e-15 48,
+                          -25 -1.37903e-14 69,
+                          -12.001 -20.7837 48,
+                          -12.4988 -21.651 48,
+                          -21.651 -12.4988 48,
+                          -21.651 -12.4988 69,
+                          -21.651 -12.4988 48,
+                          -12.4988 -21.651 48,
+                          -20.7853 -11.9985 48,
+                          -12.001 -20.7837 48,
+                          -21.651 -12.4988 48,
+                          -21.651 -12.4988 69,
+                          -25 -1.37903e-14 69,
+                          -21.651 -12.4988 48,
+                          -2.9128e-15 -23.9996 48,
+                          -3.06152e-15 -25 48,
+                          -12.4988 -21.651 48,
+                          -12.4988 -21.651 69,
+                          -12.4988 -21.651 48,
+                          -3.06152e-15 -25 48,
+                          -12.001 -20.7837 48,
+                          -2.9128e-15 -23.9996 48,
+                          -12.4988 -21.651 48,
+                          -21.651 -12.4988 69,
+                          -12.4988 -21.651 48,
+                          -12.4988 -21.651 69,
+                          -2.9128e-15 -23.9996 48,
+                          12.4988 -21.651 48,
+                          -3.06152e-15 -25 48,
+                          -3.06152e-15 -25 69,
+                          -3.06152e-15 -25 48,
+                          12.4988 -21.651 48,
+                          -12.4988 -21.651 69,
+                          -3.06152e-15 -25 48,
+                          -3.06152e-15 -25 69,
+                          12.001 -20.7837 48,
+                          21.651 -12.4988 48,
+                          12.4988 -21.651 48,
+                          12.4988 -21.651 69,
+                          12.4988 -21.651 48,
+                          21.651 -12.4988 48,
+                          -2.9128e-15 -23.9996 48,
+                          12.001 -20.7837 48,
+                          12.4988 -21.651 48,
+                          -3.06152e-15 -25 69,
+                          12.4988 -21.651 48,
+                          12.4988 -21.651 69,
+                          24 -1.21277e-14 48,
+                          25 -1.21889e-14 48,
+                          21.651 -12.4988 48,
+                          21.651 -12.4988 69,
+                          21.651 -12.4988 48,
+                          25 -1.21889e-14 48,
+                          20.7853 -11.9985 48,
+                          24 -1.21277e-14 48,
+                          21.651 -12.4988 48,
+                          12.001 -20.7837 48,
+                          20.7853 -11.9985 48,
+                          21.651 -12.4988 48,
+                          12.4988 -21.651 69,
+                          21.651 -12.4988 48,
+                          21.651 -12.4988 69,
+                          20.7853 11.9985 48,
+                          21.651 12.4988 48,
+                          25 -1.21889e-14 48,
+                          25 -1.68518e-14 69,
+                          25 -1.21889e-14 48,
+                          21.651 12.4988 48,
+                          24 -1.21277e-14 48,
+                          20.7853 11.9985 48,
+                          25 -1.21889e-14 48,
+                          21.651 -12.4988 69,
+                          25 -1.21889e-14 48,
+                          25 -1.68518e-14 69,
+                          12.001 20.7837 48,
+                          12.4988 21.651 48,
+                          21.651 12.4988 48,
+                          21.651 12.4988 69,
+                          21.651 12.4988 48,
+                          12.4988 21.651 48,
+                          20.7853 11.9985 48,
+                          12.001 20.7837 48,
+                          21.651 12.4988 48,
+                          25 -1.68518e-14 69,
+                          21.651 12.4988 48,
+                          21.651 12.4988 69,
+                          2.62081e-17 23.9996 48,
+                          -3.87697e-21 25 48,
+                          12.4988 21.651 48,
+                          12.4988 21.651 69,
+                          12.4988 21.651 48,
+                          -3.87697e-21 25 48,
+                          12.001 20.7837 48,
+                          2.62081e-17 23.9996 48,
+                          12.4988 21.651 48,
+                          21.651 12.4988 69,
+                          12.4988 21.651 48,
+                          12.4988 21.651 69,
+                          2.62081e-17 23.9996 48,
+                          -12.4988 21.651 48,
+                          -3.87697e-21 25 48,
+                          -3.87697e-21 25 69,
+                          -3.87697e-21 25 48,
+                          -12.4988 21.651 48,
+                          12.4988 21.651 69,
+                          -3.87697e-21 25 48,
+                          -3.87697e-21 25 69,
+                          -12.001 20.7837 48,
+                          -21.651 12.4988 48,
+                          -12.4988 21.651 48,
+                          -12.4988 21.651 69,
+                          -12.4988 21.651 48,
+                          -21.651 12.4988 48,
+                          2.62081e-17 23.9996 48,
+                          -12.001 20.7837 48,
+                          -12.4988 21.651 48,
+                          -3.87697e-21 25 69,
+                          -12.4988 21.651 48,
+                          -12.4988 21.651 69,
+                          -20.7853 11.9985 48,
+                          -24 -9.18861e-15 48,
+                          -21.651 12.4988 48,
+                          -12.001 20.7837 48,
+                          -20.7853 11.9985 48,
+                          -21.651 12.4988 48,
+                          -12.4988 21.651 69,
+                          -21.651 12.4988 48,
+                          -21.651 12.4988 69,
+                          -21.651 -12.4988 69,
+                          -22.9501 -13.2488 69,
+                          -26.5 -1.36985e-14 69,
+                          -26.5 -2.01378e-14 98,
+                          -26.5 -1.36985e-14 69,
+                          -22.9501 -13.2488 69,
+                          -25 -1.37903e-14 69,
+                          -26.5 -1.36985e-14 69,
+                          -22.9501 13.2488 69,
+                          -22.9501 13.2488 98,
+                          -22.9501 13.2488 69,
+                          -26.5 -1.36985e-14 69,
+                          -21.651 -12.4988 69,
+                          -26.5 -1.36985e-14 69,
+                          -25 -1.37903e-14 69,
+                          -22.9501 13.2488 98,
+                          -26.5 -1.36985e-14 69,
+                          -26.5 -2.01378e-14 98,
+                          -12.4988 -21.651 69,
+                          -13.2488 -22.9501 69,
+                          -22.9501 -13.2488 69,
+                          -22.9501 -13.2488 98,
+                          -22.9501 -13.2488 69,
+                          -13.2488 -22.9501 69,
+                          -21.651 -12.4988 69,
+                          -12.4988 -21.651 69,
+                          -22.9501 -13.2488 69,
+                          -22.9501 -13.2488 98,
+                          -26.5 -2.01378e-14 98,
+                          -22.9501 -13.2488 69,
+                          -3.06152e-15 -25 69,
+                          -3.24521e-15 -26.5 69,
+                          -13.2488 -22.9501 69,
+                          -13.2488 -22.9501 98,
+                          -13.2488 -22.9501 69,
+                          -3.24521e-15 -26.5 69,
+                          -12.4988 -21.651 69,
+                          -3.06152e-15 -25 69,
+                          -13.2488 -22.9501 69,
+                          -22.9501 -13.2488 98,
+                          -13.2488 -22.9501 69,
+                          -13.2488 -22.9501 98,
+                          -3.06152e-15 -25 69,
+                          13.2488 -22.9501 69,
+                          -3.24521e-15 -26.5 69,
+                          -3.24521e-15 -26.5 98,
+                          -3.24521e-15 -26.5 69,
+                          13.2488 -22.9501 69,
+                          -13.2488 -22.9501 98,
+                          -3.24521e-15 -26.5 69,
+                          -3.24521e-15 -26.5 98,
+                          12.4988 -21.651 69,
+                          22.9501 -13.2488 69,
+                          13.2488 -22.9501 69,
+                          13.2488 -22.9501 98,
+                          13.2488 -22.9501 69,
+                          22.9501 -13.2488 69,
+                          -3.06152e-15 -25 69,
+                          12.4988 -21.651 69,
+                          13.2488 -22.9501 69,
+                          -3.24521e-15 -26.5 98,
+                          13.2488 -22.9501 69,
+                          13.2488 -22.9501 98,
+                          25 -1.68518e-14 69,
+                          26.5 -1.69437e-14 69,
+                          22.9501 -13.2488 69,
+                          22.9501 -13.2488 98,
+                          22.9501 -13.2488 69,
+                          26.5 -1.69437e-14 69,
+                          21.651 -12.4988 69,
+                          25 -1.68518e-14 69,
+                          22.9501 -13.2488 69,
+                          12.4988 -21.651 69,
+                          21.651 -12.4988 69,
+                          22.9501 -13.2488 69,
+                          13.2488 -22.9501 98,
+                          22.9501 -13.2488 69,
+                          22.9501 -13.2488 98,
+                          21.651 12.4988 69,
+                          22.9501 13.2488 69,
+                          26.5 -1.69437e-14 69,
+                          26.5 -2.3383e-14 98,
+                          26.5 -1.69437e-14 69,
+                          22.9501 13.2488 69,
+                          25 -1.68518e-14 69,
+                          21.651 12.4988 69,
+                          26.5 -1.69437e-14 69,
+                          22.9501 -13.2488 98,
+                          26.5 -1.69437e-14 69,
+                          26.5 -2.3383e-14 98,
+                          12.4988 21.651 69,
+                          13.2488 22.9501 69,
+                          22.9501 13.2488 69,
+                          22.9501 13.2488 98,
+                          22.9501 13.2488 69,
+                          13.2488 22.9501 69,
+                          21.651 12.4988 69,
+                          12.4988 21.651 69,
+                          22.9501 13.2488 69,
+                          26.5 -2.3383e-14 98,
+                          22.9501 13.2488 69,
+                          22.9501 13.2488 98,
+                          -3.87697e-21 25 69,
+                          -3.87697e-21 26.5 69,
+                          13.2488 22.9501 69,
+                          13.2488 22.9501 98,
+                          13.2488 22.9501 69,
+                          -3.87697e-21 26.5 69,
+                          12.4988 21.651 69,
+                          -3.87697e-21 25 69,
+                          13.2488 22.9501 69,
+                          22.9501 13.2488 98,
+                          13.2488 22.9501 69,
+                          13.2488 22.9501 98,
+                          -3.87697e-21 25 69,
+                          -13.2488 22.9501 69,
+                          -3.87697e-21 26.5 69,
+                          -3.87697e-21 26.5 98,
+                          -3.87697e-21 26.5 69,
+                          -13.2488 22.9501 69,
+                          13.2488 22.9501 98,
+                          -3.87697e-21 26.5 69,
+                          -3.87697e-21 26.5 98,
+                          -12.4988 21.651 69,
+                          -22.9501 13.2488 69,
+                          -13.2488 22.9501 69,
+                          -13.2488 22.9501 98,
+                          -13.2488 22.9501 69,
+                          -22.9501 13.2488 69,
+                          -3.87697e-21 25 69,
+                          -12.4988 21.651 69,
+                          -13.2488 22.9501 69,
+                          -3.87697e-21 26.5 98,
+                          -13.2488 22.9501 69,
+                          -13.2488 22.9501 98,
+                          -21.651 12.4988 69,
+                          -25 -1.37903e-14 69,
+                          -22.9501 13.2488 69,
+                          -12.4988 21.651 69,
+                          -21.651 12.4988 69,
+                          -22.9501 13.2488 69,
+                          -13.2488 22.9501 98,
+                          -22.9501 13.2488 69,
+                          -22.9501 13.2488 98,
+                          -22.9501 -13.2488 98,
+                          -23.8161 -13.7487 98,
+                          -27.5 -2.00765e-14 98,
+                          -27.5 -2.49615e-14 120,
+                          -27.5 -2.00765e-14 98,
+                          -23.8161 -13.7487 98,
+                          -26.5 -2.01378e-14 98,
+                          -27.5 -2.00765e-14 98,
+                          -23.8161 13.7487 98,
+                          -23.8161 13.7487 120,
+                          -23.8161 13.7487 98,
+                          -27.5 -2.00765e-14 98,
+                          -22.9501 -13.2488 98,
+                          -27.5 -2.00765e-14 98,
+                          -26.5 -2.01378e-14 98,
+                          -23.8161 13.7487 120,
+                          -27.5 -2.00765e-14 98,
+                          -27.5 -2.49615e-14 120,
+                          -13.2488 -22.9501 98,
+                          -13.7487 -23.8161 98,
+                          -23.8161 -13.7487 98,
+                          -23.8161 -13.7487 120,
+                          -23.8161 -13.7487 98,
+                          -13.7487 -23.8161 98,
+                          -22.9501 -13.2488 98,
+                          -13.2488 -22.9501 98,
+                          -23.8161 -13.7487 98,
+                          -23.8161 -13.7487 120,
+                          -27.5 -2.49615e-14 120,
+                          -23.8161 -13.7487 98,
+                          -3.24521e-15 -26.5 98,
+                          -3.36767e-15 -27.5 98,
+                          -13.7487 -23.8161 98,
+                          -13.7487 -23.8161 120,
+                          -13.7487 -23.8161 98,
+                          -3.36767e-15 -27.5 98,
+                          -13.2488 -22.9501 98,
+                          -3.24521e-15 -26.5 98,
+                          -13.7487 -23.8161 98,
+                          -23.8161 -13.7487 120,
+                          -13.7487 -23.8161 98,
+                          -13.7487 -23.8161 120,
+                          -3.24521e-15 -26.5 98,
+                          13.7487 -23.8161 98,
+                          -3.36767e-15 -27.5 98,
+                          -3.36767e-15 -27.5 120,
+                          -3.36767e-15 -27.5 98,
+                          13.7487 -23.8161 98,
+                          -13.7487 -23.8161 120,
+                          -3.36767e-15 -27.5 98,
+                          -3.36767e-15 -27.5 120,
+                          13.2488 -22.9501 98,
+                          23.8161 -13.7487 98,
+                          13.7487 -23.8161 98,
+                          13.7487 -23.8161 120,
+                          13.7487 -23.8161 98,
+                          23.8161 -13.7487 98,
+                          -3.24521e-15 -26.5 98,
+                          13.2488 -22.9501 98,
+                          13.7487 -23.8161 98,
+                          -3.36767e-15 -27.5 120,
+                          13.7487 -23.8161 98,
+                          13.7487 -23.8161 120,
+                          26.5 -2.3383e-14 98,
+                          27.5 -2.34442e-14 98,
+                          23.8161 -13.7487 98,
+                          23.8161 -13.7487 120,
+                          23.8161 -13.7487 98,
+                          27.5 -2.34442e-14 98,
+                          22.9501 -13.2488 98,
+                          26.5 -2.3383e-14 98,
+                          23.8161 -13.7487 98,
+                          13.2488 -22.9501 98,
+                          22.9501 -13.2488 98,
+                          23.8161 -13.7487 98,
+                          13.7487 -23.8161 120,
+                          23.8161 -13.7487 98,
+                          23.8161 -13.7487 120,
+                          22.9501 13.2488 98,
+                          23.8161 13.7487 98,
+                          27.5 -2.34442e-14 98,
+                          27.5 -2.83292e-14 120,
+                          27.5 -2.34442e-14 98,
+                          23.8161 13.7487 98,
+                          26.5 -2.3383e-14 98,
+                          22.9501 13.2488 98,
+                          27.5 -2.34442e-14 98,
+                          23.8161 -13.7487 120,
+                          27.5 -2.34442e-14 98,
+                          27.5 -2.83292e-14 120,
+                          13.2488 22.9501 98,
+                          13.7487 23.8161 98,
+                          23.8161 13.7487 98,
+                          23.8161 13.7487 120,
+                          23.8161 13.7487 98,
+                          13.7487 23.8161 98,
+                          22.9501 13.2488 98,
+                          13.2488 22.9501 98,
+                          23.8161 13.7487 98,
+                          27.5 -2.83292e-14 120,
+                          23.8161 13.7487 98,
+                          23.8161 13.7487 120,
+                          -3.87697e-21 26.5 98,
+                          -3.87697e-21 27.5 98,
+                          13.7487 23.8161 98,
+                          13.7487 23.8161 120,
+                          13.7487 23.8161 98,
+                          -3.87697e-21 27.5 98,
+                          13.2488 22.9501 98,
+                          -3.87697e-21 26.5 98,
+                          13.7487 23.8161 98,
+                          23.8161 13.7487 120,
+                          13.7487 23.8161 98,
+                          13.7487 23.8161 120,
+                          -3.87697e-21 26.5 98,
+                          -13.7487 23.8161 98,
+                          -3.87697e-21 27.5 98,
+                          -3.87697e-21 27.5 120,
+                          -3.87697e-21 27.5 98,
+                          -13.7487 23.8161 98,
+                          13.7487 23.8161 120,
+                          -3.87697e-21 27.5 98,
+                          -3.87697e-21 27.5 120,
+                          -13.2488 22.9501 98,
+                          -23.8161 13.7487 98,
+                          -13.7487 23.8161 98,
+                          -13.7487 23.8161 120,
+                          -13.7487 23.8161 98,
+                          -23.8161 13.7487 98,
+                          -3.87697e-21 26.5 98,
+                          -13.2488 22.9501 98,
+                          -13.7487 23.8161 98,
+                          -3.87697e-21 27.5 120,
+                          -13.7487 23.8161 98,
+                          -13.7487 23.8161 120,
+                          -22.9501 13.2488 98,
+                          -26.5 -2.01378e-14 98,
+                          -23.8161 13.7487 98,
+                          -13.2488 22.9501 98,
+                          -22.9501 13.2488 98,
+                          -23.8161 13.7487 98,
+                          -13.7487 23.8161 120,
+                          -23.8161 13.7487 98,
+                          -23.8161 13.7487 120,
+                          -23.8161 -13.7487 120,
+                          -27.4796 -13.2335 120,
+                          -30.5 -2.47778e-14 120,
+                          -30.5 -2.52219e-14 122,
+                          -30.5 -2.47778e-14 120,
+                          -27.4796 -13.2335 120,
+                          -27.5 -2.49615e-14 120,
+                          -30.5 -2.47778e-14 120,
+                          -27.4796 13.2335 120,
+                          -27.4796 13.2335 122,
+                          -27.4796 13.2335 120,
+                          -30.5 -2.47778e-14 120,
+                          -23.8161 -13.7487 120,
+                          -30.5 -2.47778e-14 120,
+                          -27.5 -2.49615e-14 120,
+                          -27.4796 13.2335 122,
+                          -30.5 -2.47778e-14 120,
+                          -30.5 -2.52219e-14 122,
+                          -13.7487 -23.8161 120,
+                          -19.0164 -23.8459 120,
+                          -27.4796 -13.2335 120,
+                          -27.4796 -13.2335 122,
+                          -27.4796 -13.2335 120,
+                          -19.0164 -23.8459 120,
+                          -23.8161 -13.7487 120,
+                          -13.7487 -23.8161 120,
+                          -27.4796 -13.2335 120,
+                          -27.4796 -13.2335 122,
+                          -30.5 -2.52219e-14 122,
+                          -27.4796 -13.2335 120,
+                          6.78689 -29.7353 120,
+                          -6.78689 -29.7353 120,
+                          -19.0164 -23.8459 120,
+                          -19.0164 -23.8459 122,
+                          -19.0164 -23.8459 120,
+                          -6.78689 -29.7353 120,
+                          -3.36767e-15 -27.5 120,
+                          6.78689 -29.7353 120,
+                          -19.0164 -23.8459 120,
+                          -13.7487 -23.8161 120,
+                          -3.36767e-15 -27.5 120,
+                          -19.0164 -23.8459 120,
+                          -27.4796 -13.2335 122,
+                          -19.0164 -23.8459 120,
+                          -19.0164 -23.8459 122,
+                          -6.78689 -29.7353 122,
+                          -6.78689 -29.7353 120,
+                          6.78689 -29.7353 120,
+                          -19.0164 -23.8459 122,
+                          -6.78689 -29.7353 120,
+                          -6.78689 -29.7353 122,
+                          -3.36767e-15 -27.5 120,
+                          19.0164 -23.8459 120,
+                          6.78689 -29.7353 120,
+                          6.78689 -29.7353 122,
+                          6.78689 -29.7353 120,
+                          19.0164 -23.8459 120,
+                          -6.78689 -29.7353 122,
+                          6.78689 -29.7353 120,
+                          6.78689 -29.7353 122,
+                          23.8161 -13.7487 120,
+                          27.4796 -13.2335 120,
+                          19.0164 -23.8459 120,
+                          19.0164 -23.8459 122,
+                          19.0164 -23.8459 120,
+                          27.4796 -13.2335 120,
+                          13.7487 -23.8161 120,
+                          23.8161 -13.7487 120,
+                          19.0164 -23.8459 120,
+                          -3.36767e-15 -27.5 120,
+                          13.7487 -23.8161 120,
+                          19.0164 -23.8459 120,
+                          6.78689 -29.7353 122,
+                          19.0164 -23.8459 120,
+                          19.0164 -23.8459 122,
+                          27.5 -2.83292e-14 120,
+                          30.5 -2.85129e-14 120,
+                          27.4796 -13.2335 120,
+                          27.4796 -13.2335 122,
+                          27.4796 -13.2335 120,
+                          30.5 -2.85129e-14 120,
+                          23.8161 -13.7487 120,
+                          27.5 -2.83292e-14 120,
+                          27.4796 -13.2335 120,
+                          19.0164 -23.8459 122,
+                          27.4796 -13.2335 120,
+                          27.4796 -13.2335 122,
+                          23.8161 13.7487 120,
+                          27.4796 13.2335 120,
+                          30.5 -2.85129e-14 120,
+                          30.5 -2.8957e-14 122,
+                          30.5 -2.85129e-14 120,
+                          27.4796 13.2335 120,
+                          27.5 -2.83292e-14 120,
+                          23.8161 13.7487 120,
+                          30.5 -2.85129e-14 120,
+                          27.4796 -13.2335 122,
+                          30.5 -2.85129e-14 120,
+                          30.5 -2.8957e-14 122,
+                          13.7487 23.8161 120,
+                          19.0164 23.8459 120,
+                          27.4796 13.2335 120,
+                          27.4796 13.2335 122,
+                          27.4796 13.2335 120,
+                          19.0164 23.8459 120,
+                          23.8161 13.7487 120,
+                          13.7487 23.8161 120,
+                          27.4796 13.2335 120,
+                          30.5 -2.8957e-14 122,
+                          27.4796 13.2335 120,
+                          27.4796 13.2335 122,
+                          -6.78689 29.7353 120,
+                          6.78689 29.7353 120,
+                          19.0164 23.8459 120,
+                          19.0164 23.8459 122,
+                          19.0164 23.8459 120,
+                          6.78689 29.7353 120,
+                          -3.87697e-21 27.5 120,
+                          -6.78689 29.7353 120,
+                          19.0164 23.8459 120,
+                          13.7487 23.8161 120,
+                          -3.87697e-21 27.5 120,
+                          19.0164 23.8459 120,
+                          27.4796 13.2335 122,
+                          19.0164 23.8459 120,
+                          19.0164 23.8459 122,
+                          6.78689 29.7353 122,
+                          6.78689 29.7353 120,
+                          -6.78689 29.7353 120,
+                          19.0164 23.8459 122,
+                          6.78689 29.7353 120,
+                          6.78689 29.7353 122,
+                          -3.87697e-21 27.5 120,
+                          -19.0164 23.8459 120,
+                          -6.78689 29.7353 120,
+                          -6.78689 29.7353 122,
+                          -6.78689 29.7353 120,
+                          -19.0164 23.8459 120,
+                          6.78689 29.7353 122,
+                          -6.78689 29.7353 120,
+                          -6.78689 29.7353 122,
+                          -23.8161 13.7487 120,
+                          -27.4796 13.2335 120,
+                          -19.0164 23.8459 120,
+                          -19.0164 23.8459 122,
+                          -19.0164 23.8459 120,
+                          -27.4796 13.2335 120,
+                          -13.7487 23.8161 120,
+                          -23.8161 13.7487 120,
+                          -19.0164 23.8459 120,
+                          -3.87697e-21 27.5 120,
+                          -13.7487 23.8161 120,
+                          -19.0164 23.8459 120,
+                          -6.78689 29.7353 122,
+                          -19.0164 23.8459 120,
+                          -19.0164 23.8459 122,
+                          -23.8161 13.7487 120,
+                          -27.5 -2.49615e-14 120,
+                          -27.4796 13.2335 120,
+                          -19.0164 23.8459 122,
+                          -27.4796 13.2335 120,
+                          -27.4796 13.2335 122,
+                          -27.4796 -13.2335 122,
+                          -40.6501 -16.8395 122,
+                          -44 -2.43953e-14 122,
+                          -44 -2.55055e-14 127,
+                          -44 -2.43953e-14 122,
+                          -40.6501 -16.8395 122,
+                          -30.5 -2.52219e-14 122,
+                          -44 -2.43953e-14 122,
+                          -40.6501 16.8395 122,
+                          -40.6501 16.8395 127,
+                          -40.6501 16.8395 122,
+                          -44 -2.43953e-14 122,
+                          -27.4796 -13.2335 122,
+                          -44 -2.43953e-14 122,
+                          -30.5 -2.52219e-14 122,
+                          -40.6501 16.8395 127,
+                          -44 -2.43953e-14 122,
+                          -44 -2.55055e-14 127,
+                          -6.78689 -29.7353 122,
+                          -31.1113 -31.1138 122,
+                          -40.6501 -16.8395 122,
+                          -40.6501 -16.8395 127,
+                          -40.6501 -16.8395 122,
+                          -31.1113 -31.1138 122,
+                          -19.0164 -23.8459 122,
+                          -6.78689 -29.7353 122,
+                          -40.6501 -16.8395 122,
+                          -27.4796 -13.2335 122,
+                          -19.0164 -23.8459 122,
+                          -40.6501 -16.8395 122,
+                          -40.6501 -16.8395 127,
+                          -44 -2.55055e-14 127,
+                          -40.6501 -16.8395 122,
+                          16.8369 -40.6508 122,
+                          -16.8369 -40.6508 122,
+                          -31.1113 -31.1138 122,
+                          -31.1113 -31.1138 127,
+                          -31.1113 -31.1138 122,
+                          -16.8369 -40.6508 122,
+                          31.1113 -31.1138 122,
+                          16.8369 -40.6508 122,
+                          -31.1113 -31.1138 122,
+                          -6.78689 -29.7353 122,
+                          31.1113 -31.1138 122,
+                          -31.1113 -31.1138 122,
+                          -40.6501 -16.8395 127,
+                          -31.1113 -31.1138 122,
+                          -31.1113 -31.1138 127,
+                          16.8369 -40.6508 122,
+                          -4.69252e-15 -43.9996 122,
+                          -16.8369 -40.6508 122,
+                          -16.8369 -40.6508 127,
+                          -16.8369 -40.6508 122,
+                          -4.69252e-15 -43.9996 122,
+                          -31.1113 -31.1138 127,
+                          -16.8369 -40.6508 122,
+                          -16.8369 -40.6508 127,
+                          -4.69252e-15 -43.9996 127,
+                          -4.69252e-15 -43.9996 122,
+                          16.8369 -40.6508 122,
+                          -16.8369 -40.6508 127,
+                          -4.69252e-15 -43.9996 122,
+                          -4.69252e-15 -43.9996 127,
+                          16.8369 -40.6508 127,
+                          16.8369 -40.6508 122,
+                          31.1113 -31.1138 122,
+                          -4.69252e-15 -43.9996 127,
+                          16.8369 -40.6508 122,
+                          16.8369 -40.6508 127,
+                          19.0164 -23.8459 122,
+                          40.6501 -16.8395 122,
+                          31.1113 -31.1138 122,
+                          31.1113 -31.1138 127,
+                          31.1113 -31.1138 122,
+                          40.6501 -16.8395 122,
+                          6.78689 -29.7353 122,
+                          19.0164 -23.8459 122,
+                          31.1113 -31.1138 122,
+                          -6.78689 -29.7353 122,
+                          6.78689 -29.7353 122,
+                          31.1113 -31.1138 122,
+                          16.8369 -40.6508 127,
+                          31.1113 -31.1138 122,
+                          31.1113 -31.1138 127,
+                          30.5 -2.8957e-14 122,
+                          44 -2.97836e-14 122,
+                          40.6501 -16.8395 122,
+                          40.6501 -16.8395 127,
+                          40.6501 -16.8395 122,
+                          44 -2.97836e-14 122,
+                          27.4796 -13.2335 122,
+                          30.5 -2.8957e-14 122,
+                          40.6501 -16.8395 122,
+                          19.0164 -23.8459 122,
+                          27.4796 -13.2335 122,
+                          40.6501 -16.8395 122,
+                          31.1113 -31.1138 127,
+                          40.6501 -16.8395 122,
+                          40.6501 -16.8395 127,
+                          27.4796 13.2335 122,
+                          40.6501 16.8395 122,
+                          44 -2.97836e-14 122,
+                          44 -3.08938e-14 127,
+                          44 -2.97836e-14 122,
+                          40.6501 16.8395 122,
+                          30.5 -2.8957e-14 122,
+                          27.4796 13.2335 122,
+                          44 -2.97836e-14 122,
+                          40.6501 -16.8395 127,
+                          44 -2.97836e-14 122,
+                          44 -3.08938e-14 127,
+                          6.78689 29.7353 122,
+                          31.1113 31.1138 122,
+                          40.6501 16.8395 122,
+                          40.6501 16.8395 127,
+                          40.6501 16.8395 122,
+                          31.1113 31.1138 122,
+                          19.0164 23.8459 122,
+                          6.78689 29.7353 122,
+                          40.6501 16.8395 122,
+                          27.4796 13.2335 122,
+                          19.0164 23.8459 122,
+                          40.6501 16.8395 122,
+                          44 -3.08938e-14 127,
+                          40.6501 16.8395 122,
+                          40.6501 16.8395 127,
+                          -16.8369 40.6508 122,
+                          16.8369 40.6508 122,
+                          31.1113 31.1138 122,
+                          31.1113 31.1138 127,
+                          31.1113 31.1138 122,
+                          16.8369 40.6508 122,
+                          -31.1113 31.1138 122,
+                          -16.8369 40.6508 122,
+                          31.1113 31.1138 122,
+                          6.78689 29.7353 122,
+                          -31.1113 31.1138 122,
+                          31.1113 31.1138 122,
+                          40.6501 16.8395 127,
+                          31.1113 31.1138 122,
+                          31.1113 31.1138 127,
+                          -16.8369 40.6508 122,
+                          6.95707e-16 43.9996 122,
+                          16.8369 40.6508 122,
+                          16.8369 40.6508 127,
+                          16.8369 40.6508 122,
+                          6.95707e-16 43.9996 122,
+                          31.1113 31.1138 127,
+                          16.8369 40.6508 122,
+                          16.8369 40.6508 127,
+                          6.95707e-16 43.9996 127,
+                          6.95707e-16 43.9996 122,
+                          -16.8369 40.6508 122,
+                          16.8369 40.6508 127,
+                          6.95707e-16 43.9996 122,
+                          6.95707e-16 43.9996 127,
+                          -16.8369 40.6508 127,
+                          -16.8369 40.6508 122,
+                          -31.1113 31.1138 122,
+                          6.95707e-16 43.9996 127,
+                          -16.8369 40.6508 122,
+                          -16.8369 40.6508 127,
+                          -19.0164 23.8459 122,
+                          -40.6501 16.8395 122,
+                          -31.1113 31.1138 122,
+                          -31.1113 31.1138 127,
+                          -31.1113 31.1138 122,
+                          -40.6501 16.8395 122,
+                          -6.78689 29.7353 122,
+                          -19.0164 23.8459 122,
+                          -31.1113 31.1138 122,
+                          6.78689 29.7353 122,
+                          -6.78689 29.7353 122,
+                          -31.1113 31.1138 122,
+                          -16.8369 40.6508 127,
+                          -31.1113 31.1138 122,
+                          -31.1113 31.1138 127,
+                          -27.4796 13.2335 122,
+                          -30.5 -2.52219e-14 122,
+                          -40.6501 16.8395 122,
+                          -19.0164 23.8459 122,
+                          -27.4796 13.2335 122,
+                          -40.6501 16.8395 122,
+                          -31.1113 31.1138 127,
+                          -40.6501 16.8395 122,
+                          -40.6501 16.8395 127,
+                          -40.6501 -16.8395 127,
+                          -20.7853 -11.9985 127,
+                          -24 -2.67301e-14 127,
+                          -44 -2.55055e-14 127,
+                          -24 -2.67301e-14 127,
+                          -20.7853 11.9985 127,
+                          -40.6501 -16.8395 127,
+                          -24 -2.67301e-14 127,
+                          -44 -2.55055e-14 127,
+                          -40.6501 -16.8395 127,
+                          -12.001 -20.7837 127,
+                          -20.7853 -11.9985 127,
+                          -31.1113 -31.1138 127,
+                          -2.9128e-15 -23.9996 127,
+                          -12.001 -20.7837 127,
+                          -40.6501 -16.8395 127,
+                          -31.1113 -31.1138 127,
+                          -12.001 -20.7837 127,
+                          40.6501 -16.8395 127,
+                          12.001 -20.7837 127,
+                          -2.9128e-15 -23.9996 127,
+                          -31.1113 -31.1138 127,
+                          40.6501 -16.8395 127,
+                          -2.9128e-15 -23.9996 127,
+                          40.6501 -16.8395 127,
+                          20.7853 -11.9985 127,
+                          12.001 -20.7837 127,
+                          44 -3.08938e-14 127,
+                          24 -2.96692e-14 127,
+                          20.7853 -11.9985 127,
+                          40.6501 -16.8395 127,
+                          44 -3.08938e-14 127,
+                          20.7853 -11.9985 127,
+                          40.6501 16.8395 127,
+                          20.7853 11.9985 127,
+                          24 -2.96692e-14 127,
+                          44 -3.08938e-14 127,
+                          40.6501 16.8395 127,
+                          24 -2.96692e-14 127,
+                          40.6501 16.8395 127,
+                          12.001 20.7837 127,
+                          20.7853 11.9985 127,
+                          31.1113 31.1138 127,
+                          2.62081e-17 23.9996 127,
+                          12.001 20.7837 127,
+                          40.6501 16.8395 127,
+                          31.1113 31.1138 127,
+                          12.001 20.7837 127,
+                          -40.6501 16.8395 127,
+                          -12.001 20.7837 127,
+                          2.62081e-17 23.9996 127,
+                          31.1113 31.1138 127,
+                          -40.6501 16.8395 127,
+                          2.62081e-17 23.9996 127,
+                          -40.6501 16.8395 127,
+                          -20.7853 11.9985 127,
+                          -12.001 20.7837 127,
+                          -40.6501 16.8395 127,
+                          -44 -2.55055e-14 127,
+                          -20.7853 11.9985 127,
+                          31.1113 31.1138 127,
+                          -31.1113 31.1138 127,
+                          -40.6501 16.8395 127,
+                          16.8369 40.6508 127,
+                          -16.8369 40.6508 127,
+                          -31.1113 31.1138 127,
+                          31.1113 31.1138 127,
+                          16.8369 40.6508 127,
+                          -31.1113 31.1138 127,
+                          16.8369 40.6508 127,
+                          6.95707e-16 43.9996 127,
+                          -16.8369 40.6508 127,
+                          -31.1113 -31.1138 127,
+                          31.1113 -31.1138 127,
+                          40.6501 -16.8395 127,
+                          -16.8369 -40.6508 127,
+                          16.8369 -40.6508 127,
+                          31.1113 -31.1138 127,
+                          -31.1113 -31.1138 127,
+                          -16.8369 -40.6508 127,
+                          31.1113 -31.1138 127,
+                          -16.8369 -40.6508 127,
+                          -4.69252e-15 -43.9996 127,
+                          16.8369 -40.6508 127 ]
+        }
+        FaceSet {
+            numVertices [ 3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3,
+                              3, 3, 3, 3, 3, 3, 3, 3 ]
+        }
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/armar/torso/hd_torso2.wrl b/data/RobotAPI/robots/Armar3/fullmodel/armar/torso/hd_torso2.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..64d9346e887476dcdedba86f15f4ffd98a204f34
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/armar/torso/hd_torso2.wrl
@@ -0,0 +1,1532 @@
+#VRML V2.0 utf8
+
+# Generated by VCGLIB, (C)Copyright 1999-2001 VCG, IEI-CNR
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 1 1 1
+  translation 0 0 0
+  children
+  [
+    Shape
+    {
+      geometry IndexedFaceSet
+      {
+        creaseAngle .5
+        solid FALSE
+        coord Coordinate
+        {
+          point
+          [
+            25.97 -111 509, 36 -111 361, -1 -111 361, -1 -117 361, 
+            18.97 -111 509, 10.97 -111 509, -26.9162 -111 482.374, -36 -111 361, 
+            -36 -117 361, 45 -111 476, 45 -111 361, 36 -117 361, 
+            45 -117 361, 45 -117 476, 25.97 -117 509, 18.97 -117 509, 
+            -39.9973 -111 491.876, -81.03 -111 509, 10.97 -117 509, -30.0027 -111 491.876, 
+            -35 -111 493.5, -26.9162 -111 487.626, -94 -111 361, -96.03 -111 509, 
+            -81.03 -117 509, -43.0838 -111 487.626, -115 -111 361, -115 -111 476, 
+            -96.03 -117 509, -115 -117 476, -115 -117 361, -39.9973 -111 478.124, 
+            -94 -117 361, -43.0838 -111 482.374, -30.0027 -111 478.124, -35 -111 476.5, 
+            -35 -122 493.5, -39.9973 -122 491.876, -30.0027 -122 491.876, -26.9162 -122 487.626, 
+            -26.9162 -122 482.374, -30.0027 -122 478.124, -35 -122 476.5, -39.9973 -122 478.124, 
+            -43.0838 -122 482.374, -43.0838 -122 487.626, -31.1373 -117 473.112, -22.5 -117 485, 
+            -24.8873 -117 477.653, -47.5 -117 485, -45.1127 -117 477.653, -38.8627 -117 473.112, 
+            -31.1373 -117 496.888, -38.8627 -117 496.888, -45.1127 -117 492.347, -24.8873 -117 492.347, 
+            -22.5 -122 485, -24.8889 -122 477.651, -24.8889 -122 492.349, -31.1386 -122 496.888, 
+            -38.8614 -122 496.888, -45.1111 -122 492.349, -47.5 -122 485, -45.1111 -122 477.651, 
+            -38.8614 -122 473.112, -31.1386 -122 473.112, -95.97 111 509, -106 111 361, 
+            -69 111 361, -69 117 361, -88.97 111 509, -80.97 111 509, 
+            -43.0838 111 482.374, -34 111 361, -34 117 361, -115 111 476, 
+            -115 111 361, -106 117 361, -115 117 361, -115 117 476, 
+            -95.97 117 509, -88.97 117 509, -30.0027 111 491.876, 11.03 111 509, 
+            -80.97 117 509, -39.9973 111 491.876, -35 111 493.5, -43.0838 111 487.626, 
+            24 111 361, 26.03 111 509, 11.03 117 509, -26.9162 111 487.626, 
+            45 111 361, 45 111 476, 26.03 117 509, 45 117 476, 
+            45 117 361, -30.0027 111 478.124, 24 117 361, -26.9162 111 482.374, 
+            -39.9973 111 478.124, -35 111 476.5, -35 122 493.5, -30.0027 122 491.876, 
+            -39.9973 122 491.876, -43.0838 122 487.626, -43.0838 122 482.374, -39.9973 122 478.124, 
+            -35 122 476.5, -30.0027 122 478.124, -26.9162 122 482.374, -26.9162 122 487.626, 
+            -38.8627 117 473.112, -47.5 117 485, -45.1127 117 477.653, -22.5 117 485, 
+            -24.8873 117 477.653, -31.1373 117 473.112, -38.8627 117 496.888, -31.1373 117 496.888, 
+            -24.8873 117 492.347, -45.1127 117 492.347, -47.5 122 485, -45.1111 122 477.651, 
+            -45.1111 122 492.349, -38.8614 122 496.888, -31.1386 122 496.888, -24.8889 122 492.349, 
+            -22.5 122 485, -24.8889 122 477.651, -31.1386 122 473.112, -38.8614 122 473.112, 
+            -106 119.941 357, -106 110.941 357, -115 110.941 357, -115 110.941 361, 
+            -100 144.941 357, -115 129.941 357, -115 129.941 361, -106 110.941 361, 
+            -87.5 138.441 357, -106 119.941 361, -74 170.941 357, -69 119.941 357, 
+            -87.5 138.441 361, 45 170.941 357, -69 110.941 357, -69 119.941 361, 
+            -34 119.496 357, -34 110.941 357, -69 110.941 361, -34 110.941 361, 
+            17 148.941 357, -34 119.496 361, 45 148.941 357, 17 148.941 361, 
+            45 148.941 361, 45 170.941 361, -74 170.941 361, -100 144.941 361, 
+            -106 -120 361, -106 -111 361, -115 -111 361, -115 -111 357, 
+            -100 -145 361, -115 -130 361, -115 -130 357, -106 -111 357, 
+            -87.5 -138.5 361, -106 -120 357, -74 -171 361, -69 -120 361, 
+            -87.5 -138.5 357, 45 -171 361, -69 -111 361, -69 -120 357, 
+            -34 -119.555 361, -34 -111 361, -69 -111 357, -34 -111 357, 
+            17 -149 361, -34 -119.555 357, 45 -149 361, 17 -149 357, 
+            45 -149 357, 45 -171 357, -74 -171 357, -100 -145 357, 
+            -81 -110.34 488, -84 -110.34 488, -84 -117 488, -84 -117 431, 
+            -81 -117 488, -81 -109.046 488.171, -84 -111 431, -84 -111 406, 
+            -84 -109.046 488.171, -81 -111 431, -81 -81 406, -81 -117 431, 
+            -81 -111 406, -84 -81 406, -84 -107.84 488.67, -84 -81 415.5, 
+            -84 111 431, -81 111 406, -84 111 406, -81 81 406, 
+            -84 81 406, -81 111 431, -81 110.34 488, -81 109.046 488.171, 
+            -81 107.84 488.67, -81 81 415.5, -84 117 431, -81 117 431, 
+            -84 110.34 488, -84 117 488, -81 117 488, -84 109.046 488.171, 
+            -81 60.8949 515, -84 46.5 515, -81 46.5 515, -84 43.6724 516.171, 
+            -81 77 419.5, -81 43.6724 516.171, -84 60.8949 515, -84 -77 419.5, 
+            -81 62.1888 514.829, -84 62.1888 514.829, -84 -60.8949 515, -81 -46.5 515, 
+            -84 -46.5 515, -81 -43.6724 516.171, -84 -43.6724 516.171, -81 -60.8949 515, 
+            -84 -62.1888 514.829, -81 -62.1888 514.829, -84 63.3949 514.33, -81 63.3949 514.33, 
+            -81 79.8276 418.329, -84 107.84 488.67, -84 77 419.5, -84 79.8276 418.329, 
+            -84 81 415.5, -81 -63.3949 514.33, -84 -63.3949 514.33, -84 -79.8293 418.328, 
+            -81 -107.84 488.67, -81 -77 419.5, -81 -79.8293 418.328, -81 -81 415.5, 
+            -84 42.5 519, -84 42.5 535, -84 -42.5 519, -81 42.5 519, 
+            -84 -42.5 535, -81 42.5 535, -81 -42.5 535, -81 -42.5 519, 
+            14 -110.34 488, 11 -110.34 488, 11 -117 488, 11 -117 431, 
+            14 -117 488, 14 -109.046 488.171, 11 -111 431, 11 -111 406, 
+            11 -109.046 488.171, 14 -111 431, 14 -81 406, 14 -117 431, 
+            14 -111 406, 11 -81 406, 11 -107.84 488.67, 11 -81 415.5, 
+            11 111 431, 14 111 406, 11 111 406, 14 81 406, 
+            11 81 406, 14 111 431, 14 110.34 488, 14 109.046 488.171, 
+            14 107.84 488.67, 14 81 415.5, 11 117 431, 14 117 431, 
+            11 110.34 488, 11 117 488, 14 117 488, 11 109.046 488.171, 
+            14 60.8949 515, 11 46.5 515, 14 46.5 515, 11 43.6724 516.171, 
+            14 77 419.5, 14 43.6724 516.171, 11 60.8949 515, 11 -77 419.5, 
+            14 62.1888 514.829, 11 62.1888 514.829, 11 -60.8949 515, 14 -46.5 515, 
+            11 -46.5 515, 14 -43.6724 516.171, 11 -43.6724 516.171, 14 -60.8949 515, 
+            11 -62.1888 514.829, 14 -62.1888 514.829, 11 63.3949 514.33, 14 63.3949 514.33, 
+            14 79.8276 418.329, 11 107.84 488.67, 11 77 419.5, 11 79.8276 418.329, 
+            11 81 415.5, 14 -63.3949 514.33, 11 -63.3949 514.33, 11 -79.8293 418.328, 
+            14 -107.84 488.67, 14 -77 419.5, 14 -79.8293 418.328, 14 -81 415.5, 
+            11 42.5 519, 11 42.5 535, 11 -42.5 519, 14 42.5 519, 
+            11 -42.5 535, 14 42.5 535, 14 -42.5 535, 14 -42.5 519, 
+            -118 -81 381, -118 -119 361, -118 -119 466, -115 -119 466, 
+            -118 -81 428, -118 -109 466, -115 -109 466, -118 -71 158, 
+            -118 -119 357, -115 -119 361, -118 -130 357, -115 -119 357, 
+            -118 -130 320.282, -115 -130 357, -118 -170 251, -115 -130 320.282, 
+            -118 -175 251, -115 -170 251, -118 -61 131, -118 -175 131, 
+            -115 -175 251, -115 -175 131, -118 -61 158, -115 -61 131, 
+            -115 -61 158, -118 -71 381, -115 -71 158, -115 -71 381, 
+            -115 -81 381, -118 -81 466, -115 -81 428, -115 -81 466, 
+            -115 71 281, -115 54 281, -115 54 131, -118 54 131, 
+            -115 170 251, -115 175 251, -115 175 131, -118 175 131, 
+            -118 54 281, -115 81 381, -115 71 381, -118 71 281, 
+            -115 119 361, -115 119 357, -115 130 357, -115 130 320.282, 
+            -118 71 381, -115 119 466, -115 81 428, -118 81 381, 
+            -115 109 466, -115 81 466, -118 81 428, -118 81 466, 
+            -118 109 466, -118 119 466, -118 119 361, -118 119 357, 
+            -118 130 357, -118 130 320.282, -118 170 251, -118 175 251, 
+            14 42.5 535, 14 -42.5 535, -1 -42.5 535, -1 -42.5 540, 
+            -1 42.5 535, -31 -42.5 535, -31 -42.5 540, 14 -42.5 540, 
+            14 42.5 540, -48 42.5 535, -1 42.5 540, -84 -42.5 535, 
+            -84 42.5 535, -48 42.5 540, -84 42.5 540, -84 -42.5 540, 
+            -98 83 220.5, -129 111.183 220.5, -129 117.817 220.5, -129 114.5 219.5, 
+            -129 146 220.5, -129 146 230.5, -129 119.786 222.662, -157 118.749 221.264, 
+            -157 114.505 219.5, -115 83 220.5, -129 83 220.5, -129 109.214 222.662, 
+            -157 110.257 221.257, -129 83 230.5, -129 111.183 230.5, -129 109.214 228.338, 
+            -129 108.5 225.5, -115 83 230.5, -115 146 220.5, -98 146 220.5, 
+            -98 83 230.5, -98 146 230.5, -115 146 230.5, -129 117.817 230.5, 
+            -129 119.786 228.338, -129 114.5 231.5, -157 118.743 229.743, -157 114.495 231.5, 
+            -129 120.5 225.5, -157 110.251 229.736, -157 108.5 225.5, -157 120.5 225.5, 
+            -168.385 107.986 229.736, -164.247 107.546 225.5, -170.009 111.908 231.5, -171.635 115.832 229.743, 
+            -172.307 117.455 225.5, -171.637 115.838 221.264, -170.013 111.916 219.5, -168.388 107.992 221.257, 
+            -157 42.2499 221.265, -157 50.7434 221.258, -157 52.5 225.5, -168.388 53.0078 221.257, 
+            -157 40.5 225.5, -157 50.7501 229.735, -164.247 53.4541 225.5, -157 46.4953 219.5, 
+            -170.013 49.0837 219.5, -171.637 45.1623 221.264, -172.307 43.5448 225.5, -157 42.2566 229.742, 
+            -171.635 45.1684 229.743, -157 46.5047 231.5, -170.009 49.0924 231.5, -168.385 53.0139 229.736, 
+            -171 104.749 225.5, -178.037 101.537 229.736, -176.799 100.299 225.5, -184.486 91.8851 229.736, 
+            -181.249 94.5 225.5, -178.042 101.542 221.257, -184.046 87.7469 225.5, -184.492 91.8876 221.257, 
+            -186.751 80.5 229.736, -185 80.5 225.5, -184.486 69.1149 229.736, -184.046 73.2531 225.5, 
+            -186.757 80.5 221.257, -181.249 66.5 225.5, -184.492 69.1124 221.257, -178.037 59.4631 229.736, 
+            -176.799 60.701 225.5, -171 56.2513 225.5, -178.042 59.4584 221.257, -181.038 56.4617 231.5, 
+            -188.408 67.4906 231.5, -190.995 80.5 231.5, -188.408 93.5094 231.5, -181.038 104.538 231.5, 
+            -184.042 53.4584 229.743, -192.332 65.8652 229.743, -195.243 80.5 229.743, -192.332 95.1348 229.743, 
+            -184.042 107.542 229.743, -185.284 52.2157 225.5, -193.955 65.1927 225.5, -197 80.5 225.5, 
+            -193.955 95.8073 225.5, -185.284 108.784 225.5, -184.046 53.4537 221.264, -192.338 65.8626 221.264, 
+            -195.249 80.5 221.264, -192.338 95.1374 221.264, -184.046 107.546 221.264, -181.045 56.455 219.5, 
+            -188.416 67.487 219.5, -191.005 80.5 219.5, -188.416 93.513 219.5, -181.045 104.545 219.5, 
+            -98 83 243.5, -129 111.183 243.5, -129 117.817 243.5, -129 114.5 242.5, 
+            -129 146 243.5, -129 146 253.5, -129 119.786 245.662, -157 118.749 244.264, 
+            -157 114.505 242.5, -115 83 243.5, -129 83 243.5, -129 109.214 245.662, 
+            -157 110.257 244.257, -129 83 253.5, -129 111.183 253.5, -129 109.214 251.338, 
+            -129 108.5 248.5, -115 83 253.5, -115 146 243.5, -98 146 243.5, 
+            -98 83 253.5, -98 146 253.5, -115 146 253.5, -129 117.817 253.5, 
+            -129 119.786 251.338, -129 114.5 254.5, -157 118.743 252.743, -157 114.495 254.5, 
+            -129 120.5 248.5, -157 110.251 252.736, -157 108.5 248.5, -157 120.5 248.5, 
+            -168.385 107.986 252.736, -164.247 107.546 248.5, -170.009 111.908 254.5, -171.635 115.832 252.743, 
+            -172.307 117.455 248.5, -171.637 115.838 244.264, -170.013 111.916 242.5, -168.388 107.992 244.257, 
+            -157 42.2499 244.265, -157 50.7434 244.258, -157 52.5 248.5, -168.388 53.0078 244.257, 
+            -157 40.5 248.5, -157 50.7501 252.735, -164.247 53.4541 248.5, -157 46.4953 242.5, 
+            -170.013 49.0837 242.5, -171.637 45.1623 244.264, -172.307 43.5448 248.5, -157 42.2566 252.742, 
+            -171.635 45.1684 252.743, -157 46.5047 254.5, -170.009 49.0924 254.5, -168.385 53.0139 252.736, 
+            -171 104.749 248.5, -178.037 101.537 252.736, -176.799 100.299 248.5, -184.486 91.8851 252.736, 
+            -181.249 94.5 248.5, -178.042 101.542 244.257, -184.046 87.7469 248.5, -184.492 91.8876 244.257, 
+            -186.751 80.5 252.736, -185 80.5 248.5, -184.486 69.1149 252.736, -184.046 73.2531 248.5, 
+            -186.757 80.5 244.257, -181.249 66.5 248.5, -184.492 69.1124 244.257, -178.037 59.4631 252.736, 
+            -176.799 60.701 248.5, -171 56.2513 248.5, -178.042 59.4584 244.257, -181.038 56.4617 254.5, 
+            -188.408 67.4906 254.5, -190.995 80.5 254.5, -188.408 93.5094 254.5, -181.038 104.538 254.5, 
+            -184.042 53.4584 252.743, -192.332 65.8652 252.743, -195.243 80.5 252.743, -192.332 95.1348 252.743, 
+            -184.042 107.542 252.743, -185.284 52.2157 248.5, -193.955 65.1927 248.5, -197 80.5 248.5, 
+            -193.955 95.8073 248.5, -185.284 108.784 248.5, -184.046 53.4537 244.264, -192.338 65.8626 244.264, 
+            -195.249 80.5 244.264, -192.338 95.1374 244.264, -184.046 107.546 244.264, -181.045 56.455 242.5, 
+            -188.416 67.487 242.5, -191.005 80.5 242.5, -188.416 93.513 242.5, -181.045 104.545 242.5, 
+            -116 110.549 441.217, -116 109.5 446, -116 106.425 438.575, -140 106.425 438.575, 
+            -116 107.839 437.161, -116 99 435.5, -140 99 435.5, -116 111.5 446, 
+            -116 106.425 453.425, -140 109.5 446, -116 99.0005 458.5, -116 99 456.5, 
+            -140 106.425 453.425, -116 110.548 450.784, -116 90.1612 454.839, -116 91.5754 453.425, 
+            -140 99 456.5, -116 94.2169 457.549, -116 87.4514 450.783, -116 88.5001 446, 
+            -140 91.5754 453.425, -116 86.5001 446, -116 91.5754 438.575, -140 88.5001 446, 
+            -116 98.9995 433.5, -140 91.5754 438.575, -116 87.4517 441.216, -116 103.783 434.451, 
+            -118 107.839 437.161, -118 110.549 441.217, -118 103.783 434.451, -116 94.2162 434.452, 
+            -118 98.9995 433.5, -116 90.1612 437.161, -118 94.2162 434.452, -118 90.1612 437.161, 
+            -118 87.4517 441.216, -118 86.5001 446, -118 87.4514 450.783, -118 90.1612 454.839, 
+            -118 94.2169 457.549, -116 103.784 457.548, -118 99.0005 458.5, -116 107.839 454.839, 
+            -118 103.784 457.548, -118 107.839 454.839, -118 110.548 450.784, -118 111.5 446, 
+            -140 90.1612 454.839, -140 99.0005 458.5, -140 86.5001 446, -140 98.9995 433.5, 
+            -140 90.1612 437.161, -140 107.839 437.161, -140 111.5 446, -140 108.899 436.1, 
+            -140 101.19 432.172, -140 107.839 454.839, -140 112.828 443.81, -140 105.356 458.474, 
+            -140 111.474 452.356, -140 96.8104 459.828, -140 89.1005 455.9, -140 85.1723 448.19, 
+            -140 92.644 433.526, -140 86.5261 439.644, -135 101.19 432.172, -135 108.899 436.1, 
+            -135 92.644 433.526, -135 86.5261 439.644, -135 85.1723 448.19, -135 89.1005 455.9, 
+            -135 96.8104 459.828, -135 90.8683 454.132, -135 99 457.5, -135 90.8683 437.868, 
+            -135 87.5001 446, -135 99 434.5, -135 107.132 437.868, -135 112.828 443.81, 
+            -135 110.5 446, -120 107.132 437.868, -120 99 434.5, -135 107.132 454.132, 
+            -120 110.5 446, -120 107.132 454.132, -135 111.474 452.356, -120 99 457.5, 
+            -120 90.8683 454.132, -120 87.5001 446, -120 90.8683 437.868, -135 105.356 458.474, 
+            -120 85.565 459.435, -120 96.0275 464.766, -120 80.234 448.972, -120 101.972 427.234, 
+            -120 90.3738 429.071, -120 112.435 432.565, -120 117.766 443.028, -118 112.435 432.565, 
+            -118 101.972 427.234, -120 107.626 462.929, -120 115.929 454.626, -118 117.766 443.028, 
+            -118 115.929 454.626, -118 107.626 462.929, -118 96.0275 464.766, -118 85.565 459.435, 
+            -120 82.0711 437.374, -118 80.234 448.972, -118 82.0711 437.374, -118 90.3738 429.071, 
+            -116 -103.783 434.451, -116 -99 435.5, -116 -106.425 438.575, -140 -106.425 438.575, 
+            -116 -107.839 437.161, -116 -109.5 446, -140 -109.5 446, -116 -98.9995 433.5, 
+            -116 -91.5754 438.575, -140 -99 435.5, -116 -86.5001 446, -116 -88.5001 446, 
+            -140 -91.5754 438.575, -116 -94.2162 434.452, -116 -90.1612 454.839, -116 -91.5754 453.425, 
+            -140 -88.5001 446, -116 -87.4514 450.783, -116 -94.2169 457.549, -116 -99 456.5, 
+            -140 -91.5754 453.425, -116 -99.0005 458.5, -116 -106.425 453.425, -140 -99 456.5, 
+            -116 -111.5 446, -140 -106.425 453.425, -116 -103.784 457.548, -116 -110.549 441.217, 
+            -118 -107.839 437.161, -118 -103.783 434.451, -118 -110.549 441.217, -116 -110.548 450.784, 
+            -118 -111.5 446, -116 -107.839 454.839, -118 -110.548 450.784, -118 -107.839 454.839, 
+            -118 -103.784 457.548, -118 -99.0005 458.5, -118 -94.2169 457.549, -118 -90.1612 454.839, 
+            -118 -87.4514 450.783, -116 -87.4517 441.216, -118 -86.5001 446, -116 -90.1612 437.161, 
+            -118 -87.4517 441.216, -118 -90.1612 437.161, -118 -94.2162 434.452, -118 -98.9995 433.5, 
+            -140 -90.1612 454.839, -140 -86.5001 446, -140 -99.0005 458.5, -140 -111.5 446, 
+            -140 -107.839 454.839, -140 -107.839 437.161, -140 -98.9995 433.5, -140 -108.899 436.1, 
+            -140 -112.828 443.81, -140 -90.1612 437.161, -140 -101.19 432.172, -140 -86.5261 439.644, 
+            -140 -92.644 433.526, -140 -85.1723 448.19, -140 -89.1005 455.9, -140 -96.8104 459.828, 
+            -140 -111.474 452.356, -140 -105.356 458.474, -135 -112.828 443.81, -135 -108.899 436.1, 
+            -135 -111.474 452.356, -135 -105.356 458.474, -135 -96.8104 459.828, -135 -89.1005 455.9, 
+            -135 -85.1723 448.19, -135 -90.8683 454.132, -135 -87.5001 446, -135 -107.132 454.132, 
+            -135 -99 457.5, -135 -110.5 446, -135 -107.132 437.868, -135 -101.19 432.172, 
+            -135 -99 434.5, -120 -107.132 437.868, -120 -110.5 446, -135 -90.8683 437.868, 
+            -120 -99 434.5, -120 -90.8683 437.868, -135 -92.644 433.526, -120 -87.5001 446, 
+            -120 -90.8683 454.132, -120 -99 457.5, -120 -107.132 454.132, -135 -86.5261 439.644, 
+            -120 -85.565 459.435, -120 -80.234 448.972, -120 -96.0275 464.766, -120 -117.766 443.028, 
+            -120 -115.929 454.626, -120 -112.435 432.565, -120 -101.972 427.234, -118 -112.435 432.565, 
+            -118 -117.766 443.028, -120 -82.0711 437.374, -120 -90.3738 429.071, -118 -101.972 427.234, 
+            -118 -90.3738 429.071, -118 -82.0711 437.374, -118 -80.234 448.972, -118 -85.565 459.435, 
+            -120 -107.626 462.929, -118 -96.0275 464.766, -118 -107.626 462.929, -118 -115.929 454.626, 
+            48.5449 115 567, 14.8041 82.9463 567, 47.2102 66 567, 47.2102 66 566, 
+            48.5449 66 567, 48.5449 66 566.667, 48.5449 66 566.333, 48.5449 66 566, 
+            -20.4705 92.5699 567, 14.8041 82.9463 566, -57 94.4281 567, -20.4705 92.5699 566, 
+            -57 115 567, -57 94.4281 566, -57 115 566, 48.854 65.9743 566.956, 
+            49.1673 115 566.806, 49.5716 115 566.295, 48.5449 115 566, 49.1462 65.8965 566.821, 
+            48.7177 65.9837 566.647, -57 -115 567, -29.1903 -93.6551 567, -57 -94.4281 567, 
+            -57 -94.4281 566, -57 -115 566, -1.89655 -88.1989 567, -29.1903 -93.6551 566, 
+            24.0854 -78.2163 567, -1.89655 -88.1989 566, 48.5449 -64 567, 48 -64 567, 
+            24.0854 -78.2163 566, 48.5449 -115 567, 48.5449 -64 566.667, 48.5449 -64 566.333, 
+            48.5449 -64 566, 48 -64 566, 49.1673 -115 566.806, 48.854 -63.9743 566.956, 
+            48.5449 -115 566, 57.3044 -51.9904 546.199, 49.5716 -63.593 566.295, 49.5716 -115 566.295, 
+            49.3952 -63.7686 566.598, 95.5836 115 446.718, 95.5836 -115 446.718, 94.6503 -115 446.359, 
+            48.6383 -115 565.936, 48.5996 65.8965 565.984, 48.7372 65.9339 566.288, 49.2605 -63.593 566.175, 
+            49.1668 -63.7372 566.348, 62.768 1 532, 56.3711 -51.9904 545.84, 48.9491 -63.593 566.055, 
+            48.6383 -63.593 565.936, 57.3044 53.9904 546.199, 61.8347 1 531.641, 49.5716 65.593 566.295, 
+            56.3711 53.9904 545.84, 49.3952 65.7686 566.598, 49.2605 65.593 566.175, 48.6383 115 565.936, 
+            48.6222 65.7686 565.963, 48.8234 65.851 566.232, 95.6904 -115 446.326, 95.6904 115 446.326, 
+            95.7154 115 445.919, 94.6503 115 446.359, 94.065 -115 405.045, 95.7154 -115 445.919, 
+            93.0658 -115 405.085, 94.7037 -115 446.163, 94.7162 -115 445.96, 94.065 115 405.045, 
+            94.7162 115 445.96, 94.7037 115 446.163, 93.9165 -115.312 401.365, 93.9165 115.312 401.365, 
+            93.0658 115 405.085, 93.7723 -116.237 397.794, 93.7723 116.237 397.794, 92.9173 115.312 401.405, 
+            88.6339 -116.237 270.534, 88.6339 116.237 270.534, 88.6296 116.369 270.535, 93.7537 116.366 397.437, 
+            92.7357 116.368 397.124, 92.7731 116.237 397.835, 92.7566 116.301 397.478, 86.3288 -101.202 213.442, 
+            88.6339 116.5 270.534, 87.6348 116.5 270.575, 87.6348 116.237 270.575, 86.3288 101.202 213.442, 
+            86.2033 -100.793 210.336, 86.1275 100.943 208.459, 85.3296 101.202 213.483, 86.2666 -100.896 211.903, 
+            85.9395 -102.729 203.801, 85.9395 102.729 203.801, 85.1284 100.943 208.5, 86.0657 -101.288 206.928, 
+            85.2036 -114.564 185.577, 85.2036 114.564 185.577, 84.9403 102.729 203.841, 84.9862 -116.445 180.191, 
+            84.9862 116.445 180.191, 84.2044 114.564 185.617, 84.7582 -115.626 174.546, 84.7582 115.626 174.546, 
+            83.987 116.445 180.232, 83 -98.0326 131, 83 98.0326 131, 83.759 115.626 174.586, 
+            82.0008 98.0326 131.04, 82.0008 -98.0326 131.04, 83.759 -115.626 174.586, 83.987 -116.445 180.232, 
+            84.2044 -114.564 185.617, 84.9403 -102.729 203.841, 85.0665 -101.288 206.968, 85.2042 -100.793 210.377, 
+            85.2674 -100.896 211.943, 88.6339 -116.5 270.534, 85.3296 -101.202 213.483, 87.6348 -116.237 270.575, 
+            87.6348 -116.5 270.575, 93.7536 -116.366 397.435, 88.6164 -116.501 270.535, 88.6296 -116.369 270.535, 
+            92.7731 -116.237 397.835, 92.9173 -115.312 401.405, 75.6316 178.518 360.407, 75.5763 178.724 360.409, 
+            75.5957 178.762 361.138, 74.6112 178.465 360.448, 88.5729 116.754 270.713, 93.6695 116.754 396.938, 
+            92.7043 116.496 396.977, 74.6306 178.503 361.177, 74.6664 178.259 360.446, 73.7975 178.518 314.982, 
+            73.294 179.4 315.002, 75.1281 179.4 360.427, 73.4006 180 314.998, 72.8323 178.259 315.021, 
+            72.1529 178.958 315.048, 72.5806 178.7 315.031, 72.4354 179.741 315.037, 93.7019 116.628 397.01, 
+            88.5987 116.629 270.625, 87.626 116.369 270.575, 87.6078 116.496 270.752, 87.6189 116.433 270.664, 
+            75.5763 -178.724 360.409, 93.6695 -116.754 396.938, 75.5957 -178.762 361.138, 74.6306 -178.503 361.177, 
+            73.7975 -178.518 314.982, 88.5729 -116.754 270.713, 88.5987 -116.629 270.625, 75.6316 -178.518 360.407, 
+            93.7019 -116.628 397.01, 92.7357 -116.368 397.124, 92.7043 -116.496 396.977, 92.7221 -116.432 397.05, 
+            73.4006 -180 314.998, 87.6078 -116.496 270.752, 72.4354 -179.741 315.037, 75.1281 -179.4 360.427, 
+            73.294 -179.4 315.002, 72.8323 -178.259 315.021, 74.6112 -178.465 360.448, 73.9871 -178.958 360.473, 
+            74.4147 -178.7 360.456, 74.6664 -178.259 360.446, 15 -180 360.773, 71.8672 -180 315.06, 
+            73.7008 -180 360.471, 72.1616 -179.978 315.048, 15 -179 360.773, 73.8926 -179.991 360.47, 
+            73.7008 -179 360.471, 15 -180 317.356, 14.9073 -180 315.06, 71.8672 -179 315.06, 
+            72.4387 -179.916 315.036, 72.1529 -178.958 315.048, 72.0144 -178.989 315.054, 14.9073 -179 315.06, 
+            15 -179 317.356, 14.9073 180 315.06, 73.7008 180 360.471, 71.8672 180 315.06, 
+            73.8926 179.991 360.47, 14.9073 179 315.06, 72.1616 179.978 315.048, 72.0144 178.989 315.054, 
+            71.8672 179 315.06, 15 180 317.356, 15 180 360.773, 73.7008 179 360.471, 
+            48.8961 65.7372 566.153, 15 179 360.773, 15 179 317.356, 49.1462 -63.8965 566.821, 
+            48.8853 -63.9339 566.587, 48.7177 -63.9837 566.647, 49.038 -63.851 566.487, 49.038 65.851 566.487, 
+            49.1668 65.7372 566.348, 48.8853 65.9339 566.587, 88.6164 116.501 270.535, 93.7262 116.5 397.084, 
+            92.7221 116.432 397.05, 48.6425 65.9837 566.322, 93.7262 -116.5 397.084, 87.6189 -116.433 270.664, 
+            87.626 -116.369 270.575, 92.7565 -116.302 397.475, 74.0826 -179.963 360.469, 74.1787 -179.942 360.465, 
+            73.8919 -178.982 360.477, 74.2728 -179.916 360.461, 72.5806 -178.7 315.031, 74.2728 179.916 360.461, 
+            72.4387 179.916 315.036, 74.1787 179.942 360.465, 74.0826 179.963 360.469, 73.9871 178.958 360.473, 
+            74.4147 178.7 360.456, 73.8919 178.982 360.477, 48.8961 -63.7372 566.153, 48.6222 -63.7686 565.963, 
+            48.9491 65.593 566.055, 48.6383 65.593 565.936, 48.5996 -63.8965 565.984, 48.6425 -63.9837 566.322, 
+            48.7372 -63.9339 566.288, 48.8234 -63.851 566.232, -164.341 117.456 177.024, -164.348 -117.472 178.111, 
+            -165.806 -117.472 396.371, -164.287 -117.991 179.246, -165.807 117.456 396.563, -165.809 -116.509 396.919, 
+            -164.809 -116.511 396.925, -165.733 -117.997 396.074, -164.806 -117.472 396.378, -164.334 116.992 176, 
+            -164.334 -116.508 176, -163.348 -117.472 178.117, -163.321 -117.731 179.253, -164 116.992 126, 
+            -164 -116.508 126, -163.334 -116.508 176.007, -163 -116.508 126.007, -163 116.992 126.007, 
+            -163.334 116.992 176.007, -165.735 117.981 396.263, -164.28 117.975 178.169, -163.341 117.456 177.031, 
+            -165.809 116.993 396.828, -164.809 116.994 396.834, -164.77 117.717 396.271, -164.807 117.456 396.569, 
+            -165.889 95.984 408.843, -165.907 -90.6468 411.631, -165.936 88.1547 415.871, -164.889 95.984 408.849, 
+            -166 -79.2771 425.497, -166 83.9102 425.497, -164.936 88.1519 415.882, -165.947 -83.6735 417.512, 
+            -166 83.615 427.237, -165 83.9102 425.5, -165 -79.2771 425.5, -166 83.4431 429, 
+            -166 -78.769 427.239, -165 -78.7675 427.246, -164.947 -83.6732 417.519, -164.907 -90.6468 411.637, 
+            -165 83.6156 427.233, -166 -78.3913 429, -165.81 -78.2412 429.956, -165.863 83.406 429.817, 
+            -165 83.4431 429, -165 -78.3913 429, -164.886 -78.2412 429.573, -139.387 114.992 566.383, 
+            -137.9 -115.008 567, -137.9 -61.021 567, -135.465 -71.783 567, -137.9 61.0049 567, 
+            -137.9 61.0049 566, -137.9 -61.021 566, -139.387 -115.008 566.383, -137.9 -115.008 566, 
+            -88.0955 -91.2583 567, -118.738 -85.3297 567, -128.634 -80.4486 567, -57.0616 -94.4326 567, 
+            -57.0616 -115.008 567, -57.0616 -115.008 566, -140 114.992 564.9, -140 -115.008 564.9, 
+            -139 -115.008 564.9, -138.679 -115.008 565.677, -140 -115.008 488.408, -139 114.992 564.9, 
+            -140 114.992 500.125, -140 86.6938 450.644, -140 84.2346 444.653, -139 114.992 500.125, 
+            -140 -86.0247 461.577, -140 -80.0997 453.242, -140 -78.008 443.231, -140 -78.008 433.534, 
+            -137.9 114.992 567, -138.679 114.992 565.677, -135.465 71.767 567, -128.634 80.4326 567, 
+            -118.738 85.3136 567, -57.0616 114.992 567, -137.9 114.992 566, -135.465 71.767 566, 
+            -118.738 -85.3297 566, -128.634 -80.4486 566, -88.0955 -91.2583 566, -57.0616 -94.4326 566, 
+            -135.465 -71.783 566, -88.0955 91.2422 567, -57.0616 94.4165 567, -57.0616 94.4165 566, 
+            -57.0616 114.992 566, -88.0955 91.2422 566, -118.738 85.3136 566, -128.634 80.4326 566, 
+            -165.267 -78.1432 430.769, -164.595 83.3954 431.247, -165.463 83.3954 430.548, -164.678 83.3954 429.929, 
+            -164.918 83.406 429.49, -163.5 -78.0786 431.5, -163.5 83.3954 431.5, -163.5 83.3954 430.5, 
+            -164.453 -78.093 431.311, -164.157 83.3954 430.348, -140.5 83.3954 431.5, -163.5 -78.0786 430.5, 
+            -151.998 -78.0845 431.5, -151.998 -78.0845 430.5, -164.072 -78.093 430.387, -164.56 -78.1432 430.061, 
+            -140.5 -78.0907 431.5, -140.147 -78.0793 431.646, -140.147 83.3954 431.647, -139.441 83.3954 430.941, 
+            -140.5 83.3954 430.5, -140.5 -78.0907 430.5, -139.44 -78.0793 430.939, -140 -78.0552 432, 
+            -140 83.3954 432, -140 83.3954 438.232, -139 83.3954 432, -139 -78.0552 432, 
+            -140 -78.0198 432.766, -139 -78.0198 432.766, -139 86.6938 450.644, -139 84.2346 444.653, 
+            -139 -115.008 488.408, -139 -86.0247 461.577, -139 -80.0997 453.242, -139 -78.008 443.231, 
+            -139 -78.008 433.534, -139 83.3954 438.232, -164.095 -118.472 180.3, -130.35 -179.016 361.598, 
+            -165.534 -118.472 395.804, -164.668 -117.972 395.81, -164.769 -117.734 396.081, -130.024 -179.016 312.851, 
+            -129.283 -179.748 311.444, -129.484 -178.516 361.604, -129.662 -179.72 361.203, -129.158 -178.516 312.856, 
+            -128.783 -178.882 311.448, -163.229 -117.972 180.306, -130.024 179 312.833, -164.088 118.456 179.231, 
+            -165.535 118.456 395.993, -130.35 179 361.601, -129.484 178.5 361.607, -164.669 117.956 395.999, 
+            -163.222 117.956 179.237, -163.314 117.715 178.175, -129.584 179.749 361.178, -129.158 178.5 312.839, 
+            -129.282 179.732 311.436, -129.108 178.87 361.183, -129.139 -178.868 361.206, -128.782 178.866 311.439, 
+            -43.1873 -180.016 361.072, 15 -180.016 315.06, 15 -180.016 360.773, 15 -179.016 360.773, 
+            -43.1873 -179.016 361.072, -48.9627 -180.016 361.033, -128.024 -180.016 312.881, 15 -179.016 315.06, 
+            -128.614 -180.016 361.033, -128.005 -180.016 310.04, -128.024 -179.016 312.881, -128.307 -180.016 310.04, 
+            -128.273 -179.016 310.04, -128.005 -179.016 310.04, -128.793 -180.008 361.044, -128.614 -179.016 361.033, 
+            -48.9627 -179.016 361.033, -128.703 -179.012 361.045, 15 180 315.06, -43.1873 180 361.072, 
+            15 180 360.773, 15 179 360.773, 15 179 315.06, -128.024 180 312.864, 
+            -48.9627 180 361.033, -43.1873 179 361.072, -128.614 180 361.033, -48.9627 179 361.033, 
+            -128.024 180 310.04, -128.307 180 310.04, -128.614 179 361.033, -128.024 179 310.04, 
+            -128.273 179 310.04, -128.024 179 312.864, 58.3073 173.955 131, -128.307 173.955 131, 
+            -113 177 131, -113 177 187, 43 177 131, 71.2843 165.284 131, 
+            -141.284 165.284 131, -134.634 167.271 187, -124.271 173.532 187, 79.9552 152.307 131, 
+            -149.955 152.307 131, -143.271 158.634 187, 83 137 131, -153 137 131, 
+            -149.532 148.271 187, 83 -137 131, -153 -137 131, -153 137 187, 
+            79.9552 -152.307 131, -149.955 -152.307 131, -153 -137 187, -153 137 299.112, 
+            -153 137 355, -153 137 243.056, 71.2843 -165.284 131, -141.284 -165.284 131, 
+            -143.271 -158.634 187, -149.532 -148.271 187, 58.3073 -173.955 131, -128.307 -173.955 131, 
+            -134.634 -167.271 187, 43 -177 131, -113 -177 131, -124.271 -173.532 187, 
+            43 -177 187, -113 -177 187, 64.6336 -167.271 187, 54.2705 -173.532 187, 
+            73.2705 -158.634 187, 79.5317 -148.271 187, 83 -137 187, 83 137 187, 
+            83 -137 299.112, 83 -137 355, 83 -137 243.056, 73.2705 158.634 187, 
+            79.5317 148.271 187, 64.6336 167.271 187, 54.2705 173.532 187, 43 177 187, 
+            -112.586 176 355, 43 177 355, -113 177 355, 43 177 299.112, 
+            -123 167 355, -122.088 170.508 299.112, -113 177 299.112, 42.5858 176 355, 
+            53 167 355, 52.2727 166.312 355, 63 157 355, 60.8741 163.086 299.112, 
+            52.088 170.508 299.112, 62.282 156.302 355, 73 147 355, 69.086 154.874 299.112, 
+            72.2917 146.293 355, 83 137 355, 76.5075 146.088 299.112, 82 -136.586 355, 
+            83 137 299.112, 82 136.586 355, 72.3118 -146.273 355, 73 -147 355, 
+            83 137 243.056, 62.302 -156.282 355, 63 -157 355, 69.086 -154.874 299.112, 
+            76.5075 -146.088 299.112, 52.2928 -166.292 355, 53 -167 355, 60.8741 -163.086 299.112, 
+            42.5858 -176 355, 43 -177 355, 52.088 -170.508 299.112, -113 -177 355, 
+            -113 -177 299.112, 43 -177 299.112, -112.586 -176 355, -123 -167 355, 
+            -122.273 -166.312 355, -133 -157 355, -130.874 -163.086 299.112, -122.088 -170.508 299.112, 
+            -132.282 -156.302 355, -143 -147 355, -139.086 -154.874 299.112, -142.292 -146.293 355, 
+            -153 -137 355, -146.508 -146.088 299.112, -152 136.586 355, -153 -137 299.112, 
+            -152 -136.586 355, -142.312 146.273 355, -143 147 355, -153 -137 243.056, 
+            -132.302 156.282 355, -133 157 355, -139.086 154.874 299.112, -146.508 146.088 299.112, 
+            -122.293 166.292 355, -130.874 163.086 299.112, -152 136.689 299.25, -143.971 147.67 299.24, 
+            -143.953 -147.692 299.24, -152 136.895 187.75, -152 136.999 132, -152 -136.689 299.25, 
+            -152 136.792 243.5, -134.344 -158.364 299.25, -123.67 -167.971 299.24, 42.689 -176 299.25, 
+            -112.689 -176 299.25, 53.6919 -167.953 299.24, 64.364 -158.344 299.25, 73.9711 -147.67 299.24, 
+            82 -136.689 299.25, 73.9532 147.692 299.24, 82 -136.895 187.75, 82 -136.999 132, 
+            82 136.689 299.25, 82 -136.792 243.5, 64.3436 158.364 299.25, 53.6698 167.971 299.24, 
+            -112.689 176 299.25, 42.689 176 299.25, -123.692 167.953 299.24, -134.364 158.344 299.25, 
+            -113 177 243.056, -123.179 172.02 243.056, -132.754 165.178 243.056, -141.178 156.754 243.056, 
+            -148.02 147.179 243.056, 43 177 243.056, -148.02 -147.179 243.056, -141.178 -156.754 243.056, 
+            -132.754 -165.178 243.056, -123.179 -172.02 243.056, -113 -177 243.056, 43 -177 243.056, 
+            53.1792 -172.02 243.056, 62.7538 -165.178 243.056, 71.1783 -156.754 243.056, 78.0196 -147.179 243.056, 
+            78.0196 147.179 243.056, 71.1783 156.754 243.056, 62.7538 165.178 243.056, 53.1792 172.02 243.056, 
+            -127.9 173 132, 42.9987 176 132, -112.999 176 132, 42.8954 176 187.75, 
+            -112.895 176 187.75, 57.8715 173.012 132, 70.5285 164.55 132, 56.4716 171.321 187.746, 
+            -140.55 164.528 132, 79.0001 151.9 132, 77.3071 150.498 187.746, 68.4668 162.488 187.75, 
+            82 136.999 132, 82 136.895 187.75, -149.012 151.871 132, -152 -136.999 132, 
+            -149 -151.9 132, 79.0117 -151.871 132, 82 136.792 243.5, 70.55 -164.528 132, 
+            77.3208 -150.472 187.746, -140.528 -164.55 132, 57.8995 -173 132, 56.4978 -171.307 187.746, 
+            68.488 -162.467 187.75, -112.999 -176 132, 42.9987 -176 132, 42.8954 -176 187.75, 
+            -127.871 -173.012 132, -112.895 -176 187.75, -126.472 -171.321 187.746, -147.307 -150.498 187.746, 
+            -138.467 -162.488 187.75, -152 -136.895 187.75, -152 -136.792 243.5, -147.321 150.472 187.746, 
+            -126.498 171.307 187.746, -138.488 162.467 187.75, -145.64 149.07 243.493, -136.426 160.405 243.5, 
+            -125.094 169.625 243.493, -112.792 176 243.5, 42.7922 176 243.5, -145.625 -149.094 243.493, 
+            -125.07 -169.64 243.493, -136.405 -160.426 243.5, -112.792 -176 243.5, 42.7922 -176 243.5, 
+            55.0944 -169.625 243.493, 75.6404 -149.07 243.493, 66.426 -160.405 243.5, 75.6246 149.094 243.493, 
+            55.0703 169.64 243.493, 66.4052 160.426 243.5, -47 -36.5 583.5, -40.0097 -36.5 596.989, 
+            -34 -36.5 594.5, -34 -37.5 594.5, 4.26326e-014 -36.5 548, -27.9903 -36.5 596.989, 
+            -27.9896 -37.5 596.99, -42.4998 -36.5 603, -40.0104 -37.5 596.99, -47 -36.5 616, 
+            -40.0097 -36.5 609.011, -42.5 -37.5 603, -34 -36.5 611.5, -40.0104 -37.5 609.01, 
+            -22 -36.5 611, -27.9903 -36.5 609.011, -34 -37.5 611.5, -25.5002 -36.5 603, 
+            -27.9896 -37.5 609.01, -25.5 -37.5 603, -27 -36.5 616, -27 -42.5 616, 
+            -22 -42.5 611, -47 -42.5 616, -56 -36.5 583.5, -47 -42.5 583.5, 
+            -47 -36.5 577.5, -56 -36.5 577.5, -56 -42.5 577.5, -56 -42.5 583.5, 
+            -47 -36.5 548, -47 -42.5 577.5, -47 -42.5 548, 7.10543e-014 -36.5 611, 
+            4.9738e-014 -42.5 548, 7.81597e-014 -42.5 611, -27.2833 -42.5 596.282, -34 -42.5 593.5, 
+            -34 -37.5 593.5, -40.7167 -42.5 596.282, -40.7175 -37.5 596.282, -24.5003 -42.5 603, 
+            -27.2825 -37.5 596.282, -27.2833 -42.5 609.718, -24.5 -37.5 603, -34 -42.5 612.5, 
+            -27.2825 -37.5 609.718, -40.7167 -42.5 609.718, -34 -37.5 612.5, -43.4997 -42.5 603, 
+            -40.7175 -37.5 609.718, -43.5 -37.5 603, -47 36.5 610, -40.0097 36.5 609.011, 
+            -34 36.5 611.5, -34 37.5 611.5, -22 36.5 611, -27.9903 36.5 609.011, 
+            -27.9896 37.5 609.01, -27 36.5 616, -47 36.5 596, -42.4998 36.5 603, 
+            -40.0104 37.5 609.01, -40.0097 36.5 596.989, -42.5 37.5 603, -34 36.5 594.5, 
+            -40.0104 37.5 596.99, -30 36.5 579, -27.9903 36.5 596.989, -34 37.5 594.5, 
+            4.9738e-014 36.5 611, -25.5002 36.5 603, -27.9896 37.5 596.99, -25.5 37.5 603, 
+            -30 36.5 548, 2.13163e-014 36.5 548, 1.42109e-014 42.5 548, 4.26326e-014 42.5 611, 
+            -30 42.5 548, -30 42.5 579, -47 42.5 596, -41 36.5 616, 
+            -47 42.5 610, -41 42.5 616, -27 42.5 616, -22 42.5 611, 
+            -27.2826 42.5 609.717, -34 42.5 612.5, -34 37.5 612.5, -40.7174 42.5 609.717, 
+            -40.7167 37.5 609.718, -24.5 42.5 603, -27.2833 37.5 609.718, -27.2826 42.5 596.283, 
+            -24.5003 37.5 603, -34 42.5 593.5, -27.2833 37.5 596.282, -40.7174 42.5 596.283, 
+            -34 37.5 593.5, -43.5 42.5 603, -40.7167 37.5 596.282, -43.4997 37.5 603, 
+            26 -20 548, 26 20 548, 1.42109e-014 42.2 548, 1.42109e-014 42.2 540, 
+            4.26326e-014 -42.2 548, -30 42.2 548, -30 42.2 540, 26 20 540, 
+            26 -20 540, -47 -42.2 548, 4.26326e-014 -42.2 540, -94 20 548, 
+            -94 -20 548, -47 -42.2 540, -94 -20 540, -94 20 540, 
+            -20.7853 -11.9985 132, -19.0208 -6.18136 132, -20 -2.80853e-014 132, -20 -6.98432e-015 48, 
+            -24 -2.78404e-014 132, -19.0208 6.18136 132, -19.0211 6.18034 48, -16.1794 -11.7568 132, 
+            -19.0211 -6.18034 48, -11.7545 -16.1809 132, -16.1803 -11.7557 48, -12.001 -20.7837 132, 
+            -6.17955 -19.021 132, -11.7557 -16.1803 48, -2.44583e-015 -19.9997 132, -6.18034 -19.0211 48, 
+            12.001 -20.7837 132, 6.17955 -19.021 132, -4.89843e-015 -20 48, 20.7853 -11.9985 132, 
+            11.7545 -16.1809 132, 6.18034 -19.0211 48, 16.1794 -11.7568 132, 11.7557 -16.1803 48, 
+            24 -3.07794e-014 132, 19.0208 -6.18136 132, 16.1803 -11.7557 48, 20 -3.05345e-014 132, 
+            19.0211 -6.18034 48, 20.7853 11.9985 132, 19.0208 6.18136 132, 20 -1.18827e-014 48, 
+            16.1794 11.7568 132, 19.0211 6.18034 48, 11.7545 16.1809 132, 16.1803 11.7557 48, 
+            12.001 20.7837 132, 6.17955 19.021 132, 11.7557 16.1803 48, 3.33575e-018 19.9997 132, 
+            6.18034 19.0211 48, -12.001 20.7837 132, -6.17955 19.021 132, 2.44921e-015 20 48, 
+            -20.7853 11.9985 132, -11.7545 16.1809 132, -6.18034 19.0211 48, -16.1794 11.7568 132, 
+            -11.7557 16.1803 48, -16.1803 11.7557 48, -24 -2.67301e-014 127, -20.7853 -11.9985 127, 
+            -20.7853 11.9985 127, 2.62081e-017 23.9996 132, -12.001 20.7837 127, 2.62081e-017 23.9996 127, 
+            12.001 20.7837 127, 20.7853 11.9985 127, 24 -2.96692e-014 127, 20.7853 -11.9985 127, 
+            -2.9128e-015 -23.9996 132, 12.001 -20.7837 127, -2.9128e-015 -23.9996 127, -12.001 -20.7837 127, 
+            -16.1794 -11.7568 36, -20.7853 -11.9985 36, -24 -6.52407e-015 36, -24 -9.18861e-015 48, 
+            -20 -6.76899e-015 36, -20.7853 11.9985 36, -20.7853 11.9985 48, -19.0208 -6.18136 36, 
+            -6.17955 -19.021 36, -12.001 -20.7837 36, -20.7853 -11.9985 48, -11.7545 -16.1809 36, 
+            12.001 -20.7837 36, -2.9128e-015 -23.9996 36, -12.001 -20.7837 48, -2.44583e-015 -19.9997 36, 
+            -2.9128e-015 -23.9996 48, 11.7545 -16.1809 36, 20.7853 -11.9985 36, 12.001 -20.7837 48, 
+            6.17955 -19.021 36, 20 -9.21821e-015 36, 24 -9.46313e-015 36, 20.7853 -11.9985 48, 
+            19.0208 -6.18136 36, 16.1794 -11.7568 36, 16.1794 11.7568 36, 20.7853 11.9985 36, 
+            24 -1.21277e-014 48, 19.0208 6.18136 36, 6.17955 19.021 36, 12.001 20.7837 36, 
+            20.7853 11.9985 48, 11.7545 16.1809 36, -12.001 20.7837 36, 2.62081e-017 23.9996 36, 
+            12.001 20.7837 48, 3.33575e-018 19.9997 36, 2.62081e-017 23.9996 48, -11.7545 16.1809 36, 
+            -12.001 20.7837 48, -6.17955 19.021 36, -19.0208 6.18136 36, -16.1794 11.7568 36, 
+            -21.651 -12.4988 48, -25 -9.12738e-015 48, -25 -1.37903e-014 69, -21.651 12.4988 48, 
+            -21.651 12.4988 69, -12.4988 -21.651 48, -21.651 -12.4988 69, -3.06152e-015 -25 48, 
+            -12.4988 -21.651 69, 12.4988 -21.651 48, -3.06152e-015 -25 69, 21.651 -12.4988 48, 
+            12.4988 -21.651 69, 25 -1.21889e-014 48, 21.651 -12.4988 69, 21.651 12.4988 48, 
+            25 -1.68518e-014 69, 12.4988 21.651 48, 21.651 12.4988 69, -3.87697e-021 25 48, 
+            12.4988 21.651 69, -12.4988 21.651 48, -3.87697e-021 25 69, -12.4988 21.651 69, 
+            -22.9501 -13.2488 69, -26.5 -1.36985e-014 69, -26.5 -2.01378e-014 98, -22.9501 13.2488 69, 
+            -22.9501 13.2488 98, -13.2488 -22.9501 69, -22.9501 -13.2488 98, -3.24521e-015 -26.5 69, 
+            -13.2488 -22.9501 98, 13.2488 -22.9501 69, -3.24521e-015 -26.5 98, 22.9501 -13.2488 69, 
+            13.2488 -22.9501 98, 26.5 -1.69437e-014 69, 22.9501 -13.2488 98, 22.9501 13.2488 69, 
+            26.5 -2.3383e-014 98, 13.2488 22.9501 69, 22.9501 13.2488 98, -3.87697e-021 26.5 69, 
+            13.2488 22.9501 98, -13.2488 22.9501 69, -3.87697e-021 26.5 98, -13.2488 22.9501 98, 
+            -23.8161 -13.7487 98, -27.5 -2.00765e-014 98, -27.5 -2.49615e-014 120, -23.8161 13.7487 98, 
+            -23.8161 13.7487 120, -13.7487 -23.8161 98, -23.8161 -13.7487 120, -3.36767e-015 -27.5 98, 
+            -13.7487 -23.8161 120, 13.7487 -23.8161 98, -3.36767e-015 -27.5 120, 23.8161 -13.7487 98, 
+            13.7487 -23.8161 120, 27.5 -2.34442e-014 98, 23.8161 -13.7487 120, 23.8161 13.7487 98, 
+            27.5 -2.83292e-014 120, 13.7487 23.8161 98, 23.8161 13.7487 120, -3.87697e-021 27.5 98, 
+            13.7487 23.8161 120, -13.7487 23.8161 98, -3.87697e-021 27.5 120, -13.7487 23.8161 120, 
+            -27.4796 -13.2335 120, -30.5 -2.47778e-014 120, -30.5 -2.52219e-014 122, -27.4796 13.2335 120, 
+            -27.4796 13.2335 122, -19.0164 -23.8459 120, -27.4796 -13.2335 122, 6.78689 -29.7353 120, 
+            -6.78689 -29.7353 120, -19.0164 -23.8459 122, -6.78689 -29.7353 122, 19.0164 -23.8459 120, 
+            6.78689 -29.7353 122, 27.4796 -13.2335 120, 19.0164 -23.8459 122, 30.5 -2.85129e-014 120, 
+            27.4796 -13.2335 122, 27.4796 13.2335 120, 30.5 -2.8957e-014 122, 19.0164 23.8459 120, 
+            27.4796 13.2335 122, -6.78689 29.7353 120, 6.78689 29.7353 120, 19.0164 23.8459 122, 
+            6.78689 29.7353 122, -19.0164 23.8459 120, -6.78689 29.7353 122, -19.0164 23.8459 122, 
+            -40.6501 -16.8395 122, -44 -2.43953e-014 122, -44 -2.55055e-014 127, -40.6501 16.8395 122, 
+            -40.6501 16.8395 127, -31.1113 -31.1138 122, -40.6501 -16.8395 127, 16.8369 -40.6508 122, 
+            -16.8369 -40.6508 122, -31.1113 -31.1138 127, 31.1113 -31.1138 122, -4.69252e-015 -43.9996 122, 
+            -16.8369 -40.6508 127, -4.69252e-015 -43.9996 127, 16.8369 -40.6508 127, 40.6501 -16.8395 122, 
+            31.1113 -31.1138 127, 44 -2.97836e-014 122, 40.6501 -16.8395 127, 40.6501 16.8395 122, 
+            44 -3.08938e-014 127, 31.1113 31.1138 122, 40.6501 16.8395 127, -16.8369 40.6508 122, 
+            16.8369 40.6508 122, 31.1113 31.1138 127, -31.1113 31.1138 122, 6.95707e-016 43.9996 122, 
+            16.8369 40.6508 127, 6.95707e-016 43.9996 127, -16.8369 40.6508 127, -31.1113 31.1138 127
+          ]
+        }
+        color Color
+        {
+          color
+          [
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 0.647059 0.647059 0.647059, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            0.498039 0.498039 0, 0.498039 0.498039 0, 0.498039 0.498039 0, 0.498039 0.498039 0, 
+            0.498039 0.498039 0, 0.498039 0.498039 0, 0.498039 0.498039 0, 0.498039 0.498039 0, 
+            0.498039 0.498039 0, 0.498039 0.498039 0, 0.498039 0.498039 0, 0.498039 0.498039 0, 
+            0.498039 0.498039 0, 0.498039 0.498039 0, 0.498039 0.498039 0, 0.498039 0.498039 0, 
+            0.498039 0.498039 0, 0.498039 0.498039 0, 0.498039 0.498039 0, 0.498039 0.498039 0, 
+            0.498039 0.498039 0, 0.498039 0.498039 0, 0.498039 0.498039 0, 0.498039 0.498039 0, 
+            0.498039 0.498039 0, 0.498039 0.498039 0, 0.498039 0.498039 0, 0.498039 0.498039 0, 
+            0.498039 0.498039 0, 0.498039 0.498039 0, 0.498039 0.498039 0, 0.498039 0.498039 0, 
+            0.698039 0.333333 0, 0.698039 0.333333 0, 0.698039 0.333333 0, 0.698039 0.333333 0, 
+            0.698039 0.333333 0, 0.698039 0.333333 0, 0.698039 0.333333 0, 0.698039 0.333333 0, 
+            0.698039 0.333333 0, 0.698039 0.333333 0, 0.698039 0.333333 0, 0.698039 0.333333 0, 
+            0.698039 0.333333 0, 0.698039 0.333333 0, 0.698039 0.333333 0, 0.698039 0.333333 0, 
+            0.698039 0.333333 0, 0.698039 0.333333 0, 0.698039 0.333333 0, 0.698039 0.333333 0, 
+            0.698039 0.333333 0, 0.698039 0.333333 0, 0.698039 0.333333 0, 0.698039 0.333333 0, 
+            0.698039 0.333333 0, 0.698039 0.333333 0, 0.698039 0.333333 0, 0.698039 0.333333 0, 
+            0.698039 0.333333 0, 0.698039 0.333333 0, 0.698039 0.333333 0, 0.698039 0.333333 0, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 1 1, 1 1 1, 1 1 1, 1 1 1, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 1 0.478431 0, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 
+            0.498039 0.498039 0.498039, 0.498039 0.498039 0.498039, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 
+            0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 
+            0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 
+            0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 
+            0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 
+            0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 
+            0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 
+            0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 
+            0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 
+            0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 
+            0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 
+            0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 
+            0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 
+            0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 
+            0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 
+            0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 
+            0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 
+            0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 
+            0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 
+            0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 
+            0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 
+            0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 
+            0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 
+            0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 
+            0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 
+            0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 0.701961 0.52549 0.258824, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 0.87451 0.945098 1, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 
+            0.388235 0 0, 0.388235 0 0, 0.388235 0 0, 0.388235 0 0
+          ]
+        }
+        coordIndex
+        [
+          0,1,2,-1, 3,2,1,-1, 4,0,2,-1, 5,4,2,-1, 6,5,2,-1, 6,2,7,-1, 
+          8,7,2,-1, 8,2,3,-1, 9,10,1,-1, 11,1,10,-1, 0,9,1,-1, 11,3,1,-1, 
+          12,10,9,-1, 11,10,12,-1, 13,9,0,-1, 12,9,13,-1, 14,0,4,-1, 13,0,14,-1, 
+          15,4,5,-1, 14,4,15,-1, 16,17,5,-1, 18,5,17,-1, 19,20,5,-1, 16,5,20,-1, 
+          21,19,5,-1, 6,21,5,-1, 15,5,18,-1, 22,23,17,-1, 24,17,23,-1, 25,22,17,-1, 
+          16,25,17,-1, 18,17,24,-1, 26,27,23,-1, 28,23,27,-1, 22,26,23,-1, 24,23,28,-1, 
+          29,27,26,-1, 28,27,29,-1, 30,26,22,-1, 29,26,30,-1, 31,7,22,-1, 32,22,7,-1, 
+          33,31,22,-1, 25,33,22,-1, 30,22,32,-1, 34,6,7,-1, 35,34,7,-1, 31,35,7,-1, 
+          32,7,8,-1, 36,20,19,-1, 37,16,20,-1, 36,37,20,-1, 38,19,21,-1, 38,36,19,-1, 
+          39,21,6,-1, 39,38,21,-1, 40,6,34,-1, 40,39,6,-1, 41,34,35,-1, 41,40,34,-1, 
+          42,35,31,-1, 41,35,42,-1, 43,31,33,-1, 43,42,31,-1, 44,33,25,-1, 44,43,33,-1, 
+          45,25,16,-1, 45,44,25,-1, 37,45,16,-1, 46,8,3,-1, 11,18,3,-1, 47,3,18,-1, 
+          48,3,47,-1, 48,46,3,-1, 24,32,8,-1, 49,24,8,-1, 50,49,8,-1, 51,50,8,-1, 
+          46,51,8,-1, 29,30,32,-1, 28,29,32,-1, 24,28,32,-1, 52,18,24,-1, 53,52,24,-1, 
+          54,53,24,-1, 49,54,24,-1, 11,15,18,-1, 55,47,18,-1, 52,55,18,-1, 11,14,15,-1, 
+          12,13,14,-1, 11,12,14,-1, 56,47,55,-1, 57,48,47,-1, 57,47,56,-1, 58,55,52,-1, 
+          58,56,55,-1, 59,52,53,-1, 58,52,59,-1, 60,53,54,-1, 59,53,60,-1, 61,54,49,-1, 
+          60,54,61,-1, 62,49,50,-1, 61,49,62,-1, 63,50,51,-1, 62,50,63,-1, 64,51,46,-1, 
+          63,51,64,-1, 65,46,48,-1, 64,46,65,-1, 65,48,57,-1, 63,42,43,-1, 57,41,42,-1, 
+          64,57,42,-1, 63,64,42,-1, 63,43,44,-1, 62,44,45,-1, 62,63,44,-1, 62,45,37,-1, 
+          61,37,36,-1, 61,62,37,-1, 58,36,38,-1, 59,61,36,-1, 58,59,36,-1, 58,38,39,-1, 
+          56,39,40,-1, 58,39,56,-1, 56,40,41,-1, 57,56,41,-1, 64,65,57,-1, 59,60,61,-1, 
+          66,67,68,-1, 69,68,67,-1, 70,66,68,-1, 71,70,68,-1, 72,71,68,-1, 72,68,73,-1, 
+          74,73,68,-1, 74,68,69,-1, 75,76,67,-1, 77,67,76,-1, 66,75,67,-1, 77,69,67,-1, 
+          78,76,75,-1, 77,76,78,-1, 79,75,66,-1, 78,75,79,-1, 80,66,70,-1, 79,66,80,-1, 
+          81,70,71,-1, 80,70,81,-1, 82,83,71,-1, 84,71,83,-1, 85,86,71,-1, 82,71,86,-1, 
+          87,85,71,-1, 72,87,71,-1, 81,71,84,-1, 88,89,83,-1, 90,83,89,-1, 91,88,83,-1, 
+          82,91,83,-1, 84,83,90,-1, 92,93,89,-1, 94,89,93,-1, 88,92,89,-1, 90,89,94,-1, 
+          95,93,92,-1, 94,93,95,-1, 96,92,88,-1, 95,92,96,-1, 97,73,88,-1, 98,88,73,-1, 
+          99,97,88,-1, 91,99,88,-1, 96,88,98,-1, 100,72,73,-1, 101,100,73,-1, 97,101,73,-1, 
+          98,73,74,-1, 102,86,85,-1, 103,82,86,-1, 102,103,86,-1, 104,85,87,-1, 104,102,85,-1, 
+          105,87,72,-1, 105,104,87,-1, 106,72,100,-1, 106,105,72,-1, 107,100,101,-1, 107,106,100,-1, 
+          108,101,97,-1, 107,101,108,-1, 109,97,99,-1, 109,108,97,-1, 110,99,91,-1, 110,109,99,-1, 
+          111,91,82,-1, 111,110,91,-1, 103,111,82,-1, 112,74,69,-1, 77,84,69,-1, 113,69,84,-1, 
+          114,69,113,-1, 114,112,69,-1, 90,98,74,-1, 115,90,74,-1, 116,115,74,-1, 117,116,74,-1, 
+          112,117,74,-1, 95,96,98,-1, 94,95,98,-1, 90,94,98,-1, 118,84,90,-1, 119,118,90,-1, 
+          120,119,90,-1, 115,120,90,-1, 77,81,84,-1, 121,113,84,-1, 118,121,84,-1, 77,80,81,-1, 
+          78,79,80,-1, 77,78,80,-1, 122,113,121,-1, 123,114,113,-1, 123,113,122,-1, 124,121,118,-1, 
+          124,122,121,-1, 125,118,119,-1, 124,118,125,-1, 126,119,120,-1, 125,119,126,-1, 127,120,115,-1, 
+          126,120,127,-1, 128,115,116,-1, 127,115,128,-1, 129,116,117,-1, 128,116,129,-1, 130,117,112,-1, 
+          129,117,130,-1, 131,112,114,-1, 130,112,131,-1, 131,114,123,-1, 129,108,109,-1, 123,107,108,-1, 
+          130,123,108,-1, 129,130,108,-1, 129,109,110,-1, 128,110,111,-1, 128,129,110,-1, 128,111,103,-1, 
+          127,103,102,-1, 127,128,103,-1, 124,102,104,-1, 125,127,102,-1, 124,125,102,-1, 124,104,105,-1, 
+          122,105,106,-1, 124,105,122,-1, 122,106,107,-1, 123,122,107,-1, 130,131,123,-1, 125,126,127,-1, 
+          132,133,134,-1, 135,134,133,-1, 136,132,134,-1, 137,136,134,-1, 138,137,134,-1, 138,134,135,-1, 
+          139,133,132,-1, 139,135,133,-1, 136,140,132,-1, 141,132,140,-1, 139,132,141,-1, 142,143,140,-1, 
+          144,140,143,-1, 136,142,140,-1, 141,140,144,-1, 145,146,143,-1, 147,143,146,-1, 142,145,143,-1, 
+          144,143,147,-1, 148,149,146,-1, 150,146,149,-1, 145,148,146,-1, 147,146,150,-1, 151,149,148,-1, 
+          150,149,151,-1, 145,152,148,-1, 153,148,152,-1, 151,148,153,-1, 145,154,152,-1, 155,152,154,-1, 
+          153,152,155,-1, 156,154,145,-1, 155,154,156,-1, 157,145,142,-1, 156,145,157,-1, 158,142,136,-1, 
+          157,142,158,-1, 159,136,137,-1, 158,136,159,-1, 159,137,138,-1, 139,138,135,-1, 141,159,138,-1, 
+          139,141,138,-1, 144,158,159,-1, 141,144,159,-1, 156,157,158,-1, 155,156,158,-1, 153,155,158,-1, 
+          151,153,158,-1, 147,151,158,-1, 144,147,158,-1, 147,150,151,-1, 160,161,162,-1, 163,162,161,-1, 
+          164,160,162,-1, 165,164,162,-1, 166,165,162,-1, 166,162,163,-1, 167,161,160,-1, 167,163,161,-1, 
+          164,168,160,-1, 169,160,168,-1, 167,160,169,-1, 170,171,168,-1, 172,168,171,-1, 164,170,168,-1, 
+          169,168,172,-1, 173,174,171,-1, 175,171,174,-1, 170,173,171,-1, 172,171,175,-1, 176,177,174,-1, 
+          178,174,177,-1, 173,176,174,-1, 175,174,178,-1, 179,177,176,-1, 178,177,179,-1, 173,180,176,-1, 
+          181,176,180,-1, 179,176,181,-1, 173,182,180,-1, 183,180,182,-1, 181,180,183,-1, 184,182,173,-1, 
+          183,182,184,-1, 185,173,170,-1, 184,173,185,-1, 186,170,164,-1, 185,170,186,-1, 187,164,165,-1, 
+          186,164,187,-1, 187,165,166,-1, 167,166,163,-1, 169,187,166,-1, 167,169,166,-1, 172,186,187,-1, 
+          169,172,187,-1, 184,185,186,-1, 183,184,186,-1, 181,183,186,-1, 179,181,186,-1, 175,179,186,-1, 
+          172,175,186,-1, 175,178,179,-1, 188,189,190,-1, 191,190,189,-1, 192,188,190,-1, 191,192,190,-1, 
+          193,189,188,-1, 194,189,195,-1, 196,195,189,-1, 191,189,194,-1, 193,196,189,-1, 197,188,192,-1, 
+          198,188,197,-1, 198,193,188,-1, 199,197,192,-1, 199,192,191,-1, 197,194,195,-1, 200,197,195,-1, 
+          201,200,195,-1, 196,202,195,-1, 203,195,202,-1, 203,201,195,-1, 199,194,197,-1, 199,191,194,-1, 
+          198,197,200,-1, 198,200,201,-1, 204,205,206,-1, 207,206,205,-1, 208,204,206,-1, 207,208,206,-1, 
+          204,209,205,-1, 210,205,209,-1, 211,205,210,-1, 211,212,205,-1, 213,205,212,-1, 213,207,205,-1, 
+          214,209,204,-1, 215,210,209,-1, 215,209,214,-1, 216,217,204,-1, 214,204,217,-1, 208,216,204,-1, 
+          216,218,217,-1, 215,217,218,-1, 215,214,217,-1, 216,210,218,-1, 215,218,210,-1, 219,210,216,-1, 
+          219,211,210,-1, 208,219,216,-1, 220,221,222,-1, 223,222,221,-1, 224,220,222,-1, 225,222,223,-1, 
+          225,224,222,-1, 220,226,221,-1, 227,221,226,-1, 223,221,227,-1, 228,226,220,-1, 229,226,228,-1, 
+          227,226,229,-1, 224,228,220,-1, 230,231,232,-1, 233,232,231,-1, 227,230,232,-1, 234,227,232,-1, 
+          233,234,232,-1, 230,235,231,-1, 224,231,235,-1, 233,231,224,-1, 236,235,230,-1, 237,235,236,-1, 
+          224,235,237,-1, 227,236,230,-1, 212,238,239,-1, 229,239,238,-1, 213,212,239,-1, 229,228,239,-1, 
+          224,239,228,-1, 240,239,224,-1, 240,213,239,-1, 212,241,238,-1, 242,238,241,-1, 227,229,238,-1, 
+          242,227,238,-1, 211,241,212,-1, 219,241,211,-1, 208,241,219,-1, 243,242,241,-1, 244,243,241,-1, 
+          208,244,241,-1, 202,245,246,-1, 237,246,245,-1, 203,202,246,-1, 237,236,246,-1, 227,246,236,-1, 
+          247,203,246,-1, 227,247,246,-1, 202,248,245,-1, 249,245,248,-1, 224,237,245,-1, 249,224,245,-1, 
+          196,248,202,-1, 193,248,196,-1, 198,248,193,-1, 250,249,248,-1, 251,250,248,-1, 198,251,248,-1, 
+          198,201,203,-1, 251,203,247,-1, 198,203,251,-1, 250,247,227,-1, 251,247,250,-1, 249,227,242,-1, 
+          252,223,227,-1, 253,252,227,-1, 254,253,227,-1, 234,254,227,-1, 250,227,249,-1, 224,242,243,-1, 
+          249,242,224,-1, 240,243,244,-1, 240,224,243,-1, 213,244,208,-1, 240,244,213,-1, 213,208,207,-1, 
+          225,223,252,-1, 255,252,253,-1, 225,252,255,-1, 254,256,253,-1, 257,253,256,-1, 255,253,257,-1, 
+          258,256,254,-1, 257,256,258,-1, 259,254,234,-1, 258,254,259,-1, 259,234,233,-1, 259,233,224,-1, 
+          258,259,224,-1, 255,258,224,-1, 225,255,224,-1, 255,257,258,-1, 260,261,262,-1, 263,262,261,-1, 
+          264,260,262,-1, 263,264,262,-1, 265,261,260,-1, 266,261,267,-1, 268,267,261,-1, 263,261,266,-1, 
+          265,268,261,-1, 269,260,264,-1, 270,260,269,-1, 270,265,260,-1, 271,269,264,-1, 271,264,263,-1, 
+          269,266,267,-1, 272,269,267,-1, 273,272,267,-1, 268,274,267,-1, 275,267,274,-1, 275,273,267,-1, 
+          271,266,269,-1, 271,263,266,-1, 270,269,272,-1, 270,272,273,-1, 276,277,278,-1, 279,278,277,-1, 
+          280,276,278,-1, 279,280,278,-1, 276,281,277,-1, 282,277,281,-1, 283,277,282,-1, 283,284,277,-1, 
+          285,277,284,-1, 285,279,277,-1, 286,281,276,-1, 287,282,281,-1, 287,281,286,-1, 288,289,276,-1, 
+          286,276,289,-1, 280,288,276,-1, 288,290,289,-1, 287,289,290,-1, 287,286,289,-1, 288,282,290,-1, 
+          287,290,282,-1, 291,282,288,-1, 291,283,282,-1, 280,291,288,-1, 292,293,294,-1, 295,294,293,-1, 
+          296,292,294,-1, 297,294,295,-1, 297,296,294,-1, 292,298,293,-1, 299,293,298,-1, 295,293,299,-1, 
+          300,298,292,-1, 301,298,300,-1, 299,298,301,-1, 296,300,292,-1, 302,303,304,-1, 305,304,303,-1, 
+          299,302,304,-1, 306,299,304,-1, 305,306,304,-1, 302,307,303,-1, 296,303,307,-1, 305,303,296,-1, 
+          308,307,302,-1, 309,307,308,-1, 296,307,309,-1, 299,308,302,-1, 284,310,311,-1, 301,311,310,-1, 
+          285,284,311,-1, 301,300,311,-1, 296,311,300,-1, 312,311,296,-1, 312,285,311,-1, 284,313,310,-1, 
+          314,310,313,-1, 299,301,310,-1, 314,299,310,-1, 283,313,284,-1, 291,313,283,-1, 280,313,291,-1, 
+          315,314,313,-1, 316,315,313,-1, 280,316,313,-1, 274,317,318,-1, 309,318,317,-1, 275,274,318,-1, 
+          309,308,318,-1, 299,318,308,-1, 319,275,318,-1, 299,319,318,-1, 274,320,317,-1, 321,317,320,-1, 
+          296,309,317,-1, 321,296,317,-1, 268,320,274,-1, 265,320,268,-1, 270,320,265,-1, 322,321,320,-1, 
+          323,322,320,-1, 270,323,320,-1, 270,273,275,-1, 323,275,319,-1, 270,275,323,-1, 322,319,299,-1, 
+          323,319,322,-1, 321,299,314,-1, 324,295,299,-1, 325,324,299,-1, 326,325,299,-1, 306,326,299,-1, 
+          322,299,321,-1, 296,314,315,-1, 321,314,296,-1, 312,315,316,-1, 312,296,315,-1, 285,316,280,-1, 
+          312,316,285,-1, 285,280,279,-1, 297,295,324,-1, 327,324,325,-1, 297,324,327,-1, 326,328,325,-1, 
+          329,325,328,-1, 327,325,329,-1, 330,328,326,-1, 329,328,330,-1, 331,326,306,-1, 330,326,331,-1, 
+          331,306,305,-1, 331,305,296,-1, 330,331,296,-1, 327,330,296,-1, 297,327,296,-1, 327,329,330,-1, 
+          332,333,334,-1, 335,334,333,-1, 336,332,334,-1, 337,336,334,-1, 338,337,334,-1, 338,334,335,-1, 
+          339,340,333,-1, 341,333,340,-1, 332,339,333,-1, 341,335,333,-1, 339,342,340,-1, 343,340,342,-1, 
+          341,340,343,-1, 339,344,342,-1, 345,342,344,-1, 343,342,345,-1, 339,346,344,-1, 347,344,346,-1, 
+          345,344,347,-1, 339,348,346,-1, 349,346,348,-1, 347,346,349,-1, 350,351,348,-1, 352,348,351,-1, 
+          339,350,348,-1, 349,348,352,-1, 353,351,350,-1, 352,351,353,-1, 339,354,350,-1, 355,350,354,-1, 
+          353,350,355,-1, 356,354,339,-1, 355,354,356,-1, 332,357,339,-1, 358,339,357,-1, 356,339,358,-1, 
+          359,357,332,-1, 358,357,359,-1, 360,332,336,-1, 359,332,360,-1, 337,361,336,-1, 362,336,361,-1, 
+          360,336,362,-1, 363,361,337,-1, 362,361,363,-1, 363,337,338,-1, 341,338,335,-1, 341,363,338,-1, 
+          341,362,363,-1, 341,360,362,-1, 341,359,360,-1, 349,358,359,-1, 347,349,359,-1, 343,347,359,-1, 
+          341,343,359,-1, 353,356,358,-1, 349,353,358,-1, 353,355,356,-1, 349,352,353,-1, 343,345,347,-1, 
+          364,365,366,-1, 367,366,365,-1, 368,364,366,-1, 369,368,366,-1, 370,369,366,-1, 371,370,366,-1, 
+          371,366,367,-1, 372,365,364,-1, 367,365,372,-1, 373,374,364,-1, 375,364,374,-1, 376,373,364,-1, 
+          377,376,364,-1, 378,377,364,-1, 379,378,364,-1, 368,379,364,-1, 372,364,375,-1, 380,374,373,-1, 
+          380,375,374,-1, 381,382,373,-1, 383,373,382,-1, 376,381,373,-1, 380,373,383,-1, 384,385,382,-1, 
+          386,382,385,-1, 381,384,382,-1, 383,382,386,-1, 387,385,384,-1, 386,385,387,-1, 388,384,381,-1, 
+          387,384,388,-1, 389,381,376,-1, 388,381,389,-1, 390,376,377,-1, 389,376,390,-1, 391,377,378,-1, 
+          390,377,391,-1, 392,378,379,-1, 391,378,392,-1, 393,379,368,-1, 392,379,393,-1, 394,368,369,-1, 
+          393,368,394,-1, 395,369,370,-1, 394,369,395,-1, 395,370,371,-1, 394,372,375,-1, 393,394,375,-1, 
+          380,393,375,-1, 371,367,372,-1, 394,371,372,-1, 394,395,371,-1, 391,392,393,-1, 380,391,393,-1, 
+          380,390,391,-1, 388,389,390,-1, 387,388,390,-1, 386,387,390,-1, 383,386,390,-1, 380,383,390,-1, 412,413,414,-1, 415,414,413,-1, 
+          416,412,414,-1, 417,416,414,-1, 418,417,414,-1, 419,418,414,-1, 420,414,415,-1, 420,419,414,-1, 
+          421,422,413,-1, 423,413,422,-1, 412,421,413,-1, 424,413,423,-1, 420,415,413,-1, 424,420,413,-1, 
+          425,422,421,-1, 426,422,425,-1, 427,422,426,-1, 428,423,422,-1, 427,428,422,-1, 429,421,412,-1, 
+          425,421,429,-1, 430,431,412,-1, 432,412,431,-1, 416,430,412,-1, 429,412,432,-1, 433,431,430,-1, 
+          432,431,433,-1, 434,430,416,-1, 433,430,434,-1, 434,416,417,-1, 434,417,435,-1, 436,435,417,-1, 
+          433,434,435,-1, 426,433,435,-1, 437,426,435,-1, 438,435,436,-1, 439,437,435,-1, 438,439,435,-1, 
+          440,436,417,-1, 418,440,417,-1, 429,432,433,-1, 425,429,433,-1, 426,425,433,-1, 441,427,426,-1, 
+          439,426,437,-1, 439,441,426,-1, 424,423,428,-1, 442,428,427,-1, 424,428,442,-1, 441,442,427,-1, 
+          438,436,440,-1, 443,440,418,-1, 443,438,440,-1, 419,443,418,-1, 444,442,441,-1, 445,424,442,-1, 
+          444,445,442,-1, 446,441,439,-1, 446,444,441,-1, 447,439,438,-1, 447,446,439,-1, 448,438,443,-1, 
+          448,447,438,-1, 449,443,419,-1, 449,448,443,-1, 450,419,420,-1, 450,449,419,-1, 451,420,424,-1, 
+          451,450,420,-1, 451,424,445,-1, 452,453,454,-1, 455,454,453,-1, 456,452,454,-1, 457,456,454,-1, 
+          458,457,454,-1, 455,458,454,-1, 452,459,453,-1, 460,453,459,-1, 455,453,460,-1, 461,459,452,-1, 
+          460,459,461,-1, 462,452,456,-1, 461,452,462,-1, 457,463,456,-1, 464,456,463,-1, 462,456,464,-1, 
+          457,465,463,-1, 466,463,465,-1, 464,463,466,-1, 467,465,457,-1, 466,465,467,-1, 467,457,458,-1, 
+          444,468,445,-1, 451,445,468,-1, 469,470,468,-1, 451,468,470,-1, 444,469,468,-1, 471,472,470,-1, 
+          473,470,472,-1, 469,471,470,-1, 451,470,473,-1, 471,474,472,-1, 475,472,474,-1, 473,472,475,-1, 
+          476,477,474,-1, 475,474,477,-1, 471,476,474,-1, 478,479,477,-1, 480,477,479,-1, 476,478,477,-1, 
+          475,477,480,-1, 478,481,479,-1, 482,479,481,-1, 480,479,482,-1, 483,484,481,-1, 482,481,484,-1, 
+          478,483,481,-1, 467,485,484,-1, 486,484,485,-1, 483,467,484,-1, 482,484,486,-1, 467,458,485,-1, 
+          455,485,458,-1, 486,485,455,-1, 466,467,483,-1, 487,483,478,-1, 487,466,483,-1, 488,478,476,-1, 
+          488,487,478,-1, 489,476,471,-1, 489,488,476,-1, 490,471,469,-1, 490,489,471,-1, 491,469,444,-1, 
+          491,490,469,-1, 446,491,444,-1, 464,466,487,-1, 492,487,488,-1, 492,464,487,-1, 493,488,489,-1, 
+          493,492,488,-1, 494,489,490,-1, 494,493,489,-1, 495,490,491,-1, 495,494,490,-1, 496,491,446,-1, 
+          496,495,491,-1, 447,496,446,-1, 462,464,492,-1, 497,492,493,-1, 497,462,492,-1, 498,493,494,-1, 
+          498,497,493,-1, 499,494,495,-1, 499,498,494,-1, 500,495,496,-1, 500,499,495,-1, 501,496,447,-1, 
+          501,500,496,-1, 448,501,447,-1, 461,462,497,-1, 502,497,498,-1, 502,461,497,-1, 503,498,499,-1, 
+          503,502,498,-1, 504,499,500,-1, 504,503,499,-1, 505,500,501,-1, 505,504,500,-1, 506,501,448,-1, 
+          506,505,501,-1, 449,506,448,-1, 460,461,502,-1, 507,502,503,-1, 507,460,502,-1, 508,503,504,-1, 
+          508,507,503,-1, 509,504,505,-1, 509,508,504,-1, 510,505,506,-1, 510,509,505,-1, 511,506,449,-1, 
+          511,510,506,-1, 450,511,449,-1, 455,460,507,-1, 486,507,508,-1, 486,455,507,-1, 482,508,509,-1, 
+          482,486,508,-1, 480,509,510,-1, 480,482,509,-1, 475,510,511,-1, 475,480,510,-1, 473,511,450,-1, 
+          473,475,511,-1, 451,473,450,-1, 512,513,514,-1, 515,514,513,-1, 516,512,514,-1, 517,516,514,-1, 
+          518,517,514,-1, 519,518,514,-1, 520,514,515,-1, 520,519,514,-1, 521,522,513,-1, 523,513,522,-1, 
+          512,521,513,-1, 524,513,523,-1, 520,515,513,-1, 524,520,513,-1, 525,522,521,-1, 526,522,525,-1, 
+          527,522,526,-1, 528,523,522,-1, 527,528,522,-1, 529,521,512,-1, 525,521,529,-1, 530,531,512,-1, 
+          532,512,531,-1, 516,530,512,-1, 529,512,532,-1, 533,531,530,-1, 532,531,533,-1, 534,530,516,-1, 
+          533,530,534,-1, 534,516,517,-1, 534,517,535,-1, 536,535,517,-1, 533,534,535,-1, 526,533,535,-1, 
+          537,526,535,-1, 538,535,536,-1, 539,537,535,-1, 538,539,535,-1, 540,536,517,-1, 518,540,517,-1, 
+          529,532,533,-1, 525,529,533,-1, 526,525,533,-1, 541,527,526,-1, 539,526,537,-1, 539,541,526,-1, 
+          524,523,528,-1, 542,528,527,-1, 524,528,542,-1, 541,542,527,-1, 538,536,540,-1, 543,540,518,-1, 
+          543,538,540,-1, 519,543,518,-1, 544,542,541,-1, 545,524,542,-1, 544,545,542,-1, 546,541,539,-1, 
+          546,544,541,-1, 547,539,538,-1, 547,546,539,-1, 548,538,543,-1, 548,547,538,-1, 549,543,519,-1, 
+          549,548,543,-1, 550,519,520,-1, 550,549,519,-1, 551,520,524,-1, 551,550,520,-1, 551,524,545,-1, 
+          552,553,554,-1, 555,554,553,-1, 556,552,554,-1, 557,556,554,-1, 558,557,554,-1, 555,558,554,-1, 
+          552,559,553,-1, 560,553,559,-1, 555,553,560,-1, 561,559,552,-1, 560,559,561,-1, 562,552,556,-1, 
+          561,552,562,-1, 557,563,556,-1, 564,556,563,-1, 562,556,564,-1, 557,565,563,-1, 566,563,565,-1, 
+          564,563,566,-1, 567,565,557,-1, 566,565,567,-1, 567,557,558,-1, 544,568,545,-1, 551,545,568,-1, 
+          569,570,568,-1, 551,568,570,-1, 544,569,568,-1, 571,572,570,-1, 573,570,572,-1, 569,571,570,-1, 
+          551,570,573,-1, 571,574,572,-1, 575,572,574,-1, 573,572,575,-1, 576,577,574,-1, 575,574,577,-1, 
+          571,576,574,-1, 578,579,577,-1, 580,577,579,-1, 576,578,577,-1, 575,577,580,-1, 578,581,579,-1, 
+          582,579,581,-1, 580,579,582,-1, 583,584,581,-1, 582,581,584,-1, 578,583,581,-1, 567,585,584,-1, 
+          586,584,585,-1, 583,567,584,-1, 582,584,586,-1, 567,558,585,-1, 555,585,558,-1, 586,585,555,-1, 
+          566,567,583,-1, 587,583,578,-1, 587,566,583,-1, 588,578,576,-1, 588,587,578,-1, 589,576,571,-1, 
+          589,588,576,-1, 590,571,569,-1, 590,589,571,-1, 591,569,544,-1, 591,590,569,-1, 546,591,544,-1, 
+          564,566,587,-1, 592,587,588,-1, 592,564,587,-1, 593,588,589,-1, 593,592,588,-1, 594,589,590,-1, 
+          594,593,589,-1, 595,590,591,-1, 595,594,590,-1, 596,591,546,-1, 596,595,591,-1, 547,596,546,-1, 
+          562,564,592,-1, 597,592,593,-1, 597,562,592,-1, 598,593,594,-1, 598,597,593,-1, 599,594,595,-1, 
+          599,598,594,-1, 600,595,596,-1, 600,599,595,-1, 601,596,547,-1, 601,600,596,-1, 548,601,547,-1, 
+          561,562,597,-1, 602,597,598,-1, 602,561,597,-1, 603,598,599,-1, 603,602,598,-1, 604,599,600,-1, 
+          604,603,599,-1, 605,600,601,-1, 605,604,600,-1, 606,601,548,-1, 606,605,601,-1, 549,606,548,-1, 
+          560,561,602,-1, 607,602,603,-1, 607,560,602,-1, 608,603,604,-1, 608,607,603,-1, 609,604,605,-1, 
+          609,608,604,-1, 610,605,606,-1, 610,609,605,-1, 611,606,549,-1, 611,610,606,-1, 550,611,549,-1, 
+          555,560,607,-1, 586,607,608,-1, 586,555,607,-1, 582,608,609,-1, 582,586,608,-1, 580,609,610,-1, 
+          580,582,609,-1, 575,610,611,-1, 575,580,610,-1, 573,611,550,-1, 573,575,611,-1, 551,573,550,-1, 
+          612,613,614,-1, 615,614,613,-1, 616,614,617,-1, 618,617,614,-1, 612,614,616,-1, 615,618,614,-1, 
+          619,620,613,-1, 621,613,620,-1, 612,619,613,-1, 621,615,613,-1, 622,623,620,-1, 624,620,623,-1, 
+          625,622,620,-1, 619,625,620,-1, 621,620,624,-1, 626,627,623,-1, 628,623,627,-1, 629,626,623,-1, 
+          622,629,623,-1, 624,623,628,-1, 630,631,627,-1, 632,627,631,-1, 626,630,627,-1, 628,627,632,-1, 
+          633,634,631,-1, 635,631,634,-1, 630,633,631,-1, 635,632,631,-1, 636,617,634,-1, 637,634,617,-1, 
+          638,636,634,-1, 633,638,634,-1, 637,635,634,-1, 639,616,617,-1, 636,639,617,-1, 618,637,617,-1, 
+          640,616,639,-1, 641,612,616,-1, 641,616,640,-1, 642,639,636,-1, 642,640,639,-1, 638,643,636,-1, 
+          644,636,643,-1, 642,636,644,-1, 638,645,643,-1, 646,643,645,-1, 644,643,646,-1, 647,645,638,-1, 
+          646,645,647,-1, 648,638,633,-1, 647,638,648,-1, 649,633,630,-1, 648,633,649,-1, 650,630,626,-1, 
+          649,630,650,-1, 651,626,629,-1, 650,626,651,-1, 652,629,622,-1, 651,629,652,-1, 625,653,622,-1, 
+          654,622,653,-1, 652,622,654,-1, 625,655,653,-1, 656,653,655,-1, 654,653,656,-1, 657,655,625,-1, 
+          656,655,657,-1, 658,625,619,-1, 657,625,658,-1, 659,619,612,-1, 658,619,659,-1, 659,612,641,-1, 
+          660,632,635,-1, 660,661,632,-1, 628,632,661,-1, 662,635,637,-1, 662,660,635,-1, 663,637,618,-1, 
+          664,662,637,-1, 663,664,637,-1, 663,618,615,-1, 663,615,665,-1, 621,665,615,-1, 621,666,665,-1, 
+          667,665,666,-1, 668,663,665,-1, 668,665,667,-1, 624,669,666,-1, 670,666,669,-1, 621,624,666,-1, 
+          670,667,666,-1, 624,661,669,-1, 671,669,661,-1, 672,670,669,-1, 671,672,669,-1, 673,661,660,-1, 
+          624,628,661,-1, 673,671,661,-1, 674,660,662,-1, 673,660,674,-1, 675,662,664,-1, 674,662,675,-1, 
+          676,664,663,-1, 677,664,676,-1, 675,664,677,-1, 676,663,668,-1, 678,668,667,-1, 679,678,667,-1, 
+          670,679,667,-1, 680,676,668,-1, 678,680,668,-1, 681,677,676,-1, 680,681,676,-1, 682,675,677,-1, 
+          681,682,677,-1, 683,674,675,-1, 682,683,675,-1, 684,674,683,-1, 673,674,684,-1, 685,683,682,-1, 
+          685,686,683,-1, 684,683,686,-1, 687,682,681,-1, 688,685,682,-1, 687,688,682,-1, 678,681,680,-1, 
+          687,681,678,-1, 689,678,679,-1, 689,687,678,-1, 689,679,690,-1, 691,690,679,-1, 670,691,679,-1, 
+          691,692,690,-1, 693,690,692,-1, 694,689,690,-1, 693,694,690,-1, 691,695,692,-1, 696,692,695,-1, 
+          696,693,692,-1, 684,686,695,-1, 697,695,686,-1, 698,684,695,-1, 691,698,695,-1, 696,695,697,-1, 
+          699,686,685,-1, 697,686,699,-1, 700,685,688,-1, 699,685,700,-1, 701,688,687,-1, 701,700,688,-1, 
+          702,687,689,-1, 702,701,687,-1, 694,702,689,-1, 698,703,684,-1, 673,684,703,-1, 671,703,698,-1, 
+          673,703,671,-1, 672,698,691,-1, 671,698,672,-1, 672,691,670,-1, 704,700,701,-1, 704,705,700,-1, 
+          699,700,705,-1, 706,701,702,-1, 706,704,701,-1, 707,702,694,-1, 708,706,702,-1, 707,708,702,-1, 
+          707,694,693,-1, 707,693,709,-1, 696,709,693,-1, 696,710,709,-1, 711,709,710,-1, 712,707,709,-1, 
+          711,712,709,-1, 713,714,710,-1, 715,710,714,-1, 697,713,710,-1, 696,697,710,-1, 715,711,710,-1, 
+          716,714,713,-1, 715,714,716,-1, 697,705,713,-1, 717,713,705,-1, 716,713,717,-1, 718,705,704,-1, 
+          697,699,705,-1, 717,705,718,-1, 719,704,706,-1, 718,704,719,-1, 708,720,706,-1, 721,706,720,-1, 
+          721,719,706,-1, 722,720,708,-1, 722,721,720,-1, 723,708,707,-1, 723,722,708,-1, 712,723,707,-1, 
+          651,719,721,-1, 652,654,719,-1, 718,719,654,-1, 651,652,719,-1, 648,721,722,-1, 650,651,721,-1, 
+          649,650,721,-1, 648,649,721,-1, 712,722,723,-1, 647,722,712,-1, 647,648,722,-1, 644,712,711,-1, 
+          646,647,712,-1, 644,646,712,-1, 642,711,640,-1, 715,640,711,-1, 642,644,711,-1, 715,641,640,-1, 
+          715,659,641,-1, 715,658,659,-1, 716,657,658,-1, 715,716,658,-1, 718,656,657,-1, 716,718,657,-1, 
+          718,654,656,-1, 716,717,718,-1, 724,725,726,-1, 727,726,725,-1, 728,726,729,-1, 730,729,726,-1, 
+          724,726,728,-1, 727,730,726,-1, 731,732,725,-1, 733,725,732,-1, 724,731,725,-1, 733,727,725,-1, 
+          734,735,732,-1, 736,732,735,-1, 737,734,732,-1, 731,737,732,-1, 733,732,736,-1, 738,739,735,-1, 
+          740,735,739,-1, 741,738,735,-1, 734,741,735,-1, 736,735,740,-1, 742,743,739,-1, 744,739,743,-1, 
+          738,742,739,-1, 740,739,744,-1, 745,746,743,-1, 747,743,746,-1, 742,745,743,-1, 747,744,743,-1, 
+          748,729,746,-1, 749,746,729,-1, 750,748,746,-1, 745,750,746,-1, 749,747,746,-1, 751,728,729,-1, 
+          748,751,729,-1, 730,749,729,-1, 752,728,751,-1, 753,724,728,-1, 753,728,752,-1, 754,751,748,-1, 
+          754,752,751,-1, 750,755,748,-1, 756,748,755,-1, 754,748,756,-1, 750,757,755,-1, 758,755,757,-1, 
+          756,755,758,-1, 759,757,750,-1, 758,757,759,-1, 760,750,745,-1, 759,750,760,-1, 761,745,742,-1, 
+          760,745,761,-1, 762,742,738,-1, 761,742,762,-1, 763,738,741,-1, 762,738,763,-1, 764,741,734,-1, 
+          763,741,764,-1, 737,765,734,-1, 766,734,765,-1, 764,734,766,-1, 737,767,765,-1, 768,765,767,-1, 
+          766,765,768,-1, 769,767,737,-1, 768,767,769,-1, 770,737,731,-1, 769,737,770,-1, 771,731,724,-1, 
+          770,731,771,-1, 771,724,753,-1, 772,744,747,-1, 772,773,744,-1, 740,744,773,-1, 774,747,749,-1, 
+          774,772,747,-1, 775,749,730,-1, 776,774,749,-1, 775,776,749,-1, 775,730,727,-1, 775,727,777,-1, 
+          733,777,727,-1, 733,778,777,-1, 779,777,778,-1, 780,775,777,-1, 780,777,779,-1, 736,781,778,-1, 
+          782,778,781,-1, 733,736,778,-1, 782,779,778,-1, 736,773,781,-1, 783,781,773,-1, 784,782,781,-1, 
+          783,784,781,-1, 785,773,772,-1, 736,740,773,-1, 785,783,773,-1, 786,772,774,-1, 785,772,786,-1, 
+          787,774,776,-1, 786,774,787,-1, 788,776,775,-1, 789,776,788,-1, 787,776,789,-1, 788,775,780,-1, 
+          790,780,779,-1, 791,790,779,-1, 782,791,779,-1, 792,788,780,-1, 790,792,780,-1, 793,789,788,-1, 
+          792,793,788,-1, 794,787,789,-1, 793,794,789,-1, 795,786,787,-1, 794,795,787,-1, 796,786,795,-1, 
+          785,786,796,-1, 797,795,794,-1, 797,798,795,-1, 796,795,798,-1, 799,794,793,-1, 800,797,794,-1, 
+          799,800,794,-1, 790,793,792,-1, 799,793,790,-1, 801,790,791,-1, 801,799,790,-1, 801,791,802,-1, 
+          803,802,791,-1, 782,803,791,-1, 803,804,802,-1, 805,802,804,-1, 806,801,802,-1, 805,806,802,-1, 
+          803,807,804,-1, 808,804,807,-1, 808,805,804,-1, 796,798,807,-1, 809,807,798,-1, 810,796,807,-1, 
+          803,810,807,-1, 808,807,809,-1, 811,798,797,-1, 809,798,811,-1, 812,797,800,-1, 811,797,812,-1, 
+          813,800,799,-1, 813,812,800,-1, 814,799,801,-1, 814,813,799,-1, 806,814,801,-1, 810,815,796,-1, 
+          785,796,815,-1, 783,815,810,-1, 785,815,783,-1, 784,810,803,-1, 783,810,784,-1, 784,803,782,-1, 
+          816,812,813,-1, 816,817,812,-1, 811,812,817,-1, 818,813,814,-1, 818,816,813,-1, 819,814,806,-1, 
+          820,818,814,-1, 819,820,814,-1, 819,806,805,-1, 819,805,821,-1, 808,821,805,-1, 808,822,821,-1, 
+          823,821,822,-1, 824,819,821,-1, 823,824,821,-1, 825,826,822,-1, 827,822,826,-1, 809,825,822,-1, 
+          808,809,822,-1, 827,823,822,-1, 828,826,825,-1, 827,826,828,-1, 809,817,825,-1, 829,825,817,-1, 
+          828,825,829,-1, 830,817,816,-1, 809,811,817,-1, 829,817,830,-1, 831,816,818,-1, 830,816,831,-1, 
+          820,832,818,-1, 833,818,832,-1, 833,831,818,-1, 834,832,820,-1, 834,833,832,-1, 835,820,819,-1, 
+          835,834,820,-1, 824,835,819,-1, 763,831,833,-1, 764,766,831,-1, 830,831,766,-1, 763,764,831,-1, 
+          760,833,834,-1, 762,763,833,-1, 761,762,833,-1, 760,761,833,-1, 824,834,835,-1, 759,834,824,-1, 
+          759,760,834,-1, 756,824,823,-1, 758,759,824,-1, 756,758,824,-1, 754,823,752,-1, 827,752,823,-1, 
+          754,756,823,-1, 827,753,752,-1, 827,771,753,-1, 827,770,771,-1, 828,769,770,-1, 827,828,770,-1, 
+          830,768,769,-1, 828,830,769,-1, 830,766,768,-1, 828,829,830,-1, 836,837,838,-1, 839,838,837,-1, 
+          840,836,838,-1, 841,840,838,-1, 842,841,838,-1, 843,842,838,-1, 839,843,838,-1, 836,844,837,-1, 
+          845,837,844,-1, 845,839,837,-1, 836,846,844,-1, 847,844,846,-1, 845,844,847,-1, 836,848,846,-1, 
+          849,846,848,-1, 847,846,849,-1, 850,848,836,-1, 849,848,850,-1, 851,836,840,-1, 852,853,836,-1, 
+          854,836,853,-1, 855,852,836,-1, 851,855,836,-1, 854,850,836,-1, 856,851,840,-1, 841,856,840,-1, 
+          857,858,859,-1, 860,859,858,-1, 861,857,859,-1, 860,861,859,-1, 857,862,858,-1, 863,858,862,-1, 
+          863,860,858,-1, 857,864,862,-1, 865,862,864,-1, 863,862,865,-1, 866,867,864,-1, 868,864,867,-1, 
+          869,866,864,-1, 857,869,864,-1, 865,864,868,-1, 870,867,866,-1, 871,867,870,-1, 872,867,871,-1, 
+          873,867,872,-1, 868,867,873,-1, 874,866,869,-1, 874,875,866,-1, 870,866,875,-1, 876,869,857,-1, 
+          876,874,869,-1, 861,876,857,-1, 877,878,879,-1, 880,879,878,-1, 881,877,879,-1, 882,881,879,-1, 
+          883,882,879,-1, 874,879,880,-1, 876,879,874,-1, 883,879,884,-1, 843,885,886,-1, 884,879,876,-1, 
+          887,878,877,-1, 888,880,878,-1, 888,878,887,-1, 881,889,877,-1, 890,877,889,-1, 891,887,877,-1, 
+          892,891,877,-1, 890,892,877,-1, 881,893,889,-1, 894,889,893,-1, 894,890,889,-1, 881,895,893,-1, 
+          896,893,895,-1, 896,894,893,-1, 881,853,895,-1, 852,895,853,-1, 897,895,852,-1, 898,895,897,-1, 
+          898,896,895,-1, 899,853,881,-1, 885,900,901,-1, 899,854,853,-1, 902,881,882,-1, 903,904,881,-1, 
+          905,881,904,-1, 902,903,881,-1, 899,881,905,-1, 883,902,882,-1, 906,904,907,-1, 903,907,904,-1, 
+          908,906,907,-1, 902,907,903,-1, 883,907,902,-1, 909,907,883,-1, 908,907,910,-1, 909,910,907,-1, 
+          906,911,904,-1, 912,904,911,-1, 913,905,904,-1, 913,904,912,-1, 914,915,911,-1, 916,911,915,-1, 
+          906,914,911,-1, 912,911,916,-1, 917,918,915,-1, 919,915,918,-1, 914,917,915,-1, 916,915,919,-1, 
+          920,921,918,-1, 922,918,921,-1, 917,920,918,-1, 923,918,922,-1, 924,918,923,-1, 919,918,925,-1, 
+          926,925,918,-1, 926,918,924,-1, 927,928,921,-1, 929,921,928,-1, 920,927,921,-1, 930,922,921,-1, 
+          929,930,921,-1, 927,931,928,-1, 929,928,931,-1, 932,933,931,-1, 934,931,933,-1, 935,932,931,-1, 
+          927,935,931,-1, 934,929,931,-1, 936,937,933,-1, 938,933,937,-1, 939,936,933,-1, 932,939,933,-1, 
+          938,934,933,-1, 940,941,937,-1, 942,937,941,-1, 936,940,937,-1, 942,938,937,-1, 943,944,941,-1, 
+          945,941,944,-1, 940,943,941,-1, 945,942,941,-1, 946,947,944,-1, 948,944,947,-1, 943,946,944,-1, 
+          948,945,944,-1, 949,950,947,-1, 951,947,950,-1, 946,949,947,-1, 951,948,947,-1, 952,950,949,-1, 
+          952,951,950,-1, 953,949,946,-1, 953,952,949,-1, 954,946,943,-1, 954,953,946,-1, 955,943,940,-1, 
+          955,954,943,-1, 956,940,936,-1, 956,955,940,-1, 957,936,939,-1, 957,956,936,-1, 958,939,932,-1, 
+          958,957,939,-1, 959,932,935,-1, 959,958,932,-1, 960,935,927,-1, 960,959,935,-1, 920,961,927,-1, 
+          962,927,961,-1, 962,960,927,-1, 963,961,920,-1, 964,962,961,-1, 963,964,961,-1, 965,920,917,-1, 
+          966,920,967,-1, 965,967,920,-1, 963,920,966,-1, 968,917,914,-1, 968,965,917,-1, 969,914,906,-1, 
+          968,914,969,-1, 969,906,908,-1, 970,971,972,-1, 973,972,971,-1, 974,970,972,-1, 975,974,972,-1, 
+          976,975,972,-1, 973,977,972,-1, 976,972,977,-1, 978,971,970,-1, 973,971,978,-1, 974,979,970,-1, 
+          980,970,979,-1, 981,970,980,-1, 978,970,981,-1, 974,982,979,-1, 983,979,982,-1, 984,980,979,-1, 
+          985,984,979,-1, 983,985,979,-1, 986,982,974,-1, 986,983,982,-1, 987,974,975,-1, 988,974,987,-1, 
+          989,974,988,-1, 990,986,974,-1, 991,990,974,-1, 989,991,974,-1, 976,987,975,-1, 992,993,994,-1, 
+          995,994,993,-1, 995,992,994,-1, 996,997,993,-1, 998,993,997,-1, 999,996,993,-1, 992,999,993,-1, 
+          1000,993,998,-1, 1001,993,1000,-1, 1002,995,993,-1, 1003,1002,993,-1, 1003,993,1001,-1, 996,1004,997,-1, 
+          1005,997,1004,-1, 1005,998,997,-1, 1006,1004,996,-1, 1006,1005,1004,-1, 1007,996,999,-1, 1008,996,1007,-1, 
+          1009,996,1008,-1, 1006,996,1009,-1, 1010,999,992,-1, 1011,1007,999,-1, 1012,1011,999,-1, 1013,1012,999,-1, 
+          1010,1013,999,-1, 995,1010,992,-1, 1014,1015,1016,-1, 1017,1016,1015,-1, 1018,1014,1016,-1, 1017,1019,1016,-1, 
+          1020,1016,1019,-1, 1020,1018,1016,-1, 1021,1022,1015,-1, 1023,1015,1022,-1, 1014,1021,1015,-1, 1017,1015,1024,-1, 
+          1025,1024,1015,-1, 1026,1025,1015,-1, 1023,1026,1015,-1, 1027,1022,1021,-1, 1027,1023,1022,-1, 1028,1021,1014,-1, 
+          1027,1021,1028,-1, 1018,1028,1014,-1, 1029,1030,1031,-1, 1032,1031,1030,-1, 1033,1029,1031,-1, 1032,1034,1031,-1, 
+          984,1031,1034,-1, 1035,1036,1031,-1, 1033,1031,1036,-1, 984,1035,1031,-1, 1037,1038,1030,-1, 1039,1030,1038,-1, 
+          1029,1037,1030,-1, 1039,1032,1030,-1, 900,1040,901,-1, 1041,1038,1037,-1, 1041,1039,1038,-1, 1042,1037,1029,-1, 
+          1042,1041,1037,-1, 1033,1042,1029,-1, 874,1043,875,-1, 1044,875,1043,-1, 1045,870,875,-1, 1044,1045,875,-1, 
+          874,880,1043,-1, 1046,1043,880,-1, 1046,1044,1043,-1, 888,1046,880,-1, 855,897,852,-1, 1047,897,855,-1, 
+          1048,898,897,-1, 1047,1048,897,-1, 1049,855,851,-1, 1049,1047,855,-1, 856,1049,851,-1, 1050,987,1051,-1, 
+          976,1051,987,-1, 922,1050,1051,-1, 923,922,1051,-1, 924,923,1051,-1, 1052,1051,976,-1, 1052,924,1051,-1, 
+          1050,988,987,-1, 989,988,1050,-1, 930,1050,922,-1, 842,1053,841,-1, 930,989,1050,-1, 1054,966,967,-1, 
+          965,1054,967,-1, 1000,998,966,-1, 1005,966,998,-1, 1054,1000,966,-1, 1053,856,841,-1, 1055,966,1005,-1, 
+          1056,963,966,-1, 1055,1056,966,-1, 1001,1000,1054,-1, 968,1054,965,-1, 1057,1054,968,-1, 1001,1054,1057,-1, 
+          1017,1058,1019,-1, 1020,1019,1058,-1, 901,1040,1047,-1, 1024,1059,1058,-1, 1011,1058,1059,-1, 1017,1024,1058,-1, 
+          1060,1020,1058,-1, 1040,1048,1047,-1, 1011,1060,1058,-1, 1024,1061,1059,-1, 1011,1059,1061,-1, 1008,1007,1061,-1, 
+          1011,1061,1007,-1, 1024,1008,1061,-1, 1025,1008,1024,-1, 1062,1009,1008,-1, 1025,1062,1008,-1, 1063,1064,1034,-1, 
+          984,1034,1064,-1, 1065,1063,1034,-1, 1066,1065,1034,-1, 1032,1066,1034,-1, 981,980,1064,-1, 984,1064,980,-1, 
+          1063,981,1064,-1, 1067,981,1063,-1, 1068,978,981,-1, 1067,1068,981,-1, 1066,1063,1065,-1, 1067,1063,1066,-1, 
+          1069,1066,1032,-1, 843,899,885,-1, 1069,1067,1066,-1, 1039,1069,1032,-1, 1020,1028,1018,-1, 1027,1028,1020,-1, 
+          886,1049,856,-1, 1027,1020,1023,-1, 1036,1039,1041,-1, 1035,1039,1036,-1, 885,901,886,-1, 1036,1041,1042,-1, 
+          1033,1036,1042,-1, 1026,1020,1060,-1, 1023,1020,1026,-1, 901,1047,1049,-1, 1026,1060,1011,-1, 1025,1011,1012,-1, 
+          1026,1011,1025,-1, 1062,1012,1013,-1, 1025,1012,1062,-1, 1062,1013,1009,-1, 1005,1009,1013,-1, 995,1013,1010,-1, 
+          1005,1013,995,-1, 1006,1009,1005,-1, 1069,1035,984,-1, 1039,1035,1069,-1, 1067,984,985,-1, 843,1053,842,-1, 
+          1069,984,1067,-1, 1068,985,983,-1, 1067,985,1068,-1, 1068,983,978,-1, 976,978,983,-1, 990,983,986,-1, 
+          976,983,990,-1, 976,973,978,-1, 1070,887,891,-1, 1070,888,887,-1, 1071,891,892,-1, 1071,1070,891,-1, 
+          883,892,890,-1, 883,884,892,-1, 845,843,839,-1, 1071,892,884,-1, 883,890,894,-1, 883,894,896,-1, 
+          1072,1073,896,-1, 899,896,1073,-1, 898,1072,896,-1, 899,883,896,-1, 1040,1073,1072,-1, 900,899,1073,-1, 
+          900,1073,1040,-1, 1048,1072,898,-1, 1040,1072,1048,-1, 934,930,929,-1, 963,930,934,-1, 968,930,963,-1, 
+          1053,886,856,-1, 925,930,968,-1, 926,930,925,-1, 962,934,938,-1, 964,934,962,-1, 963,934,964,-1, 
+          958,938,942,-1, 959,938,958,-1, 960,938,959,-1, 962,938,960,-1, 957,942,945,-1, 958,942,957,-1, 
+          956,945,948,-1, 957,945,956,-1, 955,948,951,-1, 956,948,955,-1, 954,951,952,-1, 955,951,954,-1, 
+          954,952,953,-1, 886,901,1049,-1, 976,977,973,-1, 991,976,990,-1, 1052,976,991,-1, 1005,995,1002,-1, 
+          1003,1005,1002,-1, 1003,1055,1005,-1, 1052,991,989,-1, 924,989,930,-1, 1052,989,924,-1, 926,924,930,-1, 
+          1001,963,1056,-1, 1057,968,963,-1, 1001,1057,963,-1, 1003,1056,1055,-1, 1003,1001,1056,-1, 899,905,883,-1, 
+          913,883,905,-1, 913,909,883,-1, 843,886,1053,-1, 916,908,910,-1, 912,916,910,-1, 909,912,910,-1, 
+          919,969,908,-1, 916,919,908,-1, 925,968,969,-1, 919,925,969,-1, 913,912,909,-1, 845,850,854,-1, 
+          847,849,850,-1, 845,847,850,-1, 843,854,899,-1, 845,854,843,-1, 860,876,861,-1, 1074,884,876,-1, 
+          885,899,900,-1, 873,872,876,-1, 1074,876,872,-1, 863,876,860,-1, 868,873,876,-1, 865,868,876,-1, 
+          863,865,876,-1, 1071,884,1074,-1, 871,870,1045,-1, 1075,1045,1044,-1, 1075,871,1045,-1, 1076,1044,1046,-1, 
+          1076,1075,1044,-1, 1077,1046,888,-1, 1077,1076,1046,-1, 1070,1077,888,-1, 872,871,1075,-1, 872,1075,1076,-1, 
+          1071,1074,1077,-1, 1074,1076,1077,-1, 1074,872,1076,-1, 1071,1077,1070,-1, 1078,1079,1080,-1, 1081,1080,1079,-1, 
+          1082,1078,1080,-1, 1083,1082,1080,-1, 1084,1083,1080,-1, 1085,1080,1081,-1, 1086,1080,1085,-1, 1084,1080,1086,-1, 
+          1087,1088,1079,-1, 1089,1079,1088,-1, 1078,1087,1079,-1, 1090,1081,1079,-1, 1090,1079,1089,-1, 1091,1092,1088,-1, 
+          1093,1088,1092,-1, 1087,1091,1088,-1, 1093,1089,1088,-1, 1094,1092,1091,-1, 1093,1092,1094,-1, 1095,1091,1087,-1, 
+          1094,1091,1095,-1, 1096,1087,1078,-1, 1095,1087,1096,-1, 1097,1078,1082,-1, 1098,1078,1097,-1, 1099,1078,1098,-1, 
+          1096,1078,1099,-1, 1083,1100,1082,-1, 1101,1082,1100,-1, 1102,1097,1082,-1, 1102,1082,1103,-1, 1101,1103,1082,-1, 
+          1083,1104,1100,-1, 1101,1100,1104,-1, 1105,1106,1104,-1, 1107,1104,1106,-1, 1083,1105,1104,-1, 1101,1104,1107,-1, 
+          1108,1109,1106,-1, 1110,1106,1109,-1, 1111,1108,1106,-1, 1105,1111,1106,-1, 1107,1106,1110,-1, 1112,1109,1108,-1, 
+          1113,1109,1112,-1, 1110,1109,1113,-1, 1114,1108,1111,-1, 1115,1112,1108,-1, 1116,1115,1108,-1, 1117,1116,1108,-1, 
+          1117,1108,1114,-1, 1118,1111,1105,-1, 1118,1114,1111,-1, 1119,1105,1083,-1, 1118,1105,1119,-1, 1119,1083,1084,-1, 
+          1120,1112,1115,-1, 1113,1112,1120,-1, 1116,1121,1115,-1, 1122,1115,1121,-1, 1123,1115,1122,-1, 1124,1115,1123,-1, 
+          1120,1115,1124,-1, 1125,1121,1116,-1, 1126,1122,1121,-1, 1126,1121,1125,-1, 1125,1116,1117,-1, 1127,1128,1129,-1, 
+          1130,1129,1128,-1, 1131,1127,1129,-1, 1132,1131,1129,-1, 1133,1129,1130,-1, 1132,1129,1133,-1, 1127,1134,1128,-1, 
+          1135,1128,1134,-1, 1136,1137,1128,-1, 1138,1128,1137,-1, 1139,1136,1128,-1, 1140,1139,1128,-1, 1141,1140,1128,-1, 
+          1138,1130,1128,-1, 1141,1128,1135,-1, 1142,1143,1134,-1, 1144,1134,1143,-1, 1127,1142,1134,-1, 1145,1134,1144,-1, 
+          1145,1135,1134,-1, 1146,1143,1142,-1, 1144,1143,1146,-1, 1147,1142,1127,-1, 1148,1149,1142,-1, 1150,1142,1149,-1, 
+          1151,1148,1142,-1, 1152,1146,1142,-1, 1153,1152,1142,-1, 1154,1153,1142,-1, 1155,1154,1142,-1, 1150,1155,1142,-1, 
+          1151,1142,1147,-1, 1131,1156,1127,-1, 1157,1127,1156,-1, 1157,1147,1127,-1, 1158,1156,1131,-1, 1159,1160,1156,-1, 
+          1161,1156,1160,-1, 1158,1159,1156,-1, 1162,1156,1161,-1, 1162,1157,1156,-1, 1163,1158,1131,-1, 1163,1131,1132,-1, 
+          1164,1137,1136,-1, 1165,1138,1137,-1, 1164,1165,1137,-1, 1166,1136,1139,-1, 1166,1164,1136,-1, 1167,1139,1140,-1, 
+          1166,1139,1167,-1, 1167,1140,1141,-1, 1168,1130,1138,-1, 1168,1133,1130,-1, 1165,1168,1138,-1, 1161,1169,1170,-1, 
+          1171,1170,1169,-1, 1172,1161,1170,-1, 1172,1170,1171,-1, 1161,1160,1169,-1, 1173,1169,1160,-1, 1173,1171,1169,-1, 
+          1174,1160,1159,-1, 1173,1160,1174,-1, 1175,1159,1158,-1, 1175,1174,1159,-1, 1163,1175,1158,-1, 1172,1162,1161,-1, 
+          1176,1177,1178,-1, 1179,1178,1177,-1, 1122,1176,1178,-1, 1123,1122,1178,-1, 1180,1123,1178,-1, 1180,1178,1179,-1, 
+          1181,1182,1177,-1, 1183,1177,1182,-1, 1184,1181,1177,-1, 1176,1184,1177,-1, 1185,1179,1177,-1, 1185,1177,1183,-1, 
+          1186,1182,1181,-1, 1183,1182,1186,-1, 1187,1181,1184,-1, 1188,1186,1181,-1, 1189,1188,1181,-1, 1189,1181,1187,-1, 
+          1190,1184,1176,-1, 1187,1184,1190,-1, 1191,1176,1122,-1, 1190,1176,1191,-1, 1191,1122,1126,-1, 1180,1124,1123,-1, 
+          1188,1192,1186,-1, 1193,1186,1192,-1, 1194,1186,1193,-1, 1195,1186,1194,-1, 1196,1183,1186,-1, 1195,1196,1186,-1, 
+          1197,1192,1188,-1, 1198,1193,1192,-1, 1198,1192,1197,-1, 1197,1188,1189,-1, 1194,1199,1200,-1, 1201,1200,1199,-1, 
+          1195,1194,1200,-1, 1202,1200,1201,-1, 1195,1200,1202,-1, 1194,1193,1199,-1, 1203,1199,1193,-1, 1201,1199,1204,-1, 
+          1205,1204,1199,-1, 1205,1199,1203,-1, 1203,1193,1198,-1, 1206,1149,1148,-1, 1207,1150,1149,-1, 1207,1149,1206,-1, 
+          1151,1206,1148,-1, 1208,1146,1152,-1, 1144,1146,1208,-1, 1209,1152,1153,-1, 1208,1152,1209,-1, 1210,1153,1154,-1, 
+          1209,1153,1210,-1, 1211,1154,1155,-1, 1210,1154,1211,-1, 1201,1204,1155,-1, 1212,1155,1204,-1, 1150,1201,1155,-1, 
+          1211,1155,1212,-1, 1212,1204,1205,-1, 1213,1201,1150,-1, 1213,1202,1201,-1, 1213,1150,1207,-1, 1214,1215,1216,-1, 
+          1217,1216,1215,-1, 1085,1214,1216,-1, 1218,1085,1216,-1, 1218,1216,1217,-1, 1214,1219,1215,-1, 1220,1215,1219,-1, 
+          1221,1217,1215,-1, 1222,1221,1215,-1, 1222,1215,1220,-1, 1223,1219,1214,-1, 1224,1219,1223,-1, 1224,1220,1219,-1, 
+          1085,1081,1214,-1, 1225,1214,1081,-1, 1223,1214,1225,-1, 1090,1225,1081,-1, 1086,1085,1218,-1, 1226,1227,1228,-1, 
+          1098,1228,1227,-1, 1229,1226,1228,-1, 1230,1229,1228,-1, 1098,1097,1228,-1, 1231,1228,1097,-1, 1230,1228,1231,-1, 
+          1232,1227,1226,-1, 1233,1098,1227,-1, 1233,1227,1232,-1, 1234,1226,1229,-1, 1232,1226,1235,-1, 1236,1235,1226,-1, 
+          1236,1226,1234,-1, 1237,1229,1230,-1, 1237,1234,1229,-1, 1102,1231,1097,-1, 1099,1098,1233,-1, 1113,1117,1114,-1, 
+          1118,1113,1114,-1, 1113,1125,1117,-1, 1120,1124,1125,-1, 1180,1125,1124,-1, 1113,1120,1125,-1, 1126,1125,1180,-1, 
+          1110,1113,1118,-1, 1223,1225,1217,-1, 1090,1217,1225,-1, 1221,1223,1217,-1, 1090,1218,1217,-1, 1238,1223,1221,-1, 
+          1238,1224,1223,-1, 1238,1221,1222,-1, 1089,1086,1218,-1, 1090,1089,1218,-1, 1103,1086,1089,-1, 1101,1086,1103,-1, 
+          1101,1084,1086,-1, 1103,1089,1099,-1, 1093,1099,1089,-1, 1126,1180,1179,-1, 1191,1126,1179,-1, 1185,1191,1179,-1, 
+          1185,1190,1191,-1, 1183,1187,1190,-1, 1185,1183,1190,-1, 1189,1187,1183,-1, 1197,1189,1183,-1, 1196,1197,1183,-1, 
+          1195,1197,1196,-1, 1198,1197,1195,-1, 1198,1195,1202,-1, 1203,1198,1202,-1, 1205,1203,1202,-1, 1144,1202,1213,-1, 
+          1212,1205,1202,-1, 1211,1212,1202,-1, 1210,1211,1202,-1, 1144,1210,1202,-1, 1144,1207,1206,-1, 1151,1144,1206,-1, 
+          1144,1213,1207,-1, 1144,1209,1210,-1, 1144,1208,1209,-1, 1151,1147,1144,-1, 1157,1144,1147,-1, 1157,1145,1144,-1, 
+          1232,1230,1231,-1, 1102,1232,1231,-1, 1232,1235,1230,-1, 1239,1230,1235,-1, 1239,1237,1230,-1, 1239,1235,1236,-1, 
+          1102,1233,1232,-1, 1103,1099,1233,-1, 1102,1103,1233,-1, 1093,1096,1099,-1, 1107,1119,1084,-1, 1101,1107,1084,-1, 
+          1110,1118,1119,-1, 1107,1110,1119,-1, 1094,1095,1096,-1, 1093,1094,1096,-1, 1240,1241,1242,-1, 1243,1242,1241,-1, 
+          1244,1240,1242,-1, 1244,1242,1243,-1, 1245,1246,1241,-1, 1247,1241,1246,-1, 1240,1245,1241,-1, 1243,1241,1247,-1, 
+          1248,1249,1246,-1, 1250,1246,1249,-1, 1245,1248,1246,-1, 1250,1247,1246,-1, 1248,1251,1249,-1, 1252,1249,1251,-1, 
+          1253,1250,1249,-1, 1252,1253,1249,-1, 1166,1167,1141,-1, 1254,1220,1251,-1, 1252,1251,1220,-1, 1248,1254,1251,-1, 
+          1255,1248,1245,-1, 1166,1141,1164,-1, 1256,1245,1240,-1, 1256,1255,1245,-1, 1244,1256,1240,-1, 1254,1222,1220,-1, 
+          1224,1252,1220,-1, 1238,1222,1254,-1, 1255,1254,1248,-1, 1172,1171,1162,-1, 1173,1174,1162,-1, 1238,1254,1257,-1, 
+          1255,1257,1254,-1, 1258,1259,1260,-1, 1261,1260,1259,-1, 1262,1258,1260,-1, 1261,1262,1260,-1, 1263,1264,1259,-1, 
+          1265,1259,1264,-1, 1258,1263,1259,-1, 1265,1261,1259,-1, 1263,1266,1264,-1, 1267,1264,1266,-1, 1265,1264,1267,-1, 
+          1268,1269,1266,-1, 1236,1266,1269,-1, 1263,1268,1266,-1, 1236,1234,1266,-1, 1270,1266,1234,-1, 1270,1267,1266,-1, 
+          1271,1269,1268,-1, 1239,1236,1269,-1, 1271,1272,1269,-1, 1239,1269,1272,-1, 1271,1268,1263,-1, 1273,1263,1258,-1, 
+          1273,1271,1263,-1, 1262,1273,1258,-1, 1237,1270,1234,-1, 1244,1247,1250,-1, 1244,1243,1247,-1, 1252,1250,1253,-1, 
+          1255,1250,1252,-1, 1256,1250,1255,-1, 1244,1250,1256,-1, 1224,1255,1252,-1, 1173,1162,1171,-1, 1163,1162,1175,-1, 
+          1238,1257,1224,-1, 1224,1257,1255,-1, 1273,1267,1270,-1, 1262,1267,1273,-1, 1265,1267,1262,-1, 1271,1270,1272,-1, 
+          1237,1272,1270,-1, 1273,1270,1271,-1, 1239,1272,1237,-1, 1265,1262,1261,-1, 1133,1135,1145,-1, 1168,1135,1133,-1, 
+          1165,1135,1168,-1, 1164,1135,1165,-1, 1141,1135,1164,-1, 1162,1145,1157,-1, 1132,1145,1162,-1, 1132,1133,1145,-1, 
+          1163,1132,1162,-1, 1175,1162,1174,-1, 1274,1275,1276,-1, 1277,1276,1275,-1, 1278,1274,1276,-1, 1277,1278,1276,-1, 
+          1279,1280,1275,-1, 1281,1275,1280,-1, 1274,1279,1275,-1, 1282,1277,1275,-1, 1281,1282,1275,-1, 1283,1284,1280,-1, 
+          1285,1280,1284,-1, 1279,1283,1280,-1, 1285,1281,1280,-1, 1286,1287,1284,-1, 1288,1284,1287,-1, 1283,1286,1284,-1, 
+          1288,1285,1284,-1, 1289,1290,1287,-1, 1291,1287,1290,-1, 1286,1289,1287,-1, 1291,1288,1287,-1, 1292,1293,1290,-1, 
+          1294,1290,1293,-1, 1289,1292,1290,-1, 1295,1290,1296,-1, 1294,1296,1290,-1, 1297,1291,1290,-1, 1295,1297,1290,-1, 
+          1298,1299,1293,-1, 1300,1293,1299,-1, 1292,1298,1293,-1, 1301,1294,1293,-1, 1300,1301,1293,-1, 1302,1303,1299,-1, 
+          1304,1299,1303,-1, 1298,1302,1299,-1, 1304,1300,1299,-1, 1305,1306,1303,-1, 1307,1303,1306,-1, 1302,1305,1303,-1, 
+          1307,1304,1303,-1, 1308,1306,1305,-1, 1309,1307,1306,-1, 1308,1309,1306,-1, 1308,1305,1302,-1, 1310,1302,1298,-1, 
+          1311,1308,1302,-1, 1310,1311,1302,-1, 1312,1298,1292,-1, 1312,1310,1298,-1, 1313,1292,1289,-1, 1313,1312,1292,-1, 
+          1314,1289,1286,-1, 1314,1313,1289,-1, 1315,1286,1283,-1, 1316,1286,1317,-1, 1315,1317,1286,-1, 1318,1314,1286,-1, 
+          1316,1318,1286,-1, 1319,1283,1279,-1, 1320,1315,1283,-1, 1319,1320,1283,-1, 1321,1279,1274,-1, 1321,1319,1279,-1, 
+          1322,1274,1278,-1, 1322,1321,1274,-1, 1323,1278,1277,-1, 1323,1322,1278,-1, 1324,1325,1326,-1, 1327,1326,1325,-1, 
+          1324,1326,1328,-1, 1329,1328,1326,-1, 1329,1326,1330,-1, 1327,1330,1326,-1, 1331,1332,1325,-1, 1327,1325,1332,-1, 
+          1324,1331,1325,-1, 1333,1334,1332,-1, 1335,1332,1334,-1, 1331,1333,1332,-1, 1336,1332,1335,-1, 1327,1332,1336,-1, 
+          1337,1338,1334,-1, 1339,1334,1338,-1, 1333,1337,1334,-1, 1335,1334,1339,-1, 1340,1341,1338,-1, 1342,1338,1341,-1, 
+          1337,1340,1338,-1, 1339,1338,1342,-1, 1343,1317,1341,-1, 1344,1341,1317,-1, 1345,1343,1341,-1, 1340,1345,1341,-1, 
+          1342,1341,1344,-1, 1346,1347,1317,-1, 1316,1317,1347,-1, 1343,1346,1317,-1, 1348,1344,1317,-1, 1315,1348,1317,-1, 
+          1349,1350,1347,-1, 1351,1347,1350,-1, 1346,1349,1347,-1, 1352,1347,1351,-1, 1316,1347,1352,-1, 1353,1354,1350,-1, 
+          1355,1350,1354,-1, 1349,1353,1350,-1, 1351,1350,1355,-1, 1356,1357,1354,-1, 1358,1354,1357,-1, 1353,1356,1354,-1, 
+          1355,1354,1358,-1, 1356,1359,1357,-1, 1360,1357,1359,-1, 1361,1357,1360,-1, 1358,1357,1361,-1, 1362,1363,1359,-1, 
+          1360,1359,1363,-1, 1356,1362,1359,-1, 1364,1365,1363,-1, 1366,1363,1365,-1, 1362,1364,1363,-1, 1367,1363,1366,-1, 
+          1360,1363,1367,-1, 1368,1369,1365,-1, 1370,1365,1369,-1, 1364,1368,1365,-1, 1366,1365,1370,-1, 1371,1372,1369,-1, 
+          1373,1369,1372,-1, 1368,1371,1369,-1, 1370,1369,1373,-1, 1374,1296,1372,-1, 1375,1372,1296,-1, 1376,1374,1372,-1, 
+          1371,1376,1372,-1, 1373,1372,1375,-1, 1377,1378,1296,-1, 1295,1296,1378,-1, 1377,1296,1374,-1, 1379,1375,1296,-1, 
+          1294,1379,1296,-1, 1380,1381,1378,-1, 1382,1378,1381,-1, 1377,1380,1378,-1, 1383,1378,1382,-1, 1295,1378,1383,-1, 
+          1384,1328,1381,-1, 1385,1381,1328,-1, 1380,1384,1381,-1, 1382,1381,1385,-1, 1384,1324,1328,-1, 1385,1328,1329,-1, 
+          1386,1374,1376,-1, 1387,1377,1374,-1, 1386,1387,1374,-1, 1388,1376,1371,-1, 1389,1376,1390,-1, 1391,1390,1376,-1, 
+          1392,1376,1389,-1, 1386,1376,1392,-1, 1388,1391,1376,-1, 1393,1371,1368,-1, 1388,1371,1393,-1, 1393,1368,1364,-1, 
+          1394,1364,1362,-1, 1393,1364,1394,-1, 1395,1362,1356,-1, 1396,1394,1362,-1, 1395,1396,1362,-1, 1397,1356,1353,-1, 
+          1397,1395,1356,-1, 1398,1353,1349,-1, 1397,1353,1398,-1, 1398,1349,1346,-1, 1399,1346,1343,-1, 1398,1346,1399,-1, 
+          1400,1343,1345,-1, 1400,1399,1343,-1, 1401,1345,1340,-1, 1402,1345,1403,-1, 1404,1403,1345,-1, 1405,1345,1402,-1, 
+          1400,1345,1405,-1, 1401,1404,1345,-1, 1406,1340,1337,-1, 1401,1340,1406,-1, 1406,1337,1333,-1, 1407,1333,1331,-1, 
+          1406,1333,1407,-1, 1408,1331,1324,-1, 1409,1331,1408,-1, 1409,1407,1331,-1, 1410,1324,1384,-1, 1408,1324,1410,-1, 
+          1411,1384,1380,-1, 1410,1384,1411,-1, 1411,1380,1377,-1, 1411,1377,1387,-1, 1412,1277,1282,-1, 1323,1277,1412,-1, 
+          1413,1282,1281,-1, 1413,1412,1282,-1, 1414,1281,1285,-1, 1414,1413,1281,-1, 1415,1285,1288,-1, 1415,1414,1285,-1, 
+          1416,1288,1291,-1, 1416,1415,1288,-1, 1297,1416,1291,-1, 1330,1412,1413,-1, 1417,1412,1330,-1, 1417,1323,1412,-1, 
+          1329,1413,1414,-1, 1329,1330,1413,-1, 1385,1414,1415,-1, 1385,1329,1414,-1, 1382,1415,1416,-1, 1382,1385,1415,-1, 
+          1383,1416,1297,-1, 1383,1382,1416,-1, 1295,1383,1297,-1, 1327,1417,1330,-1, 1418,1375,1379,-1, 1373,1375,1418,-1, 
+          1301,1379,1294,-1, 1418,1379,1301,-1, 1418,1301,1300,-1, 1419,1300,1304,-1, 1419,1418,1300,-1, 1420,1304,1307,-1, 
+          1420,1419,1304,-1, 1421,1307,1309,-1, 1421,1420,1307,-1, 1422,1421,1309,-1, 1423,1422,1309,-1, 1308,1423,1309,-1, 
+          1373,1418,1419,-1, 1370,1419,1420,-1, 1370,1373,1419,-1, 1366,1420,1421,-1, 1366,1370,1420,-1, 1367,1421,1422,-1, 
+          1367,1366,1421,-1, 1360,1367,1422,-1, 1361,1360,1422,-1, 1423,1361,1422,-1, 1424,1361,1423,-1, 1358,1361,1424,-1, 
+          1311,1423,1308,-1, 1424,1423,1311,-1, 1424,1311,1310,-1, 1425,1310,1312,-1, 1425,1424,1310,-1, 1426,1312,1313,-1, 
+          1426,1425,1312,-1, 1427,1313,1314,-1, 1427,1426,1313,-1, 1318,1427,1314,-1, 1358,1424,1425,-1, 1355,1425,1426,-1, 
+          1355,1358,1425,-1, 1351,1426,1427,-1, 1351,1355,1426,-1, 1352,1427,1318,-1, 1352,1351,1427,-1, 1316,1352,1318,-1, 
+          1428,1344,1348,-1, 1342,1344,1428,-1, 1320,1348,1315,-1, 1428,1348,1320,-1, 1428,1320,1319,-1, 1429,1319,1321,-1, 
+          1429,1428,1319,-1, 1430,1321,1322,-1, 1430,1429,1321,-1, 1431,1322,1323,-1, 1431,1430,1322,-1, 1417,1431,1323,-1, 
+          1342,1428,1429,-1, 1339,1429,1430,-1, 1339,1342,1429,-1, 1335,1430,1431,-1, 1335,1339,1430,-1, 1336,1431,1417,-1, 
+          1336,1335,1431,-1, 1327,1336,1417,-1, 1432,1433,1434,-1, 1435,1434,1433,-1, 1436,1432,1434,-1, 1435,1436,1434,-1, 
+          1432,1437,1433,-1, 1435,1433,1437,-1, 1432,1438,1437,-1, 1439,1437,1438,-1, 1435,1437,1439,-1, 1440,1441,1438,-1, 
+          1442,1438,1441,-1, 1432,1440,1438,-1, 1443,1439,1438,-1, 1442,1443,1438,-1, 1390,1444,1441,-1, 1445,1441,1444,-1, 
+          1446,1390,1441,-1, 1440,1446,1441,-1, 1442,1441,1445,-1, 1447,1403,1444,-1, 1445,1444,1403,-1, 1390,1447,1444,-1, 
+          1448,1449,1403,-1, 1402,1403,1449,-1, 1447,1448,1403,-1, 1450,1445,1403,-1, 1404,1450,1403,-1, 1448,1451,1449,-1, 
+          1452,1449,1451,-1, 1402,1449,1452,-1, 1453,1454,1451,-1, 1455,1451,1454,-1, 1448,1453,1451,-1, 1456,1452,1451,-1, 
+          1455,1456,1451,-1, 1457,1458,1454,-1, 1459,1454,1458,-1, 1460,1457,1454,-1, 1453,1460,1454,-1, 1455,1454,1459,-1, 
+          1461,1458,1457,-1, 1459,1458,1461,-1, 1461,1457,1460,-1, 1462,1460,1453,-1, 1461,1460,1462,-1, 1463,1453,1448,-1, 
+          1464,1462,1453,-1, 1463,1464,1453,-1, 1465,1448,1447,-1, 1463,1448,1465,-1, 1465,1447,1390,-1, 1389,1390,1446,-1, 
+          1466,1465,1390,-1, 1391,1466,1390,-1, 1467,1446,1440,-1, 1389,1446,1467,-1, 1468,1440,1432,-1, 1469,1467,1440,-1, 
+          1468,1469,1440,-1, 1436,1468,1432,-1, 1386,1470,1387,-1, 1471,1387,1470,-1, 1471,1411,1387,-1, 1392,1467,1470,-1, 
+          1469,1470,1467,-1, 1386,1392,1470,-1, 1469,1471,1470,-1, 1392,1389,1467,-1, 1410,1411,1471,-1, 1472,1471,1469,-1, 
+          1472,1410,1471,-1, 1468,1472,1469,-1, 1408,1410,1472,-1, 1473,1472,1468,-1, 1473,1408,1472,-1, 1436,1473,1468,-1, 
+          1409,1408,1473,-1, 1474,1473,1436,-1, 1409,1473,1474,-1, 1474,1436,1435,-1, 1463,1465,1466,-1, 1475,1466,1391,-1, 
+          1463,1466,1475,-1, 1475,1391,1388,-1, 1396,1476,1394,-1, 1477,1394,1476,-1, 1477,1393,1394,-1, 1478,1462,1476,-1, 
+          1464,1476,1462,-1, 1396,1478,1476,-1, 1464,1477,1476,-1, 1478,1461,1462,-1, 1459,1461,1478,-1, 1479,1478,1396,-1, 
+          1479,1459,1478,-1, 1395,1479,1396,-1, 1388,1393,1477,-1, 1475,1477,1464,-1, 1475,1388,1477,-1, 1463,1475,1464,-1, 
+          1455,1459,1479,-1, 1480,1479,1395,-1, 1455,1479,1480,-1, 1480,1395,1397,-1, 1400,1481,1399,-1, 1482,1399,1481,-1, 
+          1482,1398,1399,-1, 1405,1452,1481,-1, 1456,1481,1452,-1, 1400,1405,1481,-1, 1456,1482,1481,-1, 1405,1402,1452,-1, 
+          1397,1398,1482,-1, 1480,1482,1456,-1, 1480,1397,1482,-1, 1455,1480,1456,-1, 1442,1445,1450,-1, 1483,1450,1404,-1, 
+          1442,1450,1483,-1, 1483,1404,1401,-1, 1409,1484,1407,-1, 1485,1407,1484,-1, 1485,1406,1407,-1, 1474,1439,1484,-1, 
+          1443,1484,1439,-1, 1409,1474,1484,-1, 1443,1485,1484,-1, 1474,1435,1439,-1, 1401,1406,1485,-1, 1483,1485,1443,-1, 
+          1483,1401,1485,-1, 1442,1483,1443,-1, 
+          1604,1605,1606,-1, 1607,1606,1605,-1, 1608,1606,1609,-1, 1610,1609,1606,-1, 1604,1606,1608,-1, 1607,1610,1606,-1, 
+          1604,1611,1605,-1, 1612,1605,1611,-1, 1612,1607,1605,-1, 1604,1613,1611,-1, 1614,1611,1613,-1, 1614,1612,1611,-1, 
+          1615,1616,1613,-1, 1617,1613,1616,-1, 1604,1615,1613,-1, 1617,1614,1613,-1, 1615,1618,1616,-1, 1619,1616,1618,-1, 
+          1619,1617,1616,-1, 1620,1621,1618,-1, 1622,1618,1621,-1, 1615,1620,1618,-1, 1622,1619,1618,-1, 1623,1624,1621,-1, 
+          1625,1621,1624,-1, 1620,1623,1621,-1, 1625,1622,1621,-1, 1623,1626,1624,-1, 1627,1624,1626,-1, 1627,1625,1624,-1, 
+          1628,1629,1626,-1, 1630,1626,1629,-1, 1623,1628,1626,-1, 1630,1627,1626,-1, 1628,1631,1629,-1, 1632,1629,1631,-1, 
+          1632,1630,1629,-1, 1633,1634,1631,-1, 1635,1631,1634,-1, 1628,1633,1631,-1, 1632,1631,1635,-1, 1633,1636,1634,-1, 
+          1637,1634,1636,-1, 1637,1635,1634,-1, 1633,1638,1636,-1, 1639,1636,1638,-1, 1639,1637,1636,-1, 1640,1641,1638,-1, 
+          1642,1638,1641,-1, 1633,1640,1638,-1, 1642,1639,1638,-1, 1640,1643,1641,-1, 1644,1641,1643,-1, 1644,1642,1641,-1, 
+          1645,1646,1643,-1, 1647,1643,1646,-1, 1640,1645,1643,-1, 1647,1644,1643,-1, 1648,1649,1646,-1, 1650,1646,1649,-1, 
+          1645,1648,1646,-1, 1650,1647,1646,-1, 1648,1651,1649,-1, 1652,1649,1651,-1, 1652,1650,1649,-1, 1608,1609,1651,-1, 
+          1653,1651,1609,-1, 1648,1608,1651,-1, 1653,1652,1651,-1, 1610,1653,1609,-1, 1654,1608,1648,-1, 1655,1604,1608,-1, 
+          1655,1608,1654,-1, 1656,1648,1645,-1, 1656,1654,1648,-1, 1640,1657,1645,-1, 1658,1645,1657,-1, 1656,1645,1658,-1, 
+          1659,1657,1640,-1, 1658,1657,1659,-1, 1660,1640,1633,-1, 1659,1640,1660,-1, 1661,1633,1628,-1, 1660,1633,1661,-1, 
+          1662,1628,1623,-1, 1661,1628,1662,-1, 1663,1623,1620,-1, 1662,1623,1663,-1, 1615,1664,1620,-1, 1665,1620,1664,-1, 
+          1663,1620,1665,-1, 1666,1664,1615,-1, 1665,1664,1666,-1, 1667,1615,1604,-1, 1666,1615,1667,-1, 1667,1604,1655,-1, 
+          1668,1669,1670,-1, 1671,1670,1669,-1, 1672,1670,1673,-1, 1674,1673,1670,-1, 1675,1670,1672,-1, 1675,1668,1670,-1, 
+          1674,1670,1671,-1, 1676,1677,1669,-1, 1678,1669,1677,-1, 1679,1676,1669,-1, 1668,1679,1669,-1, 1678,1671,1669,-1, 
+          1680,1681,1677,-1, 1682,1677,1681,-1, 1683,1680,1677,-1, 1676,1683,1677,-1, 1678,1677,1682,-1, 1684,1681,1680,-1, 
+          1682,1681,1684,-1, 1685,1686,1680,-1, 1687,1680,1686,-1, 1688,1685,1680,-1, 1683,1688,1680,-1, 1684,1680,1687,-1, 
+          1689,1690,1686,-1, 1691,1686,1690,-1, 1692,1689,1686,-1, 1693,1692,1686,-1, 1685,1693,1686,-1, 1687,1686,1691,-1, 
+          1694,1695,1690,-1, 1696,1690,1695,-1, 1697,1694,1690,-1, 1689,1697,1690,-1, 1691,1690,1696,-1, 1698,1699,1695,-1, 
+          1700,1695,1699,-1, 1701,1698,1695,-1, 1694,1701,1695,-1, 1696,1695,1700,-1, 1702,1703,1699,-1, 1704,1699,1703,-1, 
+          1705,1702,1699,-1, 1698,1705,1699,-1, 1700,1699,1704,-1, 1706,1703,1702,-1, 1704,1703,1706,-1, 1707,1673,1702,-1, 
+          1708,1702,1673,-1, 1709,1707,1702,-1, 1705,1709,1702,-1, 1706,1702,1708,-1, 1710,1672,1673,-1, 1711,1710,1673,-1, 
+          1707,1711,1673,-1, 1708,1673,1674,-1, 1607,1672,1710,-1, 1612,1675,1672,-1, 1612,1672,1607,-1, 1610,1710,1711,-1, 
+          1607,1710,1610,-1, 1653,1711,1707,-1, 1610,1711,1653,-1, 1652,1707,1709,-1, 1653,1707,1652,-1, 1650,1709,1705,-1, 
+          1652,1709,1650,-1, 1647,1705,1698,-1, 1650,1705,1647,-1, 1644,1698,1701,-1, 1647,1698,1644,-1, 1642,1701,1694,-1, 
+          1644,1701,1642,-1, 1639,1694,1697,-1, 1642,1694,1639,-1, 1637,1697,1689,-1, 1639,1697,1637,-1, 1635,1689,1692,-1, 
+          1637,1689,1635,-1, 1632,1692,1693,-1, 1632,1635,1692,-1, 1630,1693,1685,-1, 1632,1693,1630,-1, 1627,1685,1688,-1, 
+          1630,1685,1627,-1, 1625,1688,1683,-1, 1627,1688,1625,-1, 1622,1683,1676,-1, 1625,1683,1622,-1, 1619,1676,1679,-1, 
+          1622,1676,1619,-1, 1617,1679,1668,-1, 1619,1679,1617,-1, 1614,1668,1675,-1, 1617,1668,1614,-1, 1614,1675,1612,-1, 
+          1678,1712,1713,-1, 1714,1713,1712,-1, 1671,1713,1715,-1, 1716,1715,1713,-1, 1678,1713,1671,-1, 1716,1713,1714,-1, 
+          1682,1717,1712,-1, 1718,1712,1717,-1, 1678,1682,1712,-1, 1718,1714,1712,-1, 1684,1719,1717,-1, 1720,1717,1719,-1, 
+          1682,1684,1717,-1, 1718,1717,1720,-1, 1684,1721,1719,-1, 1722,1719,1721,-1, 1720,1719,1722,-1, 1687,1723,1721,-1, 
+          1724,1721,1723,-1, 1684,1687,1721,-1, 1722,1721,1724,-1, 1696,1725,1723,-1, 1726,1723,1725,-1, 1691,1696,1723,-1, 
+          1687,1691,1723,-1, 1724,1723,1726,-1, 1700,1727,1725,-1, 1728,1725,1727,-1, 1696,1700,1725,-1, 1726,1725,1728,-1, 
+          1704,1729,1727,-1, 1730,1727,1729,-1, 1700,1704,1727,-1, 1728,1727,1730,-1, 1706,1731,1729,-1, 1732,1729,1731,-1, 
+          1704,1706,1729,-1, 1730,1729,1732,-1, 1706,1733,1731,-1, 1734,1731,1733,-1, 1732,1731,1734,-1, 1708,1715,1733,-1, 
+          1735,1733,1715,-1, 1706,1708,1733,-1, 1734,1733,1735,-1, 1674,1671,1715,-1, 1708,1674,1715,-1, 1735,1715,1716,-1, 
+          1718,1736,1737,-1, 1738,1737,1736,-1, 1714,1737,1739,-1, 1740,1739,1737,-1, 1718,1737,1714,-1, 1740,1737,1738,-1, 
+          1720,1741,1736,-1, 1742,1736,1741,-1, 1718,1720,1736,-1, 1742,1738,1736,-1, 1722,1743,1741,-1, 1744,1741,1743,-1, 
+          1720,1722,1741,-1, 1742,1741,1744,-1, 1722,1745,1743,-1, 1746,1743,1745,-1, 1744,1743,1746,-1, 1724,1747,1745,-1, 
+          1748,1745,1747,-1, 1722,1724,1745,-1, 1746,1745,1748,-1, 1728,1749,1747,-1, 1750,1747,1749,-1, 1726,1728,1747,-1, 
+          1724,1726,1747,-1, 1748,1747,1750,-1, 1730,1751,1749,-1, 1752,1749,1751,-1, 1728,1730,1749,-1, 1750,1749,1752,-1, 
+          1732,1753,1751,-1, 1754,1751,1753,-1, 1730,1732,1751,-1, 1752,1751,1754,-1, 1734,1755,1753,-1, 1756,1753,1755,-1, 
+          1732,1734,1753,-1, 1754,1753,1756,-1, 1734,1757,1755,-1, 1758,1755,1757,-1, 1756,1755,1758,-1, 1735,1739,1757,-1, 
+          1759,1757,1739,-1, 1734,1735,1757,-1, 1758,1757,1759,-1, 1716,1714,1739,-1, 1735,1716,1739,-1, 1759,1739,1740,-1, 
+          1742,1760,1761,-1, 1762,1761,1760,-1, 1738,1761,1763,-1, 1764,1763,1761,-1, 1742,1761,1738,-1, 1764,1761,1762,-1, 
+          1744,1765,1760,-1, 1766,1760,1765,-1, 1742,1744,1760,-1, 1766,1762,1760,-1, 1746,1767,1765,-1, 1768,1765,1767,-1, 
+          1744,1746,1765,-1, 1766,1765,1768,-1, 1746,1769,1767,-1, 1770,1767,1769,-1, 1768,1767,1770,-1, 1748,1771,1769,-1, 
+          1772,1769,1771,-1, 1746,1748,1769,-1, 1770,1769,1772,-1, 1752,1773,1771,-1, 1774,1771,1773,-1, 1750,1752,1771,-1, 
+          1748,1750,1771,-1, 1772,1771,1774,-1, 1754,1775,1773,-1, 1776,1773,1775,-1, 1752,1754,1773,-1, 1774,1773,1776,-1, 
+          1756,1777,1775,-1, 1778,1775,1777,-1, 1754,1756,1775,-1, 1776,1775,1778,-1, 1758,1779,1777,-1, 1780,1777,1779,-1, 
+          1756,1758,1777,-1, 1778,1777,1780,-1, 1758,1781,1779,-1, 1782,1779,1781,-1, 1780,1779,1782,-1, 1759,1763,1781,-1, 
+          1783,1781,1763,-1, 1758,1759,1781,-1, 1782,1781,1783,-1, 1740,1738,1763,-1, 1759,1740,1763,-1, 1783,1763,1764,-1, 
+          1766,1784,1785,-1, 1786,1785,1784,-1, 1762,1785,1787,-1, 1788,1787,1785,-1, 1766,1785,1762,-1, 1788,1785,1786,-1, 
+          1768,1789,1784,-1, 1790,1784,1789,-1, 1766,1768,1784,-1, 1790,1786,1784,-1, 1791,1792,1789,-1, 1793,1789,1792,-1, 
+          1770,1791,1789,-1, 1768,1770,1789,-1, 1790,1789,1793,-1, 1794,1792,1791,-1, 1793,1792,1794,-1, 1770,1795,1791,-1, 
+          1796,1791,1795,-1, 1794,1791,1796,-1, 1774,1797,1795,-1, 1798,1795,1797,-1, 1772,1774,1795,-1, 1770,1772,1795,-1, 
+          1796,1795,1798,-1, 1776,1799,1797,-1, 1800,1797,1799,-1, 1774,1776,1797,-1, 1798,1797,1800,-1, 1778,1801,1799,-1, 
+          1802,1799,1801,-1, 1776,1778,1799,-1, 1800,1799,1802,-1, 1780,1803,1801,-1, 1804,1801,1803,-1, 1778,1780,1801,-1, 
+          1802,1801,1804,-1, 1805,1806,1803,-1, 1807,1803,1806,-1, 1782,1805,1803,-1, 1780,1782,1803,-1, 1804,1803,1807,-1, 
+          1808,1806,1805,-1, 1807,1806,1808,-1, 1782,1809,1805,-1, 1810,1805,1809,-1, 1808,1805,1810,-1, 1764,1787,1809,-1, 
+          1811,1809,1787,-1, 1783,1764,1809,-1, 1782,1783,1809,-1, 1810,1809,1811,-1, 1764,1762,1787,-1, 1811,1787,1788,-1, 
+          1790,1812,1813,-1, 1814,1813,1812,-1, 1786,1813,1815,-1, 1816,1815,1813,-1, 1790,1813,1786,-1, 1816,1813,1814,-1, 
+          1794,1817,1812,-1, 1818,1812,1817,-1, 1793,1794,1812,-1, 1790,1793,1812,-1, 1818,1814,1812,-1, 1819,1820,1817,-1, 
+          1821,1817,1820,-1, 1822,1819,1817,-1, 1794,1822,1817,-1, 1818,1817,1821,-1, 1819,1823,1820,-1, 1824,1820,1823,-1, 
+          1821,1820,1824,-1, 1825,1823,1819,-1, 1824,1823,1825,-1, 1826,1819,1822,-1, 1825,1819,1826,-1, 1798,1827,1822,-1, 
+          1828,1822,1827,-1, 1796,1798,1822,-1, 1794,1796,1822,-1, 1826,1822,1828,-1, 1802,1829,1827,-1, 1830,1827,1829,-1, 
+          1800,1802,1827,-1, 1798,1800,1827,-1, 1828,1827,1830,-1, 1804,1831,1829,-1, 1832,1829,1831,-1, 1802,1804,1829,-1, 
+          1830,1829,1832,-1, 1808,1833,1831,-1, 1834,1831,1833,-1, 1807,1808,1831,-1, 1804,1807,1831,-1, 1832,1831,1834,-1, 
+          1835,1836,1833,-1, 1837,1833,1836,-1, 1838,1835,1833,-1, 1808,1838,1833,-1, 1834,1833,1837,-1, 1835,1839,1836,-1, 
+          1840,1836,1839,-1, 1837,1836,1840,-1, 1841,1839,1835,-1, 1840,1839,1841,-1, 1842,1835,1838,-1, 1841,1835,1842,-1, 
+          1811,1815,1838,-1, 1843,1838,1815,-1, 1810,1811,1838,-1, 1808,1810,1838,-1, 1842,1838,1843,-1, 1788,1786,1815,-1, 
+          1811,1788,1815,-1, 1843,1815,1816,-1, 1818,1655,1654,-1, 1814,1654,1656,-1, 1818,1654,1814,-1, 1818,1667,1655,-1, 
+          1821,1666,1667,-1, 1818,1821,1667,-1, 1830,1665,1666,-1, 1821,1830,1666,-1, 1830,1663,1665,-1, 1832,1662,1663,-1, 
+          1830,1832,1663,-1, 1834,1661,1662,-1, 1832,1834,1662,-1, 1834,1660,1661,-1, 1837,1659,1660,-1, 1834,1837,1660,-1, 
+          1816,1658,1659,-1, 1837,1816,1659,-1, 1816,1656,1658,-1, 1816,1814,1656,-1, 1837,1843,1816,-1, 1840,1842,1843,-1, 
+          1837,1840,1843,-1, 1840,1841,1842,-1, 1821,1828,1830,-1, 1824,1826,1828,-1, 1821,1824,1828,-1, 1824,1825,1826,-1
+        ]
+      }
+      appearance Appearance
+      {
+        material Material
+        {
+	       ambientIntensity 0.2
+	       diffuseColor 0.9 0.9 0.9
+	       specularColor .1 .1 .1
+	       shininess .5
+        }
+      }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/elbow_l.iv b/data/RobotAPI/robots/Armar3/fullmodel/elbow_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..ad3d7349062caae6eea99ebc4f096d985bf78de2
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/elbow_l.iv
@@ -0,0 +1,35 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units {
+            units MILLIMETERS
+    }
+
+ Transform {
+	translation 0 0 0
+	rotation 1 0 0 -1.57
+  }
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	} 
+ 
+	Transform {
+		#translation 0 0 0
+		rotation 0 1 0 3.14
+	} 
+        ## Kinematics 5.0 <-> armar model: 7.5
+	## Model of elbow is fixed to upperarm -> use offset, so transformations of kinematics have no effect
+#	Transform {
+#		translation 7.5 0 0 
+#		rotation 1 0 0 -0.07616814813524509
+#	} 
+	Transform {
+		translation 7.5 0 0
+		rotation 0 0 0 0 
+	} 
+#	File {name armar/hands/axis_arrows.iv }
+    	File { 
+      		name "armar/left_arm/elbow_link_l.iv"
+    	}
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/elbow_r.iv b/data/RobotAPI/robots/Armar3/fullmodel/elbow_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..710f51ae9de188c5a384841a0829947554144abf
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/elbow_r.iv
@@ -0,0 +1,30 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units {
+            units MILLIMETERS
+    }
+
+ Transform {
+	translation 0 0 0
+	rotation 1 0 0 1.57
+  }
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 1.57
+	} 
+        ## Kinematics 5.0 <-> armar model: 7.5
+	## Model of elbow is fixed to upperarm -> use offset, so transformations of kinematics have no effect
+#	Transform {
+#		translation 7.5 0 0 
+#		rotation 1 0 0 -0.07616814813524509
+#	} 
+	Transform {
+		translation 7.5 0 0
+		rotation 0 0 0 0 
+	} 
+#	File {name armar/hands/axis_arrows.iv }
+    	File { 
+      		name "armar/left_arm/elbow_link_l.iv"
+    	}
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/eye_l.iv b/data/RobotAPI/robots/Armar3/fullmodel/eye_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..5df57b2eae4774b2ab640eae55cd307d579aabc0
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/eye_l.iv
@@ -0,0 +1,16 @@
+#Inventor V2.1 ascii
+
+Separator {
+
+	Transform {
+		rotation 0 1 0 1.57
+	}
+
+	Transform {
+		rotation 0 0 1 1.57
+	}
+
+	File { 
+	  name "armar/eyes/eye.iv"
+	}
+} 
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/eye_link_l.iv b/data/RobotAPI/robots/Armar3/fullmodel/eye_link_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..8ec3c25ef28e6090eac76046700d629af1dce75e
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/eye_link_l.iv
@@ -0,0 +1,16 @@
+#Inventor V2.1 ascii
+
+Separator { 
+
+	Transform {
+		rotation 0 1 0 1.57
+	}
+
+	Transform {
+		rotation 1 0 0 1.57
+	}
+
+	File { 
+		name "armar/eyes/eyes_pitch_link_left.iv"
+	}
+} 
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/eye_link_r.iv b/data/RobotAPI/robots/Armar3/fullmodel/eye_link_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..5aef77b4bd7fc28d302e638b4fa0d368fc2d805f
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/eye_link_r.iv
@@ -0,0 +1,16 @@
+#Inventor V2.1 ascii
+
+Separator {
+
+	Transform {
+		rotation 0 1 0 1.57
+	}
+
+	Transform {
+		rotation 1 0 0 1.57
+	}
+
+	File { 
+	  name "armar/eyes/eyes_pitch_link_right.iv"
+	}
+} 
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/eye_r.iv b/data/RobotAPI/robots/Armar3/fullmodel/eye_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..5df57b2eae4774b2ab640eae55cd307d579aabc0
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/eye_r.iv
@@ -0,0 +1,16 @@
+#Inventor V2.1 ascii
+
+Separator {
+
+	Transform {
+		rotation 0 1 0 1.57
+	}
+
+	Transform {
+		rotation 0 0 1 1.57
+	}
+
+	File { 
+	  name "armar/eyes/eye.iv"
+	}
+} 
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/head.iv b/data/RobotAPI/robots/Armar3/fullmodel/head.iv
new file mode 100644
index 0000000000000000000000000000000000000000..6527ea098aa8ab01a82add6f4aa2fd1b9878d0c4
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/head.iv
@@ -0,0 +1,12 @@
+#Inventor V2.1 ascii
+
+Separator { 
+
+	Transform {
+		rotation 0 1 0 1.57
+	}
+
+	File { 
+		name "armar/head/head.iv"
+	}
+} 
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/head_base.iv b/data/RobotAPI/robots/Armar3/fullmodel/head_base.iv
new file mode 100644
index 0000000000000000000000000000000000000000..4d61ea7b5ca29e1af5cabf16ed4aab7bcc7aeb77
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/head_base.iv
@@ -0,0 +1,19 @@
+#Inventor V2.1 ascii
+
+Separator {
+    SoUnits
+    { 
+        units MILLIMETERS
+    }
+    Transform {
+		translation -35 0 -605
+	}
+    RotationXYZ{
+      axis Z
+      angle 3.14
+    }
+    
+    File { 
+      name "armar/head/head_base.wrl"
+    }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/index_l1.iv b/data/RobotAPI/robots/Armar3/fullmodel/index_l1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..b183bc5ab7f6d47adc995317b5d0c5187e0acb5e
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/index_l1.iv
@@ -0,0 +1,17 @@
+#Inventor V2.1 ascii
+
+Separator {
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	}
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+	}
+
+	Separator 
+	{
+		File {name armar/hands/metacarpals.iv }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/index_l2.iv b/data/RobotAPI/robots/Armar3/fullmodel/index_l2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..176a62121362a034d0d1b559788d381db31bf678
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/index_l2.iv
@@ -0,0 +1,17 @@
+#Inventor V2.1 ascii
+
+Separator {
+
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	} 
+	Separator 
+	{
+		File {name armar/hands/proximal_index_middle_thumb.iv }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/index_r1.iv b/data/RobotAPI/robots/Armar3/fullmodel/index_r1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..b183bc5ab7f6d47adc995317b5d0c5187e0acb5e
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/index_r1.iv
@@ -0,0 +1,17 @@
+#Inventor V2.1 ascii
+
+Separator {
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	}
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+	}
+
+	Separator 
+	{
+		File {name armar/hands/metacarpals.iv }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/index_r2.iv b/data/RobotAPI/robots/Armar3/fullmodel/index_r2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..695d4bd7dedb74de276a2c8f377346a6d26b23f7
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/index_r2.iv
@@ -0,0 +1,18 @@
+#Inventor V2.1 ascii
+
+Separator {
+
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	} 
+
+	Separator 
+	{
+		File {name armar/hands/proximal_index_middle_thumb.iv }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/jaw.iv b/data/RobotAPI/robots/Armar3/fullmodel/jaw.iv
new file mode 100644
index 0000000000000000000000000000000000000000..a6cd0a5319271bf01eb7f327b1ac5ab7ff3751e0
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/jaw.iv
@@ -0,0 +1,20 @@
+#Inventor V2.1 ascii
+
+Separator { 
+
+    Units {
+            units MILLIMETERS
+    }
+	Transform {
+		translation 0 10 0 
+		rotation 0 0 1 1.57
+	}
+
+	Transform {
+		rotation 0 1 0 -1.57
+	}
+
+	File { 
+		name "armar/head/jaw.iv"
+	}
+} 
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/lid_l_bottom.iv b/data/RobotAPI/robots/Armar3/fullmodel/lid_l_bottom.iv
new file mode 100644
index 0000000000000000000000000000000000000000..fee6dbbbc050aba14dccd2977e038c56c95f1e6a
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/lid_l_bottom.iv
@@ -0,0 +1,11 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Transform {
+		translation 0 0 0
+		rotation 0 1 0 -0.87
+	} 
+	File { 
+		name "armar/eyes/lid.iv"
+	}
+} 
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/lid_l_top.iv b/data/RobotAPI/robots/Armar3/fullmodel/lid_l_top.iv
new file mode 100644
index 0000000000000000000000000000000000000000..b3cbbaed2c7dfbb0e4787964dd903c830fed993a
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/lid_l_top.iv
@@ -0,0 +1,11 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Transform {
+		translation 0 0 0
+		rotation 0 1 0 -2.44
+	} 
+	File { 
+		name "armar/eyes/lid.iv"
+	}
+} 
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/lid_r_bottom.iv b/data/RobotAPI/robots/Armar3/fullmodel/lid_r_bottom.iv
new file mode 100644
index 0000000000000000000000000000000000000000..fee6dbbbc050aba14dccd2977e038c56c95f1e6a
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/lid_r_bottom.iv
@@ -0,0 +1,11 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Transform {
+		translation 0 0 0
+		rotation 0 1 0 -0.87
+	} 
+	File { 
+		name "armar/eyes/lid.iv"
+	}
+} 
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/lid_r_top.iv b/data/RobotAPI/robots/Armar3/fullmodel/lid_r_top.iv
new file mode 100644
index 0000000000000000000000000000000000000000..9e55171a4ab2695f4a37127c60f9b6f5f80769e1
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/lid_r_top.iv
@@ -0,0 +1,12 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Transform {
+		translation 0 0 0
+		rotation 0 1 0 -2.44
+	} 
+
+	File { 
+		name "armar/eyes/lid.iv"
+	}
+} 
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/middle_l1.iv b/data/RobotAPI/robots/Armar3/fullmodel/middle_l1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..b183bc5ab7f6d47adc995317b5d0c5187e0acb5e
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/middle_l1.iv
@@ -0,0 +1,17 @@
+#Inventor V2.1 ascii
+
+Separator {
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	}
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+	}
+
+	Separator 
+	{
+		File {name armar/hands/metacarpals.iv }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/middle_l2.iv b/data/RobotAPI/robots/Armar3/fullmodel/middle_l2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..695d4bd7dedb74de276a2c8f377346a6d26b23f7
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/middle_l2.iv
@@ -0,0 +1,18 @@
+#Inventor V2.1 ascii
+
+Separator {
+
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	} 
+
+	Separator 
+	{
+		File {name armar/hands/proximal_index_middle_thumb.iv }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/middle_r1.iv b/data/RobotAPI/robots/Armar3/fullmodel/middle_r1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..b183bc5ab7f6d47adc995317b5d0c5187e0acb5e
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/middle_r1.iv
@@ -0,0 +1,17 @@
+#Inventor V2.1 ascii
+
+Separator {
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	}
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+	}
+
+	Separator 
+	{
+		File {name armar/hands/metacarpals.iv }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/middle_r2.iv b/data/RobotAPI/robots/Armar3/fullmodel/middle_r2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..176a62121362a034d0d1b559788d381db31bf678
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/middle_r2.iv
@@ -0,0 +1,17 @@
+#Inventor V2.1 ascii
+
+Separator {
+
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	} 
+	Separator 
+	{
+		File {name armar/hands/proximal_index_middle_thumb.iv }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/neck_pitch_link.iv b/data/RobotAPI/robots/Armar3/fullmodel/neck_pitch_link.iv
new file mode 100644
index 0000000000000000000000000000000000000000..237445f2b1da9cd2e7311d6fe6ca50f1abdef60c
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/neck_pitch_link.iv
@@ -0,0 +1,15 @@
+#Inventor V2.1 ascii
+
+Separator { 
+	Transform {
+		rotation 0 0 1 -1.57
+	}
+	Transform {
+		rotation 1 0 0 -1.57
+	}
+
+
+	File { 
+	  name "armar/neck/neck_pitch_link.iv"
+	}
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/neck_roll_link.iv b/data/RobotAPI/robots/Armar3/fullmodel/neck_roll_link.iv
new file mode 100644
index 0000000000000000000000000000000000000000..4e2ae6db9eec0d30223ada356ee93e444fb01bc2
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/neck_roll_link.iv
@@ -0,0 +1,14 @@
+#Inventor V2.1 ascii
+
+Separator { 
+	Transform {
+		rotation 0 0 1 -1.57
+	}
+	Transform {
+		rotation 0 1 0 -1.57
+	}
+
+	File { 
+		name "armar/neck/neck_yaw_link.iv"
+	}
+} 
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/neck_yaw_link.iv b/data/RobotAPI/robots/Armar3/fullmodel/neck_yaw_link.iv
new file mode 100644
index 0000000000000000000000000000000000000000..ab3875f0aa57811e5a5d82470b5e40ce7b474273
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/neck_yaw_link.iv
@@ -0,0 +1,16 @@
+#Inventor V2.1 ascii
+
+Separator { 
+
+	Transform {
+		rotation 0 1 0 3.14
+	}
+
+	Transform {
+		rotation 0 0 1 1.57
+	}
+
+	File { 
+		name "armar/neck/neck_roll_link.iv"
+	}
+} 
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/palm1_l.iv b/data/RobotAPI/robots/Armar3/fullmodel/palm1_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..a568672fda16bccd8c40d0d67c0c7f7cd0117f8e
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/palm1_l.iv
@@ -0,0 +1,14 @@
+#Inventor V2.1 ascii
+
+Separator {
+
+	Transform {
+		translation 0 0 0
+		rotation 0 0 -1 1.57
+	} 
+
+	Separator 
+	{
+		File {name armar/hands/palm1_l.iv }
+	}
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/palm1_r.iv b/data/RobotAPI/robots/Armar3/fullmodel/palm1_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..26bd093ce0fe42ca29d0ea31ce7ec6afd5c79a30
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/palm1_r.iv
@@ -0,0 +1,18 @@
+#Inventor V2.1 ascii
+
+Separator {
+
+	Transform {
+		translation 0 0 0
+		rotation 0 0 -1 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 3.1415
+	} 
+
+	Separator 
+	{
+		File {name armar/hands/palm1_r.iv }
+	}
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/palm2_l.iv b/data/RobotAPI/robots/Armar3/fullmodel/palm2_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..dbdb1c8a987cb1d9f7dd9cb39b65f769b63d7073
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/palm2_l.iv
@@ -0,0 +1,17 @@
+#Inventor V2.1 ascii
+
+Separator {
+
+	Transform {
+		translation 0 0 0
+		rotation 0 0 -1 1.57
+	} 
+	Transform {
+		rotation 0 1 0 1.57
+	} 
+
+	Separator 
+	{
+		File {name armar/hands/palm2_l.iv }
+	}
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/palm2_r.iv b/data/RobotAPI/robots/Armar3/fullmodel/palm2_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..3f7e826e1f305241a7ccf99c70f16992c4d88eb5
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/palm2_r.iv
@@ -0,0 +1,17 @@
+#Inventor V2.1 ascii
+
+Separator {
+
+	Transform {
+		translation 0 0 0
+		rotation 0 0 -1 1.57
+	} 
+	Transform {
+		rotation 0 1 0 -1.57
+	} 
+
+	Separator 
+	{
+		File {name armar/hands/palm2_r.iv }
+	}
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/pinky_l1.iv b/data/RobotAPI/robots/Armar3/fullmodel/pinky_l1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..b183bc5ab7f6d47adc995317b5d0c5187e0acb5e
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/pinky_l1.iv
@@ -0,0 +1,17 @@
+#Inventor V2.1 ascii
+
+Separator {
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	}
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+	}
+
+	Separator 
+	{
+		File {name armar/hands/metacarpals.iv }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/pinky_l2.iv b/data/RobotAPI/robots/Armar3/fullmodel/pinky_l2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..05c1d220c06c592f6c81c64c05265f0abfcea07e
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/pinky_l2.iv
@@ -0,0 +1,17 @@
+#Inventor V2.1 ascii
+
+Separator {
+
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	} 
+	Separator 
+	{
+		File {name armar/hands/proximal_pinky.iv }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/pinky_r1.iv b/data/RobotAPI/robots/Armar3/fullmodel/pinky_r1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..b183bc5ab7f6d47adc995317b5d0c5187e0acb5e
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/pinky_r1.iv
@@ -0,0 +1,17 @@
+#Inventor V2.1 ascii
+
+Separator {
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	}
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+	}
+
+	Separator 
+	{
+		File {name armar/hands/metacarpals.iv }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/pinky_r2.iv b/data/RobotAPI/robots/Armar3/fullmodel/pinky_r2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..05c1d220c06c592f6c81c64c05265f0abfcea07e
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/pinky_r2.iv
@@ -0,0 +1,17 @@
+#Inventor V2.1 ascii
+
+Separator {
+
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	} 
+	Separator 
+	{
+		File {name armar/hands/proximal_pinky.iv }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/platform.iv b/data/RobotAPI/robots/Armar3/fullmodel/platform.iv
new file mode 100644
index 0000000000000000000000000000000000000000..2cc73bb1aabc6e4fbdb9ec1d79ac0681ef16feda
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/platform.iv
@@ -0,0 +1,16 @@
+#Inventor V2.1 ascii
+
+Separator { #Model
+
+ RotationXYZ {
+   axis X
+   angle 1.57
+   }
+ RotationXYZ{
+ 	axis Z
+	angle -1.57
+ }
+ File { 
+  name "armar/platform/platform.iv"
+ }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/platform_pitch_link.iv b/data/RobotAPI/robots/Armar3/fullmodel/platform_pitch_link.iv
new file mode 100644
index 0000000000000000000000000000000000000000..8d997bc117be3266d3553b8a3e633bac3af47696
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/platform_pitch_link.iv
@@ -0,0 +1,12 @@
+#Inventor V2.1 ascii
+
+Separator { #Model
+RotationXYZ{
+ 	axis Z
+	angle 1.57
+ }
+
+ File { 
+  name "armar/platform/hd_platform_pitch_link.iv"
+ }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/platform_roll_link.iv b/data/RobotAPI/robots/Armar3/fullmodel/platform_roll_link.iv
new file mode 100644
index 0000000000000000000000000000000000000000..9e8e96625a7ebe87015c116ef66bedc27d9baebc
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/platform_roll_link.iv
@@ -0,0 +1,24 @@
+#Inventor V2.1 ascii
+
+Separator { #Model
+    Units {
+            units MILLIMETERS
+    }
+RotationXYZ{
+  axis Z
+  angle 1.57
+}
+Transform{
+translation	0 0 127
+}
+Transform {
+  rotation 0 1 0 3.1415
+}
+Transform {
+  rotation 0 0 1 -1.57
+}
+#File {name armar/hands/axis_arrows.iv }
+ File { 
+  name "armar/platform/hd_platform_roll_link.iv"
+ }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/ring_l1.iv b/data/RobotAPI/robots/Armar3/fullmodel/ring_l1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..b183bc5ab7f6d47adc995317b5d0c5187e0acb5e
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/ring_l1.iv
@@ -0,0 +1,17 @@
+#Inventor V2.1 ascii
+
+Separator {
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	}
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+	}
+
+	Separator 
+	{
+		File {name armar/hands/metacarpals.iv }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/ring_l2.iv b/data/RobotAPI/robots/Armar3/fullmodel/ring_l2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..6874df6da94609201faa33b12ec4ca4488db9a97
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/ring_l2.iv
@@ -0,0 +1,17 @@
+#Inventor V2.1 ascii
+
+Separator {
+
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	} 
+	Separator 
+	{
+		File {name armar/hands/proximal_ring.iv }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/ring_r1.iv b/data/RobotAPI/robots/Armar3/fullmodel/ring_r1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..b183bc5ab7f6d47adc995317b5d0c5187e0acb5e
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/ring_r1.iv
@@ -0,0 +1,17 @@
+#Inventor V2.1 ascii
+
+Separator {
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	}
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+	}
+
+	Separator 
+	{
+		File {name armar/hands/metacarpals.iv }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/ring_r2.iv b/data/RobotAPI/robots/Armar3/fullmodel/ring_r2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..e452991409d1001847c7f3e8458a1ed34c6f92a2
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/ring_r2.iv
@@ -0,0 +1,19 @@
+#Inventor V2.1 ascii
+
+Separator {
+
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 -1.57
+	} 
+
+
+	Separator 
+	{
+		File {name armar/hands/proximal_ring.iv }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/shoulder2_l_rot.iv b/data/RobotAPI/robots/Armar3/fullmodel/shoulder2_l_rot.iv
new file mode 100644
index 0000000000000000000000000000000000000000..ece59e1732f61046f32e1da749e8fa257dacf44e
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/shoulder2_l_rot.iv
@@ -0,0 +1,16 @@
+#Inventor V2.1 ascii
+Separator {
+
+  Transform {
+	translation 0 0 0
+	rotation 0 0 1  1.57
+  }
+  Transform {
+	translation 0 0 0
+  rotation 0 0 1 1.57  
+  }
+    	File { 
+      		name "armar/left_arm/shoulder_link_l.iv"
+    	}
+
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/shoulder2_r_rot.iv b/data/RobotAPI/robots/Armar3/fullmodel/shoulder2_r_rot.iv
new file mode 100644
index 0000000000000000000000000000000000000000..b13e4cec80d06e8dd553bc783c3486cdf3c082f0
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/shoulder2_r_rot.iv
@@ -0,0 +1,20 @@
+#Inventor V2.1 ascii
+Separator {
+
+  Transform {
+	translation 0 0 0
+	rotation 0 0 1  -1.57
+  }
+  Transform {
+	translation 0 0 0
+	rotation 0 1 0 3.14
+}
+  Transform {
+	translation 0 0 0
+	rotation 0 0 1  1.57
+  }
+    	File { 
+      		name "armar/right_arm/shoulder_link_r.iv"
+    	}
+
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/shoulder_l.iv b/data/RobotAPI/robots/Armar3/fullmodel/shoulder_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..87a070db83d010019ff2598f386f30a25da0121a
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/shoulder_l.iv
@@ -0,0 +1,24 @@
+#Inventor V2.1 ascii
+Separator {
+
+    Units {
+            units MILLIMETERS
+    }
+  Transform {
+	translation 0 0 0
+	rotation 0 0 1 -1.57
+  }
+
+  Transform {
+	translation 0 0 -110
+	rotation 0 0 0 0
+  }
+  Transform {
+	translation 0 0 0
+	rotation 0 1 0 -1.57
+  } 
+#  File {name armar/hands/axis_arrows.iv }
+  File { 
+	name "armar/left_arm/shoulder_l.iv"
+  }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/shoulder_r.iv b/data/RobotAPI/robots/Armar3/fullmodel/shoulder_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..3723f8148b286f5e30868bb23c3fa8cee2a25e3b
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/shoulder_r.iv
@@ -0,0 +1,22 @@
+#Inventor V2.1 ascii
+Separator {
+    Units {
+            units MILLIMETERS
+    }
+  Transform {
+	translation 0 0 0
+	rotation 0 0 1 1.57
+  }
+  Transform {
+	translation 0 0 0
+	rotation 0 1 0 3.14
+  }
+  Transform {
+	translation 0 0 -110
+	rotation 0 0 0 0
+  }
+ 
+  File { 
+	name "armar/right_arm/shoulder_r.iv"
+  }
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/thumb_l1.iv b/data/RobotAPI/robots/Armar3/fullmodel/thumb_l1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..09b5f121e0eec2a26c9f529f2632d9d824fa6559
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/thumb_l1.iv
@@ -0,0 +1,12 @@
+#Inventor V2.1 ascii
+
+Separator {
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 -1.57
+	}	
+	Separator 
+	{
+		File {name armar/hands/metacarpals.iv }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/thumb_l2.iv b/data/RobotAPI/robots/Armar3/fullmodel/thumb_l2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..67212f9eea5a52619381380f4544a9b1dc20915f
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/thumb_l2.iv
@@ -0,0 +1,13 @@
+#Inventor V2.1 ascii
+
+Separator {
+
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 -1.57
+	} 
+	Separator 
+	{
+		File {name armar/hands/proximal_index_middle_thumb.iv }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/thumb_r1.iv b/data/RobotAPI/robots/Armar3/fullmodel/thumb_r1.iv
new file mode 100644
index 0000000000000000000000000000000000000000..09b5f121e0eec2a26c9f529f2632d9d824fa6559
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/thumb_r1.iv
@@ -0,0 +1,12 @@
+#Inventor V2.1 ascii
+
+Separator {
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 -1.57
+	}	
+	Separator 
+	{
+		File {name armar/hands/metacarpals.iv }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/thumb_r2.iv b/data/RobotAPI/robots/Armar3/fullmodel/thumb_r2.iv
new file mode 100644
index 0000000000000000000000000000000000000000..6301183b6a19ace4a20fde4994f07bbf6508f78f
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/thumb_r2.iv
@@ -0,0 +1,15 @@
+#Inventor V2.1 ascii
+
+Separator {
+
+ 
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 -1.57
+	} 
+
+	Separator 
+	{
+		File {name armar/hands/proximal_index_middle_thumb.iv }
+	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/torso.iv b/data/RobotAPI/robots/Armar3/fullmodel/torso.iv
new file mode 100644
index 0000000000000000000000000000000000000000..8cacfbbc8ab0fb4d611e317d55c80a798fa9dfec
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/torso.iv
@@ -0,0 +1,16 @@
+#Inventor V2.1 ascii
+Separator { #Model
+
+    SoUnits
+    { 
+        units MILLIMETERS
+    }
+    RotationXYZ{
+      axis Z
+      angle 1.57
+    }
+    
+    File { 
+      name "armar/torso/hd_torso2.wrl"
+    }
+} #Model
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/underarm_l.iv b/data/RobotAPI/robots/Armar3/fullmodel/underarm_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..b0edaade4fbaeacd90c9424eecc221f90dc7e7bd
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/underarm_l.iv
@@ -0,0 +1,23 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units {
+            units MILLIMETERS
+    }
+	Transform {
+		translation 0 0 -46.5
+		rotation 0 0 0 0 
+	}
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 3.14
+	}
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 1.57
+	}
+
+   	File { 
+      		name "armar/left_arm/underarm_l.iv"
+    	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/underarm_r.iv b/data/RobotAPI/robots/Armar3/fullmodel/underarm_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..2199eaf119c0d19b40a2cef82fc3ca6fa011c0b3
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/underarm_r.iv
@@ -0,0 +1,21 @@
+#Inventor V2.1 ascii
+
+Separator {
+    Units {
+            units MILLIMETERS
+    }
+
+	Transform {
+		translation 0 0 -46.5
+		rotation 0 0 0 0 
+	}
+	
+		Transform {
+		translation 0 0 0
+		rotation 0 0 1 1.57
+	}
+
+   	File { 
+      		name "armar/right_arm/underarm_r.iv"
+    	}
+}
\ No newline at end of file
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/upperarm_l.iv b/data/RobotAPI/robots/Armar3/fullmodel/upperarm_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..25d665f810b5932cb024b6e2b9f55b492f75c06a
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/upperarm_l.iv
@@ -0,0 +1,19 @@
+#Inventor V2.1 ascii
+Separator {
+    Units {
+            units MILLIMETERS
+    }
+
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 -1.57
+	}
+
+	Transform {
+		translation -25.3 0 0 
+	}
+# File {name armar/hands/axis_arrows.iv }
+    	File { 
+      		name "armar/left_arm/upperarm_l.iv"
+    	}
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/upperarm_r.iv b/data/RobotAPI/robots/Armar3/fullmodel/upperarm_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..b0da9cd8ab84e8e17457b656ce2793258c36f279
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/upperarm_r.iv
@@ -0,0 +1,22 @@
+#Inventor V2.1 ascii
+Separator {
+    Units {
+            units MILLIMETERS
+    }
+
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 -1.57
+	}
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 3.14
+	}
+	Transform {
+		translation -25.3 0 0 
+	}
+# File {name armar/hands/axis_arrows.iv }
+    	File { 
+      		name "armar/right_arm/upperarm_r.iv"
+    	}
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/wrist1_l.iv b/data/RobotAPI/robots/Armar3/fullmodel/wrist1_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..7da3fd6bd90e07b945cf6b976b7e649fced49107
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/wrist1_l.iv
@@ -0,0 +1,14 @@
+#Inventor V2.1 ascii
+
+Separator {
+
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+	} 
+
+	Separator 
+	{
+		File {name armar/hands/handlink_red.iv }
+	}
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/wrist1_r.iv b/data/RobotAPI/robots/Armar3/fullmodel/wrist1_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..ada4c2c446ced721414425b84216164381259677
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/wrist1_r.iv
@@ -0,0 +1,24 @@
+#Inventor V2.1 ascii
+
+Separator {
+
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+#File {name armar/hands/axis_arrows.iv }
+
+
+	Separator 
+	{
+		File {name armar/hands/handlink_red.iv }
+	}
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/wrist2_l.iv b/data/RobotAPI/robots/Armar3/fullmodel/wrist2_l.iv
new file mode 100644
index 0000000000000000000000000000000000000000..60ecde4082d335b567228747aa4ce4123d2a0c87
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/wrist2_l.iv
@@ -0,0 +1,25 @@
+#Inventor V2.1 ascii
+
+Separator {
+
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 1.57
+	}
+	Transform {
+		translation 0 0 0
+		rotation 1 0 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+	} 
+	 
+#File {name armar/hands/axis_arrows.iv }
+
+
+	Separator 
+	{
+		File {name armar/hands/handlink_green.iv }
+	}
+}
diff --git a/data/RobotAPI/robots/Armar3/fullmodel/wrist2_r.iv b/data/RobotAPI/robots/Armar3/fullmodel/wrist2_r.iv
new file mode 100644
index 0000000000000000000000000000000000000000..ba755a841f73dcc16ac4b2884e175ee86bc36105
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/fullmodel/wrist2_r.iv
@@ -0,0 +1,22 @@
+#Inventor V2.1 ascii
+
+Separator {
+
+	Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+	} 
+	Transform {
+		translation 0 0 0
+		rotation 0 0 1 1.57
+	} 
+		Transform {
+		translation 0 0 0
+		rotation 0 1 0 1.57
+} 
+
+	Separator 
+	{
+		File {name armar/hands/handlink_green.iv }
+	}
+}
diff --git a/data/RobotAPI/robots/Armar3/iv_primitives/cyl1.wrl b/data/RobotAPI/robots/Armar3/iv_primitives/cyl1.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..48957094e70a16fcd576592cb97338bea7f3dcba
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/iv_primitives/cyl1.wrl
@@ -0,0 +1,21 @@
+#VRML V2.0 utf8
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 0.001 0.001 0.001 # mm -> m
+  translation 0 0 0
+  children
+  [
+    Shape {
+        appearance Appearance {
+            material Material { }
+        }
+        geometry Cylinder {
+            height 60
+            radius 20
+        }
+    }
+  ]
+}
diff --git a/data/RobotAPI/robots/Armar3/iv_primitives/cyl2.wrl b/data/RobotAPI/robots/Armar3/iv_primitives/cyl2.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..59f24c981457f4a27aaa4f52fb5ca44423ab86c7
--- /dev/null
+++ b/data/RobotAPI/robots/Armar3/iv_primitives/cyl2.wrl
@@ -0,0 +1,22 @@
+#VRML V2.0 utf8
+
+NavigationInfo {
+	type [ "EXAMINE", "ANY" ]
+}
+Transform {
+  scale 0.001 0.001 0.001 # mm -> m
+  translation 0 0 0
+  rotation 1 0 0 1.57
+  children
+  [
+    Shape {
+        appearance Appearance {
+            material Material { }
+        }
+        geometry Cylinder {
+            height 30
+            radius 10
+        }
+    }
+  ]
+}
diff --git a/etc/cmake/ArmarXPackageVersion.cmake b/etc/cmake/ArmarXPackageVersion.cmake
index 60397fc223b5b4b99939b2a30c26171911c353f1..80e3e95aaf011b8fdd89e4c9af73cfe084a6d586 100644
--- a/etc/cmake/ArmarXPackageVersion.cmake
+++ b/etc/cmake/ArmarXPackageVersion.cmake
@@ -1,7 +1,7 @@
 # armarx version file
 set(ARMARX_PACKAGE_LIBRARY_VERSION_MAJOR "0")
-set(ARMARX_PACKAGE_LIBRARY_VERSION_MINOR "6")
-set(ARMARX_PACKAGE_LIBRARY_VERSION_PATCH "2")
+set(ARMARX_PACKAGE_LIBRARY_VERSION_MINOR "7")
+set(ARMARX_PACKAGE_LIBRARY_VERSION_PATCH "5")
 
 set(ARMARX_PACKAGE_LIBRARY_VERSION "${ARMARX_PACKAGE_LIBRARY_VERSION_MAJOR}.${ARMARX_PACKAGE_LIBRARY_VERSION_MINOR}.${ARMARX_PACKAGE_LIBRARY_VERSION_PATCH}")
 
diff --git a/etc/doxygen/images/TCPMoverGUI.png b/etc/doxygen/images/TCPMoverGUI.png
new file mode 100644
index 0000000000000000000000000000000000000000..20547a239b77dbc5566412d2bf164242183b6521
Binary files /dev/null and b/etc/doxygen/images/TCPMoverGUI.png differ
diff --git a/etc/doxygen/images/sensoractorunits.svg b/etc/doxygen/images/sensoractorunits.svg
new file mode 100644
index 0000000000000000000000000000000000000000..19bdf5b56a443aa561caad4986efb6e824e90ba0
--- /dev/null
+++ b/etc/doxygen/images/sensoractorunits.svg
@@ -0,0 +1,4 @@
+<?xml version="1.0" standalone="yes"?>
+
+<svg version="1.1" viewBox="0.0 0.0 960.0 540.0" fill="none" stroke="none" stroke-linecap="square" stroke-miterlimit="10" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink"><clipPath id="p5.0"><path d="m0 0l960.0 0l0 540.0l-960.0 0l0 -540.0z" clip-rule="nonzero"></path></clipPath><g clip-path="url(#p5.0)"><path fill="#ffffff" d="m0 0l960.0 0l0 540.0l-960.0 0z" fill-rule="nonzero"></path><path fill="#000000" fill-opacity="0.0" d="m320.1549 321.9537l0 -85.25983" fill-rule="nonzero"></path><path stroke="#4f81bd" stroke-width="3.0" stroke-linejoin="round" stroke-linecap="butt" d="m320.1549 321.9537l0 -67.25983" fill-rule="evenodd"></path><path fill="#4f81bd" stroke="#4f81bd" stroke-width="3.0" stroke-linecap="butt" d="m325.1101 254.69388l-4.9552 -13.614288l-4.9552 13.614288z" fill-rule="evenodd"></path><path fill="#000000" fill-opacity="0.0" d="m320.1549 168.43352l0 -85.25984" fill-rule="nonzero"></path><path stroke="#4f81bd" stroke-width="3.0" stroke-linejoin="round" stroke-linecap="butt" d="m320.1549 168.43352l0 -67.259834" fill-rule="evenodd"></path><path fill="#4f81bd" stroke="#4f81bd" stroke-width="3.0" stroke-linecap="butt" d="m325.1101 101.173676l-4.9552 -13.614288l-4.9552 13.614288z" fill-rule="evenodd"></path><defs><linearGradient id="p5.1" gradientUnits="userSpaceOnUse" gradientTransform="matrix(17.028923981523434 0.0 0.0 4.0061528558683355 175.16143937007877 168.43352047244096)" spreadMethod="pad" x1="17.028923981523434" y1="17.028923981523434" x2="17.028923981523434" y2="0.0"><stop offset="0.0" stop-color="#bedbff"></stop><stop offset="0.35" stop-color="#d1e5fe"></stop><stop offset="1.0" stop-color="#eef5ff"></stop></linearGradient></defs><path fill="url(#p5.1)" d="m175.16144 168.43352l289.98425 0l0 68.220474l-289.98425 0z" fill-rule="nonzero"></path><path stroke="#4a7dbb" stroke-width="1.0" stroke-linejoin="round" stroke-linecap="butt" d="m175.16144 168.43352l289.98425 0l0 68.220474l-289.98425 0z" fill-rule="nonzero"></path><path fill="#000000" d="m196.21802 206.83376q0 1.0625 -0.390625 1.890625q-0.390625 0.828125 -1.09375 1.421875q-0.6875 0.578125 -1.640625 0.875q-0.9375 0.28125 -2.03125 0.28125q-0.75 0 -1.40625 -0.125q-0.65625 -0.125 -1.171875 -0.3125q-0.5 -0.1875 -0.84375 -0.390625q-0.34375 -0.203125 -0.484375 -0.34375q-0.125 -0.140625 -0.203125 -0.359375q-0.0625 -0.21875 -0.0625 -0.578125q0 -0.25 0.015625 -0.421875q0.03125 -0.171875 0.078125 -0.28125q0.046875 -0.109375 0.109375 -0.140625q0.078125 -0.046875 0.171875 -0.046875q0.171875 0 0.46875 0.203125q0.296875 0.203125 0.765625 0.4375q0.46875 0.234375 1.125 0.4375q0.671875 0.203125 1.53125 0.203125q0.65625 0 1.203125 -0.171875q0.546875 -0.1875 0.9375 -0.5q0.390625 -0.328125 0.59375 -0.796875q0.21875 -0.46875 0.21875 -1.0625q0 -0.640625 -0.296875 -1.09375q-0.28125 -0.46875 -0.765625 -0.8125q-0.484375 -0.34375 -1.09375 -0.625q-0.609375 -0.296875 -1.265625 -0.59375q-0.640625 -0.296875 -1.25 -0.65625q-0.609375 -0.375 -1.09375 -0.859375q-0.46875 -0.5 -0.78125 -1.15625q-0.296875 -0.65625 -0.296875 -1.59375q0 -0.9375 0.34375 -1.6875q0.359375 -0.75 0.96875 -1.25q0.609375 -0.5 1.453125 -0.765625q0.859375 -0.265625 1.84375 -0.265625q0.5 0 1.015625 0.09375q0.515625 0.078125 0.953125 0.234375q0.453125 0.140625 0.796875 0.328125q0.359375 0.171875 0.46875 0.296875q0.125 0.109375 0.15625 0.171875q0.03125 0.0625 0.046875 0.171875q0.03125 0.09375 0.046875 0.234375q0.015625 0.140625 0.015625 0.359375q0 0.203125 -0.03125 0.375q-0.015625 0.15625 -0.046875 0.28125q-0.03125 0.109375 -0.09375 0.15625q-0.0625 0.046875 -0.15625 0.046875q-0.125 0 -0.40625 -0.15625q-0.265625 -0.171875 -0.671875 -0.375q-0.390625 -0.203125 -0.9375 -0.375q-0.546875 -0.171875 -1.21875 -0.171875q-0.640625 0 -1.109375 0.171875q-0.46875 0.171875 -0.78125 0.453125q-0.296875 0.28125 -0.453125 0.671875q-0.140625 0.390625 -0.140625 0.8125q0 0.640625 0.28125 1.09375q0.296875 0.453125 0.78125 0.8125q0.484375 0.34375 1.109375 0.640625q0.625 0.296875 1.265625 0.59375q0.640625 0.296875 1.265625 0.65625q0.625 0.359375 1.109375 0.84375q0.484375 0.484375 0.78125 1.15625q0.296875 0.65625 0.296875 1.5625zm11.667969 -1.78125q0 0.46875 -0.234375 0.65625q-0.21875 0.1875 -0.515625 0.1875l-6.921875 0q0 0.890625 0.171875 1.59375q0.1875 0.703125 0.59375 1.203125q0.40625 0.5 1.0625 0.78125q0.65625 0.265625 1.609375 0.265625q0.75 0 1.328125 -0.125q0.59375 -0.125 1.015625 -0.28125q0.4375 -0.15625 0.703125 -0.265625q0.28125 -0.125 0.421875 -0.125q0.078125 0 0.140625 0.046875q0.078125 0.03125 0.109375 0.109375q0.03125 0.078125 0.046875 0.234375q0.015625 0.140625 0.015625 0.359375q0 0.140625 -0.015625 0.265625q0 0.109375 -0.015625 0.203125q-0.015625 0.078125 -0.0625 0.15625q-0.046875 0.0625 -0.109375 0.125q-0.0625 0.0625 -0.375 0.21875q-0.3125 0.140625 -0.828125 0.28125q-0.5 0.140625 -1.171875 0.25q-0.65625 0.109375 -1.40625 0.109375q-1.296875 0 -2.28125 -0.359375q-0.96875 -0.359375 -1.640625 -1.078125q-0.671875 -0.71875 -1.015625 -1.796875q-0.328125 -1.078125 -0.328125 -2.5q0 -1.359375 0.34375 -2.4375q0.359375 -1.09375 1.015625 -1.84375q0.671875 -0.765625 1.609375 -1.171875q0.9375 -0.40625 2.09375 -0.40625q1.234375 0 2.109375 0.40625q0.875 0.390625 1.4375 1.078125q0.5625 0.671875 0.828125 1.578125q0.265625 0.90625 0.265625 1.9375l0 0.34375zm-1.953125 -0.5625q0.046875 -1.53125 -0.671875 -2.390625q-0.703125 -0.875 -2.09375 -0.875q-0.71875 0 -1.265625 0.28125q-0.53125 0.265625 -0.90625 0.71875q-0.359375 0.4375 -0.5625 1.03125q-0.1875 0.578125 -0.21875 1.234375l5.71875 0zm13.972656 6.296875q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.09375 0.046875 -0.28125 0.0625q-0.1875 0.03125 -0.46875 0.03125q-0.296875 0 -0.484375 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.046875 -0.0625 -0.046875 -0.15625l0 -6.171875q0 -0.90625 -0.140625 -1.453125q-0.140625 -0.546875 -0.40625 -0.9375q-0.265625 -0.40625 -0.703125 -0.609375q-0.421875 -0.21875 -0.984375 -0.21875q-0.71875 0 -1.453125 0.515625q-0.71875 0.515625 -1.515625 1.5l0 7.375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -10.546875q0 -0.09375 0.03125 -0.15625q0.03125 -0.0625 0.140625 -0.109375q0.109375 -0.0625 0.265625 -0.078125q0.171875 -0.015625 0.4375 -0.015625q0.265625 0 0.421875 0.015625q0.171875 0.015625 0.265625 0.078125q0.09375 0.046875 0.140625 0.109375q0.046875 0.0625 0.046875 0.15625l0 1.390625q0.890625 -0.984375 1.765625 -1.453125q0.890625 -0.46875 1.796875 -0.46875q1.046875 0 1.765625 0.359375q0.71875 0.359375 1.15625 0.96875q0.453125 0.59375 0.640625 1.390625q0.203125 0.796875 0.203125 1.921875l0 6.4375zm10.15625 -2.875q0 0.8125 -0.3125 1.453125q-0.296875 0.625 -0.84375 1.0625q-0.546875 0.4375 -1.3125 0.65625q-0.765625 0.21875 -1.671875 0.21875q-0.5625 0 -1.078125 -0.09375q-0.5 -0.078125 -0.90625 -0.203125q-0.40625 -0.140625 -0.6875 -0.28125q-0.28125 -0.15625 -0.421875 -0.265625q-0.125 -0.125 -0.1875 -0.328125q-0.046875 -0.21875 -0.046875 -0.578125q0 -0.234375 0.015625 -0.375q0.03125 -0.15625 0.0625 -0.25q0.03125 -0.09375 0.09375 -0.125q0.078125 -0.046875 0.15625 -0.046875q0.125 0 0.375 0.15625q0.25 0.15625 0.625 0.34375q0.375 0.1875 0.875 0.34375q0.5 0.15625 1.15625 0.15625q0.5 0 0.890625 -0.09375q0.40625 -0.109375 0.6875 -0.3125q0.296875 -0.21875 0.453125 -0.53125q0.15625 -0.3125 0.15625 -0.75q0 -0.4375 -0.234375 -0.734375q-0.21875 -0.3125 -0.59375 -0.546875q-0.375 -0.234375 -0.84375 -0.421875q-0.46875 -0.1875 -0.96875 -0.375q-0.5 -0.203125 -0.96875 -0.453125q-0.46875 -0.25 -0.84375 -0.609375q-0.375 -0.375 -0.609375 -0.875q-0.234375 -0.5 -0.234375 -1.203125q0 -0.625 0.234375 -1.1875q0.25 -0.578125 0.734375 -1.0q0.484375 -0.4375 1.203125 -0.6875q0.71875 -0.265625 1.671875 -0.265625q0.421875 0 0.84375 0.078125q0.421875 0.0625 0.765625 0.171875q0.34375 0.109375 0.578125 0.234375q0.25 0.125 0.359375 0.21875q0.125 0.09375 0.171875 0.171875q0.046875 0.0625 0.0625 0.15625q0.015625 0.078125 0.03125 0.203125q0.015625 0.125 0.015625 0.3125q0 0.203125 -0.015625 0.359375q-0.015625 0.140625 -0.0625 0.234375q-0.03125 0.09375 -0.09375 0.140625q-0.0625 0.03125 -0.125 0.03125q-0.109375 0 -0.3125 -0.125q-0.203125 -0.125 -0.515625 -0.265625q-0.3125 -0.15625 -0.75 -0.28125q-0.421875 -0.140625 -0.96875 -0.140625q-0.5 0 -0.875 0.125q-0.375 0.109375 -0.609375 0.3125q-0.234375 0.203125 -0.359375 0.484375q-0.125 0.28125 -0.125 0.609375q0 0.453125 0.234375 0.765625q0.234375 0.3125 0.609375 0.546875q0.375 0.234375 0.84375 0.421875q0.484375 0.1875 0.984375 0.390625q0.5 0.1875 0.984375 0.4375q0.484375 0.25 0.859375 0.609375q0.375 0.34375 0.609375 0.84375q0.234375 0.484375 0.234375 1.15625zm12.574219 -2.515625q0 1.296875 -0.34375 2.375q-0.34375 1.078125 -1.015625 1.875q-0.671875 0.78125 -1.6875 1.21875q-1.015625 0.4375 -2.34375 0.4375q-1.3125 0 -2.28125 -0.375q-0.953125 -0.390625 -1.609375 -1.125q-0.640625 -0.75 -0.953125 -1.796875q-0.3125 -1.0625 -0.3125 -2.390625q0 -1.296875 0.328125 -2.375q0.328125 -1.09375 1.0 -1.875q0.6875 -0.78125 1.6875 -1.21875q1.015625 -0.4375 2.359375 -0.4375q1.296875 0 2.265625 0.390625q0.96875 0.390625 1.609375 1.125q0.640625 0.734375 0.96875 1.796875q0.328125 1.046875 0.328125 2.375zm-2.046875 0.125q0 -0.84375 -0.15625 -1.609375q-0.15625 -0.765625 -0.53125 -1.328125q-0.359375 -0.578125 -0.984375 -0.90625q-0.609375 -0.34375 -1.53125 -0.34375q-0.859375 0 -1.484375 0.3125q-0.609375 0.296875 -1.015625 0.859375q-0.390625 0.546875 -0.59375 1.3125q-0.1875 0.765625 -0.1875 1.65625q0 0.875 0.15625 1.640625q0.171875 0.75 0.53125 1.328125q0.375 0.5625 0.984375 0.90625q0.625 0.328125 1.5625 0.328125q0.84375 0 1.453125 -0.296875q0.625 -0.3125 1.015625 -0.859375q0.40625 -0.5625 0.59375 -1.3125q0.1875 -0.765625 0.1875 -1.6875zm11.046875 -4.59375q0 0.265625 -0.015625 0.4375q0 0.171875 -0.046875 0.28125q-0.03125 0.09375 -0.078125 0.15625q-0.046875 0.046875 -0.140625 0.046875q-0.09375 0 -0.234375 -0.046875q-0.140625 -0.0625 -0.3125 -0.109375q-0.15625 -0.0625 -0.375 -0.109375q-0.203125 -0.046875 -0.453125 -0.046875q-0.296875 0 -0.578125 0.125q-0.28125 0.109375 -0.59375 0.390625q-0.3125 0.265625 -0.65625 0.71875q-0.328125 0.4375 -0.734375 1.078125l0 6.9375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -10.546875q0 -0.09375 0.03125 -0.15625q0.03125 -0.0625 0.140625 -0.109375q0.109375 -0.0625 0.265625 -0.078125q0.171875 -0.015625 0.4375 -0.015625q0.265625 0 0.421875 0.015625q0.171875 0.015625 0.265625 0.078125q0.09375 0.046875 0.140625 0.109375q0.046875 0.0625 0.046875 0.15625l0 1.53125q0.421875 -0.625 0.796875 -1.015625q0.390625 -0.40625 0.734375 -0.625q0.34375 -0.234375 0.671875 -0.328125q0.328125 -0.09375 0.671875 -0.09375q0.15625 0 0.34375 0.03125q0.203125 0.015625 0.40625 0.0625q0.21875 0.046875 0.375 0.109375q0.171875 0.046875 0.234375 0.109375q0.078125 0.0625 0.09375 0.109375q0.03125 0.046875 0.046875 0.140625q0.03125 0.078125 0.03125 0.234375q0 0.15625 0 0.421875zm6.9609375 4.234375q0 0.453125 -0.109375 0.640625q-0.109375 0.171875 -0.3125 0.171875l-4.890625 0q-0.21875 0 -0.328125 -0.171875q-0.09375 -0.1875 -0.09375 -0.640625q0 -0.4375 0.09375 -0.609375q0.109375 -0.1875 0.328125 -0.1875l4.890625 0q0.09375 0 0.171875 0.046875q0.078125 0.03125 0.125 0.125q0.0625 0.09375 0.09375 0.25q0.03125 0.15625 0.03125 0.375zm14.175781 5.203125q0.09375 0.265625 0.09375 0.421875q0.015625 0.15625 -0.078125 0.25q-0.09375 0.078125 -0.3125 0.09375q-0.21875 0.03125 -0.578125 0.03125q-0.375 0 -0.59375 -0.03125q-0.203125 -0.015625 -0.328125 -0.046875q-0.109375 -0.046875 -0.15625 -0.109375q-0.046875 -0.078125 -0.09375 -0.1875l-1.3125 -3.6875l-6.296875 0l-1.25 3.640625q-0.03125 0.109375 -0.09375 0.1875q-0.046875 0.078125 -0.171875 0.140625q-0.109375 0.046875 -0.3125 0.0625q-0.203125 0.03125 -0.53125 0.03125q-0.34375 0 -0.5625 -0.03125q-0.203125 -0.03125 -0.296875 -0.109375q-0.09375 -0.09375 -0.09375 -0.25q0.015625 -0.15625 0.109375 -0.421875l5.09375 -14.078125q0.046875 -0.125 0.109375 -0.203125q0.078125 -0.09375 0.21875 -0.140625q0.15625 -0.046875 0.375 -0.0625q0.234375 -0.015625 0.59375 -0.015625q0.375 0 0.609375 0.015625q0.25 0.015625 0.40625 0.0625q0.15625 0.046875 0.234375 0.140625q0.078125 0.078125 0.125 0.21875l5.09375 14.078125zm-6.53125 -12.4375l-0.015625 0l-2.609375 7.5625l5.28125 0l-2.65625 -7.5625zm16.417969 11.25q0 0.203125 -0.015625 0.359375q0 0.140625 -0.03125 0.25q-0.03125 0.09375 -0.078125 0.171875q-0.03125 0.0625 -0.1875 0.21875q-0.140625 0.140625 -0.5 0.359375q-0.34375 0.21875 -0.78125 0.390625q-0.4375 0.171875 -0.953125 0.265625q-0.515625 0.109375 -1.078125 0.109375q-1.125 0 -2.015625 -0.375q-0.875 -0.375 -1.46875 -1.09375q-0.59375 -0.71875 -0.90625 -1.765625q-0.296875 -1.046875 -0.296875 -2.421875q0 -1.5625 0.375 -2.671875q0.375 -1.125 1.03125 -1.84375q0.671875 -0.71875 1.5625 -1.0625q0.90625 -0.34375 1.953125 -0.34375q0.5 0 0.96875 0.09375q0.484375 0.09375 0.875 0.25q0.40625 0.15625 0.703125 0.359375q0.3125 0.1875 0.453125 0.328125q0.140625 0.140625 0.1875 0.234375q0.0625 0.078125 0.09375 0.1875q0.046875 0.109375 0.046875 0.25q0.015625 0.140625 0.015625 0.34375q0 0.46875 -0.109375 0.65625q-0.09375 0.171875 -0.25 0.171875q-0.171875 0 -0.40625 -0.1875q-0.234375 -0.203125 -0.59375 -0.4375q-0.34375 -0.234375 -0.84375 -0.421875q-0.484375 -0.203125 -1.171875 -0.203125q-1.390625 0 -2.140625 1.078125q-0.734375 1.078125 -0.734375 3.109375q0 1.015625 0.1875 1.796875q0.1875 0.765625 0.5625 1.28125q0.375 0.515625 0.921875 0.765625q0.546875 0.25 1.25 0.25q0.671875 0 1.171875 -0.203125q0.5 -0.21875 0.875 -0.46875q0.375 -0.25 0.625 -0.453125q0.25 -0.21875 0.390625 -0.21875q0.078125 0 0.140625 0.046875q0.0625 0.046875 0.09375 0.171875q0.046875 0.109375 0.0625 0.28125q0.015625 0.15625 0.015625 0.390625zm8.0546875 0.84375q0 0.328125 -0.046875 0.53125q-0.046875 0.203125 -0.140625 0.296875q-0.09375 0.09375 -0.28125 0.1875q-0.1875 0.078125 -0.4375 0.125q-0.234375 0.046875 -0.5 0.078125q-0.265625 0.046875 -0.546875 0.046875q-0.8125 0 -1.40625 -0.21875q-0.578125 -0.21875 -0.953125 -0.65625q-0.375 -0.4375 -0.546875 -1.109375q-0.171875 -0.6875 -0.171875 -1.59375l0 -6.171875l-1.46875 0q-0.1875 0 -0.296875 -0.1875q-0.09375 -0.1875 -0.09375 -0.609375q0 -0.21875 0.03125 -0.359375q0.03125 -0.15625 0.078125 -0.25q0.046875 -0.109375 0.109375 -0.140625q0.078125 -0.046875 0.171875 -0.046875l1.46875 0l0 -2.515625q0 -0.078125 0.03125 -0.140625q0.046875 -0.078125 0.15625 -0.125q0.125 -0.0625 0.3125 -0.078125q0.1875 -0.03125 0.46875 -0.03125q0.28125 0 0.46875 0.03125q0.1875 0.015625 0.296875 0.078125q0.109375 0.046875 0.15625 0.125q0.046875 0.0625 0.046875 0.140625l0 2.515625l2.703125 0q0.09375 0 0.15625 0.046875q0.078125 0.03125 0.125 0.140625q0.0625 0.09375 0.078125 0.25q0.03125 0.140625 0.03125 0.359375q0 0.421875 -0.109375 0.609375q-0.109375 0.1875 -0.28125 0.1875l-2.703125 0l0 5.890625q0 1.09375 0.3125 1.65625q0.328125 0.546875 1.15625 0.546875q0.28125 0 0.484375 -0.046875q0.21875 -0.0625 0.375 -0.109375q0.171875 -0.0625 0.28125 -0.109375q0.125 -0.0625 0.21875 -0.0625q0.046875 0 0.09375 0.03125q0.0625 0.03125 0.09375 0.109375q0.03125 0.078125 0.046875 0.21875q0.03125 0.140625 0.03125 0.359375zm12.3671875 -4.625q0 1.296875 -0.34375 2.375q-0.34375 1.078125 -1.015625 1.875q-0.671875 0.78125 -1.6875 1.21875q-1.015625 0.4375 -2.34375 0.4375q-1.3125 0 -2.28125 -0.375q-0.953125 -0.390625 -1.609375 -1.125q-0.640625 -0.75 -0.953125 -1.796875q-0.3125 -1.0625 -0.3125 -2.390625q0 -1.296875 0.328125 -2.375q0.328125 -1.09375 1.0 -1.875q0.6875 -0.78125 1.6875 -1.21875q1.015625 -0.4375 2.359375 -0.4375q1.296875 0 2.265625 0.390625q0.96875 0.390625 1.609375 1.125q0.640625 0.734375 0.96875 1.796875q0.328125 1.046875 0.328125 2.375zm-2.046875 0.125q0 -0.84375 -0.15625 -1.609375q-0.15625 -0.765625 -0.53125 -1.328125q-0.359375 -0.578125 -0.984375 -0.90625q-0.609375 -0.34375 -1.53125 -0.34375q-0.859375 0 -1.484375 0.3125q-0.609375 0.296875 -1.015625 0.859375q-0.390625 0.546875 -0.59375 1.3125q-0.1875 0.765625 -0.1875 1.65625q0 0.875 0.15625 1.640625q0.171875 0.75 0.53125 1.328125q0.375 0.5625 0.984375 0.90625q0.625 0.328125 1.5625 0.328125q0.84375 0 1.453125 -0.296875q0.625 -0.3125 1.015625 -0.859375q0.40625 -0.5625 0.59375 -1.3125q0.1875 -0.765625 0.1875 -1.6875zm11.046875 -4.59375q0 0.265625 -0.015625 0.4375q0 0.171875 -0.046875 0.28125q-0.03125 0.09375 -0.078125 0.15625q-0.046875 0.046875 -0.140625 0.046875q-0.09375 0 -0.234375 -0.046875q-0.140625 -0.0625 -0.3125 -0.109375q-0.15625 -0.0625 -0.375 -0.109375q-0.203125 -0.046875 -0.453125 -0.046875q-0.296875 0 -0.578125 0.125q-0.28125 0.109375 -0.59375 0.390625q-0.3125 0.265625 -0.65625 0.71875q-0.328125 0.4375 -0.734375 1.078125l0 6.9375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -10.546875q0 -0.09375 0.03125 -0.15625q0.03125 -0.0625 0.140625 -0.109375q0.109375 -0.0625 0.265625 -0.078125q0.171875 -0.015625 0.4375 -0.015625q0.265625 0 0.421875 0.015625q0.171875 0.015625 0.265625 0.078125q0.09375 0.046875 0.140625 0.109375q0.046875 0.0625 0.046875 0.15625l0 1.53125q0.421875 -0.625 0.796875 -1.015625q0.390625 -0.40625 0.734375 -0.625q0.34375 -0.234375 0.671875 -0.328125q0.328125 -0.09375 0.671875 -0.09375q0.15625 0 0.34375 0.03125q0.203125 0.015625 0.40625 0.0625q0.21875 0.046875 0.375 0.109375q0.171875 0.046875 0.234375 0.109375q0.078125 0.0625 0.09375 0.109375q0.03125 0.046875 0.046875 0.140625q0.03125 0.078125 0.03125 0.234375q0 0.15625 0 0.421875zm19.261719 4.546875q0 1.390625 -0.40625 2.484375q-0.40625 1.078125 -1.15625 1.828125q-0.75 0.75 -1.828125 1.140625q-1.078125 0.375 -2.453125 0.375q-1.25 0 -2.28125 -0.359375q-1.03125 -0.359375 -1.765625 -1.0625q-0.734375 -0.71875 -1.140625 -1.78125q-0.390625 -1.078125 -0.390625 -2.46875l0 -9.40625q0 -0.09375 0.046875 -0.15625q0.046875 -0.078125 0.15625 -0.109375q0.125 -0.046875 0.3125 -0.078125q0.1875 -0.03125 0.484375 -0.03125q0.28125 0 0.484375 0.03125q0.203125 0.03125 0.3125 0.078125q0.109375 0.03125 0.15625 0.109375q0.046875 0.0625 0.046875 0.15625l0 9.15625q0 1.0625 0.25 1.84375q0.265625 0.78125 0.75 1.3125q0.484375 0.515625 1.171875 0.78125q0.6875 0.265625 1.546875 0.265625q0.875 0 1.5625 -0.25q0.6875 -0.265625 1.15625 -0.78125q0.46875 -0.515625 0.71875 -1.28125q0.265625 -0.765625 0.265625 -1.78125l0 -9.265625q0 -0.09375 0.046875 -0.15625q0.046875 -0.078125 0.15625 -0.109375q0.125 -0.046875 0.3125 -0.078125q0.1875 -0.03125 0.484375 -0.03125q0.28125 0 0.46875 0.03125q0.203125 0.03125 0.3125 0.078125q0.109375 0.03125 0.15625 0.109375q0.0625 0.0625 0.0625 0.15625l0 9.25zm12.8515625 5.3125q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.09375 0.046875 -0.28125 0.0625q-0.1875 0.03125 -0.46875 0.03125q-0.296875 0 -0.484375 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.046875 -0.0625 -0.046875 -0.15625l0 -6.171875q0 -0.90625 -0.140625 -1.453125q-0.140625 -0.546875 -0.40625 -0.9375q-0.265625 -0.40625 -0.703125 -0.609375q-0.421875 -0.21875 -0.984375 -0.21875q-0.71875 0 -1.453125 0.515625q-0.71875 0.515625 -1.515625 1.5l0 7.375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -10.546875q0 -0.09375 0.03125 -0.15625q0.03125 -0.0625 0.140625 -0.109375q0.109375 -0.0625 0.265625 -0.078125q0.171875 -0.015625 0.4375 -0.015625q0.265625 0 0.421875 0.015625q0.171875 0.015625 0.265625 0.078125q0.09375 0.046875 0.140625 0.109375q0.046875 0.0625 0.046875 0.15625l0 1.390625q0.890625 -0.984375 1.765625 -1.453125q0.890625 -0.46875 1.796875 -0.46875q1.046875 0 1.765625 0.359375q0.71875 0.359375 1.15625 0.96875q0.453125 0.59375 0.640625 1.390625q0.203125 0.796875 0.203125 1.921875l0 6.4375zm5.46875 0q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -10.546875q0 -0.078125 0.03125 -0.140625q0.046875 -0.078125 0.15625 -0.125q0.109375 -0.046875 0.296875 -0.0625q0.1875 -0.03125 0.46875 -0.03125q0.296875 0 0.484375 0.03125q0.1875 0.015625 0.296875 0.0625q0.109375 0.046875 0.15625 0.125q0.046875 0.0625 0.046875 0.140625l0 10.546875zm0.21875 -14.109375q0 0.6875 -0.265625 0.9375q-0.25 0.234375 -0.9375 0.234375q-0.6875 0 -0.9375 -0.234375q-0.25 -0.25 -0.25 -0.90625q0 -0.6875 0.25 -0.921875q0.265625 -0.25 0.953125 -0.25q0.6875 0 0.9375 0.234375q0.25 0.234375 0.25 0.90625zm8.8359375 13.34375q0 0.328125 -0.046875 0.53125q-0.046875 0.203125 -0.140625 0.296875q-0.09375 0.09375 -0.28125 0.1875q-0.1875 0.078125 -0.4375 0.125q-0.234375 0.046875 -0.5 0.078125q-0.265625 0.046875 -0.546875 0.046875q-0.8125 0 -1.40625 -0.21875q-0.578125 -0.21875 -0.953125 -0.65625q-0.375 -0.4375 -0.546875 -1.109375q-0.171875 -0.6875 -0.171875 -1.59375l0 -6.171875l-1.46875 0q-0.1875 0 -0.296875 -0.1875q-0.09375 -0.1875 -0.09375 -0.609375q0 -0.21875 0.03125 -0.359375q0.03125 -0.15625 0.078125 -0.25q0.046875 -0.109375 0.109375 -0.140625q0.078125 -0.046875 0.171875 -0.046875l1.46875 0l0 -2.515625q0 -0.078125 0.03125 -0.140625q0.046875 -0.078125 0.15625 -0.125q0.125 -0.0625 0.3125 -0.078125q0.1875 -0.03125 0.46875 -0.03125q0.28125 0 0.46875 0.03125q0.1875 0.015625 0.296875 0.078125q0.109375 0.046875 0.15625 0.125q0.046875 0.0625 0.046875 0.140625l0 2.515625l2.703125 0q0.09375 0 0.15625 0.046875q0.078125 0.03125 0.125 0.140625q0.0625 0.09375 0.078125 0.25q0.03125 0.140625 0.03125 0.359375q0 0.421875 -0.109375 0.609375q-0.109375 0.1875 -0.28125 0.1875l-2.703125 0l0 5.890625q0 1.09375 0.3125 1.65625q0.328125 0.546875 1.15625 0.546875q0.28125 0 0.484375 -0.046875q0.21875 -0.0625 0.375 -0.109375q0.171875 -0.0625 0.28125 -0.109375q0.125 -0.0625 0.21875 -0.0625q0.046875 0 0.09375 0.03125q0.0625 0.03125 0.09375 0.109375q0.03125 0.078125 0.046875 0.21875q0.03125 0.140625 0.03125 0.359375zm20.902344 -6.703125q0 1.84375 -0.4375 3.328125q-0.421875 1.46875 -1.296875 2.515625q-0.859375 1.03125 -2.15625 1.59375q-1.296875 0.546875 -3.03125 0.546875q-1.71875 0 -2.96875 -0.5q-1.234375 -0.515625 -2.0625 -1.484375q-0.8125 -0.984375 -1.21875 -2.421875q-0.390625 -1.4375 -0.390625 -3.3125q0 -1.796875 0.4375 -3.25q0.4375 -1.46875 1.296875 -2.5q0.875 -1.03125 2.171875 -1.578125q1.296875 -0.5625 3.03125 -0.5625q1.6875 0 2.921875 0.515625q1.25 0.5 2.0625 1.46875q0.828125 0.953125 1.234375 2.390625q0.40625 1.421875 0.40625 3.25zm-2.125 0.140625q0 -1.28125 -0.234375 -2.390625q-0.21875 -1.109375 -0.75 -1.921875q-0.53125 -0.8125 -1.421875 -1.265625q-0.890625 -0.46875 -2.203125 -0.46875q-1.3125 0 -2.203125 0.5q-0.890625 0.484375 -1.453125 1.3125q-0.546875 0.8125 -0.796875 1.921875q-0.234375 1.09375 -0.234375 2.296875q0 1.328125 0.21875 2.453125q0.21875 1.125 0.75 1.953125q0.53125 0.8125 1.40625 1.265625q0.890625 0.4375 2.234375 0.4375q1.3125 0 2.21875 -0.484375q0.90625 -0.5 1.453125 -1.328125q0.546875 -0.84375 0.78125 -1.9375q0.234375 -1.109375 0.234375 -2.34375zm14.796875 1.921875q0 1.359375 -0.296875 2.46875q-0.296875 1.09375 -0.890625 1.875q-0.578125 0.765625 -1.421875 1.171875q-0.84375 0.40625 -1.921875 0.40625q-0.515625 0 -0.9375 -0.09375q-0.421875 -0.09375 -0.84375 -0.3125q-0.40625 -0.234375 -0.8125 -0.578125q-0.40625 -0.34375 -0.875 -0.8125l0 1.28125q0 0.09375 -0.046875 0.171875q-0.046875 0.0625 -0.15625 0.109375q-0.09375 0.046875 -0.25 0.0625q-0.15625 0.03125 -0.40625 0.03125q-0.234375 0 -0.40625 -0.03125q-0.15625 -0.015625 -0.265625 -0.0625q-0.109375 -0.046875 -0.140625 -0.109375q-0.03125 -0.078125 -0.03125 -0.171875l0 -15.65625q0 -0.09375 0.03125 -0.15625q0.046875 -0.078125 0.15625 -0.125q0.109375 -0.046875 0.296875 -0.0625q0.1875 -0.03125 0.46875 -0.03125q0.296875 0 0.484375 0.03125q0.1875 0.015625 0.296875 0.0625q0.109375 0.046875 0.15625 0.125q0.046875 0.0625 0.046875 0.15625l0 6.3125q0.46875 -0.46875 0.90625 -0.796875q0.4375 -0.328125 0.859375 -0.53125q0.421875 -0.21875 0.84375 -0.3125q0.421875 -0.09375 0.890625 -0.09375q1.140625 0 1.953125 0.46875q0.828125 0.453125 1.328125 1.21875q0.515625 0.765625 0.75 1.796875q0.234375 1.03125 0.234375 2.1875zm-2.046875 0.21875q0 -0.8125 -0.125 -1.5625q-0.109375 -0.765625 -0.421875 -1.34375q-0.296875 -0.59375 -0.8125 -0.953125q-0.5 -0.359375 -1.25 -0.359375q-0.375 0 -0.734375 0.109375q-0.359375 0.09375 -0.734375 0.34375q-0.375 0.25 -0.78125 0.640625q-0.40625 0.375 -0.859375 0.96875l0 4.203125q0.796875 0.96875 1.515625 1.484375q0.734375 0.515625 1.515625 0.515625q0.71875 0 1.234375 -0.34375q0.515625 -0.359375 0.84375 -0.9375q0.328125 -0.59375 0.46875 -1.3125q0.140625 -0.71875 0.140625 -1.453125zm11.578125 2.3125q0 0.8125 -0.3125 1.453125q-0.296875 0.625 -0.84375 1.0625q-0.546875 0.4375 -1.3125 0.65625q-0.765625 0.21875 -1.671875 0.21875q-0.5625 0 -1.078125 -0.09375q-0.5 -0.078125 -0.90625 -0.203125q-0.40625 -0.140625 -0.6875 -0.28125q-0.28125 -0.15625 -0.421875 -0.265625q-0.125 -0.125 -0.1875 -0.328125q-0.046875 -0.21875 -0.046875 -0.578125q0 -0.234375 0.015625 -0.375q0.03125 -0.15625 0.0625 -0.25q0.03125 -0.09375 0.09375 -0.125q0.078125 -0.046875 0.15625 -0.046875q0.125 0 0.375 0.15625q0.25 0.15625 0.625 0.34375q0.375 0.1875 0.875 0.34375q0.5 0.15625 1.15625 0.15625q0.5 0 0.890625 -0.09375q0.40625 -0.109375 0.6875 -0.3125q0.296875 -0.21875 0.453125 -0.53125q0.15625 -0.3125 0.15625 -0.75q0 -0.4375 -0.234375 -0.734375q-0.21875 -0.3125 -0.59375 -0.546875q-0.375 -0.234375 -0.84375 -0.421875q-0.46875 -0.1875 -0.96875 -0.375q-0.5 -0.203125 -0.96875 -0.453125q-0.46875 -0.25 -0.84375 -0.609375q-0.375 -0.375 -0.609375 -0.875q-0.234375 -0.5 -0.234375 -1.203125q0 -0.625 0.234375 -1.1875q0.25 -0.578125 0.734375 -1.0q0.484375 -0.4375 1.203125 -0.6875q0.71875 -0.265625 1.671875 -0.265625q0.421875 0 0.84375 0.078125q0.421875 0.0625 0.765625 0.171875q0.34375 0.109375 0.578125 0.234375q0.25 0.125 0.359375 0.21875q0.125 0.09375 0.171875 0.171875q0.046875 0.0625 0.0625 0.15625q0.015625 0.078125 0.03125 0.203125q0.015625 0.125 0.015625 0.3125q0 0.203125 -0.015625 0.359375q-0.015625 0.140625 -0.0625 0.234375q-0.03125 0.09375 -0.09375 0.140625q-0.0625 0.03125 -0.125 0.03125q-0.109375 0 -0.3125 -0.125q-0.203125 -0.125 -0.515625 -0.265625q-0.3125 -0.15625 -0.75 -0.28125q-0.421875 -0.140625 -0.96875 -0.140625q-0.5 0 -0.875 0.125q-0.375 0.109375 -0.609375 0.3125q-0.234375 0.203125 -0.359375 0.484375q-0.125 0.28125 -0.125 0.609375q0 0.453125 0.234375 0.765625q0.234375 0.3125 0.609375 0.546875q0.375 0.234375 0.84375 0.421875q0.484375 0.1875 0.984375 0.390625q0.5 0.1875 0.984375 0.4375q0.484375 0.25 0.859375 0.609375q0.375 0.34375 0.609375 0.84375q0.234375 0.484375 0.234375 1.15625zm11.761719 -2.859375q0 0.46875 -0.234375 0.65625q-0.21875 0.1875 -0.515625 0.1875l-6.921875 0q0 0.890625 0.171875 1.59375q0.1875 0.703125 0.59375 1.203125q0.40625 0.5 1.0625 0.78125q0.65625 0.265625 1.609375 0.265625q0.75 0 1.328125 -0.125q0.59375 -0.125 1.015625 -0.28125q0.4375 -0.15625 0.703125 -0.265625q0.28125 -0.125 0.421875 -0.125q0.078125 0 0.140625 0.046875q0.078125 0.03125 0.109375 0.109375q0.03125 0.078125 0.046875 0.234375q0.015625 0.140625 0.015625 0.359375q0 0.140625 -0.015625 0.265625q0 0.109375 -0.015625 0.203125q-0.015625 0.078125 -0.0625 0.15625q-0.046875 0.0625 -0.109375 0.125q-0.0625 0.0625 -0.375 0.21875q-0.3125 0.140625 -0.828125 0.28125q-0.5 0.140625 -1.171875 0.25q-0.65625 0.109375 -1.40625 0.109375q-1.296875 0 -2.28125 -0.359375q-0.96875 -0.359375 -1.640625 -1.078125q-0.671875 -0.71875 -1.015625 -1.796875q-0.328125 -1.078125 -0.328125 -2.5q0 -1.359375 0.34375 -2.4375q0.359375 -1.09375 1.015625 -1.84375q0.671875 -0.765625 1.609375 -1.171875q0.9375 -0.40625 2.09375 -0.40625q1.234375 0 2.109375 0.40625q0.875 0.390625 1.4375 1.078125q0.5625 0.671875 0.828125 1.578125q0.265625 0.90625 0.265625 1.9375l0 0.34375zm-1.953125 -0.5625q0.046875 -1.53125 -0.671875 -2.390625q-0.703125 -0.875 -2.09375 -0.875q-0.71875 0 -1.265625 0.28125q-0.53125 0.265625 -0.90625 0.71875q-0.359375 0.4375 -0.5625 1.03125q-0.1875 0.578125 -0.21875 1.234375l5.71875 0zm11.050781 -3.5625q0 0.265625 -0.015625 0.4375q0 0.171875 -0.046875 0.28125q-0.03125 0.09375 -0.078125 0.15625q-0.046875 0.046875 -0.140625 0.046875q-0.09375 0 -0.234375 -0.046875q-0.140625 -0.0625 -0.3125 -0.109375q-0.15625 -0.0625 -0.375 -0.109375q-0.203125 -0.046875 -0.453125 -0.046875q-0.296875 0 -0.578125 0.125q-0.28125 0.109375 -0.59375 0.390625q-0.3125 0.265625 -0.65625 0.71875q-0.328125 0.4375 -0.734375 1.078125l0 6.9375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -10.546875q0 -0.09375 0.03125 -0.15625q0.03125 -0.0625 0.140625 -0.109375q0.109375 -0.0625 0.265625 -0.078125q0.171875 -0.015625 0.4375 -0.015625q0.265625 0 0.421875 0.015625q0.171875 0.015625 0.265625 0.078125q0.09375 0.046875 0.140625 0.109375q0.046875 0.0625 0.046875 0.15625l0 1.53125q0.421875 -0.625 0.796875 -1.015625q0.390625 -0.40625 0.734375 -0.625q0.34375 -0.234375 0.671875 -0.328125q0.328125 -0.09375 0.671875 -0.09375q0.15625 0 0.34375 0.03125q0.203125 0.015625 0.40625 0.0625q0.21875 0.046875 0.375 0.109375q0.171875 0.046875 0.234375 0.109375q0.078125 0.0625 0.09375 0.109375q0.03125 0.046875 0.046875 0.140625q0.03125 0.078125 0.03125 0.234375q0 0.15625 0 0.421875zm10.8515625 -0.703125q0 0.046875 0 0.09375q0 0.046875 -0.015625 0.109375q-0.015625 0.0625 -0.03125 0.140625q-0.015625 0.0625 -0.046875 0.140625l-3.59375 10.015625q-0.046875 0.140625 -0.125 0.21875q-0.078125 0.078125 -0.234375 0.125q-0.140625 0.046875 -0.375 0.0625q-0.234375 0.03125 -0.59375 0.03125q-0.34375 0 -0.578125 -0.03125q-0.234375 -0.015625 -0.390625 -0.0625q-0.140625 -0.0625 -0.21875 -0.140625q-0.078125 -0.078125 -0.125 -0.203125l-3.59375 -10.015625q-0.046875 -0.140625 -0.078125 -0.234375q-0.03125 -0.109375 -0.03125 -0.15625q0 -0.0625 0 -0.09375q0 -0.09375 0.046875 -0.15625q0.046875 -0.078125 0.15625 -0.125q0.109375 -0.046875 0.28125 -0.046875q0.1875 -0.015625 0.453125 -0.015625q0.34375 0 0.546875 0.015625q0.203125 0.015625 0.3125 0.0625q0.125 0.046875 0.171875 0.125q0.046875 0.0625 0.09375 0.171875l2.984375 8.6875l0.046875 0.140625l0.03125 -0.140625l2.9375 -8.6875q0.03125 -0.109375 0.078125 -0.171875q0.0625 -0.078125 0.171875 -0.125q0.125 -0.046875 0.3125 -0.0625q0.1875 -0.015625 0.515625 -0.015625q0.265625 0 0.4375 0.015625q0.171875 0 0.265625 0.046875q0.109375 0.046875 0.140625 0.125q0.046875 0.0625 0.046875 0.15625zm11.199219 4.828125q0 0.46875 -0.234375 0.65625q-0.21875 0.1875 -0.515625 0.1875l-6.921875 0q0 0.890625 0.171875 1.59375q0.1875 0.703125 0.59375 1.203125q0.40625 0.5 1.0625 0.78125q0.65625 0.265625 1.609375 0.265625q0.75 0 1.328125 -0.125q0.59375 -0.125 1.015625 -0.28125q0.4375 -0.15625 0.703125 -0.265625q0.28125 -0.125 0.421875 -0.125q0.078125 0 0.140625 0.046875q0.078125 0.03125 0.109375 0.109375q0.03125 0.078125 0.046875 0.234375q0.015625 0.140625 0.015625 0.359375q0 0.140625 -0.015625 0.265625q0 0.109375 -0.015625 0.203125q-0.015625 0.078125 -0.0625 0.15625q-0.046875 0.0625 -0.109375 0.125q-0.0625 0.0625 -0.375 0.21875q-0.3125 0.140625 -0.828125 0.28125q-0.5 0.140625 -1.171875 0.25q-0.65625 0.109375 -1.40625 0.109375q-1.296875 0 -2.28125 -0.359375q-0.96875 -0.359375 -1.640625 -1.078125q-0.671875 -0.71875 -1.015625 -1.796875q-0.328125 -1.078125 -0.328125 -2.5q0 -1.359375 0.34375 -2.4375q0.359375 -1.09375 1.015625 -1.84375q0.671875 -0.765625 1.609375 -1.171875q0.9375 -0.40625 2.09375 -0.40625q1.234375 0 2.109375 0.40625q0.875 0.390625 1.4375 1.078125q0.5625 0.671875 0.828125 1.578125q0.265625 0.90625 0.265625 1.9375l0 0.34375zm-1.953125 -0.5625q0.046875 -1.53125 -0.671875 -2.390625q-0.703125 -0.875 -2.09375 -0.875q-0.71875 0 -1.265625 0.28125q-0.53125 0.265625 -0.90625 0.71875q-0.359375 0.4375 -0.5625 1.03125q-0.1875 0.578125 -0.21875 1.234375l5.71875 0zm11.050781 -3.5625q0 0.265625 -0.015625 0.4375q0 0.171875 -0.046875 0.28125q-0.03125 0.09375 -0.078125 0.15625q-0.046875 0.046875 -0.140625 0.046875q-0.09375 0 -0.234375 -0.046875q-0.140625 -0.0625 -0.3125 -0.109375q-0.15625 -0.0625 -0.375 -0.109375q-0.203125 -0.046875 -0.453125 -0.046875q-0.296875 0 -0.578125 0.125q-0.28125 0.109375 -0.59375 0.390625q-0.3125 0.265625 -0.65625 0.71875q-0.328125 0.4375 -0.734375 1.078125l0 6.9375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -10.546875q0 -0.09375 0.03125 -0.15625q0.03125 -0.0625 0.140625 -0.109375q0.109375 -0.0625 0.265625 -0.078125q0.171875 -0.015625 0.4375 -0.015625q0.265625 0 0.421875 0.015625q0.171875 0.015625 0.265625 0.078125q0.09375 0.046875 0.140625 0.109375q0.046875 0.0625 0.046875 0.15625l0 1.53125q0.421875 -0.625 0.796875 -1.015625q0.390625 -0.40625 0.734375 -0.625q0.34375 -0.234375 0.671875 -0.328125q0.328125 -0.09375 0.671875 -0.09375q0.15625 0 0.34375 0.03125q0.203125 0.015625 0.40625 0.0625q0.21875 0.046875 0.375 0.109375q0.171875 0.046875 0.234375 0.109375q0.078125 0.0625 0.09375 0.109375q0.03125 0.046875 0.046875 0.140625q0.03125 0.078125 0.03125 0.234375q0 0.15625 0 0.421875z" fill-rule="nonzero"></path><defs><linearGradient id="p5.2" gradientUnits="userSpaceOnUse" gradientTransform="matrix(25.952106099960787 0.0 0.0 2.628706594300181 25.490862204724408 321.95371706036747)" spreadMethod="pad" x1="25.95210609996079" y1="25.95210609996079" x2="25.95210609996079" y2="0.0"><stop offset="0.0" stop-color="#bedbff"></stop><stop offset="0.35" stop-color="#d1e5fe"></stop><stop offset="1.0" stop-color="#eef5ff"></stop></linearGradient></defs><path fill="url(#p5.2)" d="m25.490862 321.9537l673.51184 0l0 68.22049l-673.51184 0z" fill-rule="nonzero"></path><path stroke="#4a7dbb" stroke-width="1.0" stroke-linejoin="round" stroke-linecap="butt" d="m25.490862 321.9537l673.51184 0l0 68.22049l-673.51184 0z" fill-rule="nonzero"></path><path fill="#000000" d="m285.696 360.35394q0 1.0625 -0.390625 1.890625q-0.390625 0.828125 -1.09375 1.421875q-0.6875 0.578125 -1.640625 0.875q-0.9375 0.28125 -2.03125 0.28125q-0.75 0 -1.40625 -0.125q-0.65625 -0.125 -1.171875 -0.3125q-0.5 -0.1875 -0.84375 -0.390625q-0.34375 -0.203125 -0.484375 -0.34375q-0.125 -0.140625 -0.203125 -0.359375q-0.0625 -0.21875 -0.0625 -0.578125q0 -0.25 0.015625 -0.421875q0.03125 -0.171875 0.078125 -0.28125q0.046875 -0.109375 0.109375 -0.140625q0.078125 -0.046875 0.171875 -0.046875q0.171875 0 0.46875 0.203125q0.296875 0.203125 0.765625 0.4375q0.46875 0.234375 1.125 0.4375q0.671875 0.203125 1.53125 0.203125q0.65625 0 1.203125 -0.171875q0.546875 -0.1875 0.9375 -0.5q0.390625 -0.328125 0.59375 -0.796875q0.21875 -0.46875 0.21875 -1.0625q0 -0.640625 -0.296875 -1.09375q-0.28125 -0.46875 -0.765625 -0.8125q-0.484375 -0.34375 -1.09375 -0.625q-0.609375 -0.296875 -1.265625 -0.59375q-0.640625 -0.296875 -1.25 -0.65625q-0.609375 -0.375 -1.09375 -0.859375q-0.46875 -0.5 -0.78125 -1.15625q-0.296875 -0.65625 -0.296875 -1.59375q0 -0.9375 0.34375 -1.6875q0.359375 -0.75 0.96875 -1.25q0.609375 -0.5 1.453125 -0.765625q0.859375 -0.265625 1.84375 -0.265625q0.5 0 1.015625 0.09375q0.515625 0.078125 0.953125 0.234375q0.453125 0.140625 0.796875 0.328125q0.359375 0.171875 0.46875 0.296875q0.125 0.109375 0.15625 0.171875q0.03125 0.0625 0.046875 0.171875q0.03125 0.09375 0.046875 0.234375q0.015625 0.140625 0.015625 0.359375q0 0.203125 -0.03125 0.375q-0.015625 0.15625 -0.046875 0.28125q-0.03125 0.109375 -0.09375 0.15625q-0.0625 0.046875 -0.15625 0.046875q-0.125 0 -0.40625 -0.15625q-0.265625 -0.171875 -0.671875 -0.375q-0.390625 -0.203125 -0.9375 -0.375q-0.546875 -0.171875 -1.21875 -0.171875q-0.640625 0 -1.109375 0.171875q-0.46875 0.171875 -0.78125 0.453125q-0.296875 0.28125 -0.453125 0.671875q-0.140625 0.390625 -0.140625 0.8125q0 0.640625 0.28125 1.09375q0.296875 0.453125 0.78125 0.8125q0.484375 0.34375 1.109375 0.640625q0.625 0.296875 1.265625 0.59375q0.640625 0.296875 1.265625 0.65625q0.625 0.359375 1.109375 0.84375q0.484375 0.484375 0.78125 1.15625q0.296875 0.65625 0.296875 1.5625zm11.667969 -1.78125q0 0.46875 -0.234375 0.65625q-0.21875 0.1875 -0.515625 0.1875l-6.921875 0q0 0.890625 0.171875 1.59375q0.1875 0.703125 0.59375 1.203125q0.40625 0.5 1.0625 0.78125q0.65625 0.265625 1.609375 0.265625q0.75 0 1.328125 -0.125q0.59375 -0.125 1.015625 -0.28125q0.4375 -0.15625 0.703125 -0.265625q0.28125 -0.125 0.421875 -0.125q0.078125 0 0.140625 0.046875q0.078125 0.03125 0.109375 0.109375q0.03125 0.078125 0.046875 0.234375q0.015625 0.140625 0.015625 0.359375q0 0.140625 -0.015625 0.265625q0 0.109375 -0.015625 0.203125q-0.015625 0.078125 -0.0625 0.15625q-0.046875 0.0625 -0.109375 0.125q-0.0625 0.0625 -0.375 0.21875q-0.3125 0.140625 -0.828125 0.28125q-0.5 0.140625 -1.171875 0.25q-0.65625 0.109375 -1.40625 0.109375q-1.296875 0 -2.28125 -0.359375q-0.96875 -0.359375 -1.640625 -1.078125q-0.671875 -0.71875 -1.015625 -1.796875q-0.328125 -1.078125 -0.328125 -2.5q0 -1.359375 0.34375 -2.4375q0.359375 -1.09375 1.015625 -1.84375q0.671875 -0.765625 1.609375 -1.171875q0.9375 -0.40625 2.09375 -0.40625q1.234375 0 2.109375 0.40625q0.875 0.390625 1.4375 1.078125q0.5625 0.671875 0.828125 1.578125q0.265625 0.90625 0.265625 1.9375l0 0.34375zm-1.953125 -0.5625q0.046875 -1.53125 -0.671875 -2.390625q-0.703125 -0.875 -2.09375 -0.875q-0.71875 0 -1.265625 0.28125q-0.53125 0.265625 -0.90625 0.71875q-0.359375 0.4375 -0.5625 1.03125q-0.1875 0.578125 -0.21875 1.234375l5.71875 0zm13.972656 6.296875q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.09375 0.046875 -0.28125 0.0625q-0.1875 0.03125 -0.46875 0.03125q-0.296875 0 -0.484375 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.046875 -0.0625 -0.046875 -0.15625l0 -6.171875q0 -0.90625 -0.140625 -1.453125q-0.140625 -0.546875 -0.40625 -0.9375q-0.265625 -0.40625 -0.703125 -0.609375q-0.421875 -0.21875 -0.984375 -0.21875q-0.71875 0 -1.453125 0.515625q-0.71875 0.515625 -1.515625 1.5l0 7.375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -10.546875q0 -0.09375 0.03125 -0.15625q0.03125 -0.0625 0.140625 -0.109375q0.109375 -0.0625 0.265625 -0.078125q0.171875 -0.015625 0.4375 -0.015625q0.265625 0 0.421875 0.015625q0.171875 0.015625 0.265625 0.078125q0.09375 0.046875 0.140625 0.109375q0.046875 0.0625 0.046875 0.15625l0 1.390625q0.890625 -0.984375 1.765625 -1.453125q0.890625 -0.46875 1.796875 -0.46875q1.046875 0 1.765625 0.359375q0.71875 0.359375 1.15625 0.96875q0.453125 0.59375 0.640625 1.390625q0.203125 0.796875 0.203125 1.921875l0 6.4375zm10.15625 -2.875q0 0.8125 -0.3125 1.453125q-0.296875 0.625 -0.84375 1.0625q-0.546875 0.4375 -1.3125 0.65625q-0.765625 0.21875 -1.671875 0.21875q-0.5625 0 -1.078125 -0.09375q-0.5 -0.078125 -0.90625 -0.203125q-0.40625 -0.140625 -0.6875 -0.28125q-0.28125 -0.15625 -0.421875 -0.265625q-0.125 -0.125 -0.1875 -0.328125q-0.046875 -0.21875 -0.046875 -0.578125q0 -0.234375 0.015625 -0.375q0.03125 -0.15625 0.0625 -0.25q0.03125 -0.09375 0.09375 -0.125q0.078125 -0.046875 0.15625 -0.046875q0.125 0 0.375 0.15625q0.25 0.15625 0.625 0.34375q0.375 0.1875 0.875 0.34375q0.5 0.15625 1.15625 0.15625q0.5 0 0.890625 -0.09375q0.40625 -0.109375 0.6875 -0.3125q0.296875 -0.21875 0.453125 -0.53125q0.15625 -0.3125 0.15625 -0.75q0 -0.4375 -0.234375 -0.734375q-0.21875 -0.3125 -0.59375 -0.546875q-0.375 -0.234375 -0.84375 -0.421875q-0.46875 -0.1875 -0.96875 -0.375q-0.5 -0.203125 -0.96875 -0.453125q-0.46875 -0.25 -0.84375 -0.609375q-0.375 -0.375 -0.609375 -0.875q-0.234375 -0.5 -0.234375 -1.203125q0 -0.625 0.234375 -1.1875q0.25 -0.578125 0.734375 -1.0q0.484375 -0.4375 1.203125 -0.6875q0.71875 -0.265625 1.671875 -0.265625q0.421875 0 0.84375 0.078125q0.421875 0.0625 0.765625 0.171875q0.34375 0.109375 0.578125 0.234375q0.25 0.125 0.359375 0.21875q0.125 0.09375 0.171875 0.171875q0.046875 0.0625 0.0625 0.15625q0.015625 0.078125 0.03125 0.203125q0.015625 0.125 0.015625 0.3125q0 0.203125 -0.015625 0.359375q-0.015625 0.140625 -0.0625 0.234375q-0.03125 0.09375 -0.09375 0.140625q-0.0625 0.03125 -0.125 0.03125q-0.109375 0 -0.3125 -0.125q-0.203125 -0.125 -0.515625 -0.265625q-0.3125 -0.15625 -0.75 -0.28125q-0.421875 -0.140625 -0.96875 -0.140625q-0.5 0 -0.875 0.125q-0.375 0.109375 -0.609375 0.3125q-0.234375 0.203125 -0.359375 0.484375q-0.125 0.28125 -0.125 0.609375q0 0.453125 0.234375 0.765625q0.234375 0.3125 0.609375 0.546875q0.375 0.234375 0.84375 0.421875q0.484375 0.1875 0.984375 0.390625q0.5 0.1875 0.984375 0.4375q0.484375 0.25 0.859375 0.609375q0.375 0.34375 0.609375 0.84375q0.234375 0.484375 0.234375 1.15625zm12.574219 -2.515625q0 1.296875 -0.34375 2.375q-0.34375 1.078125 -1.015625 1.875q-0.671875 0.78125 -1.6875 1.21875q-1.015625 0.4375 -2.34375 0.4375q-1.3125 0 -2.28125 -0.375q-0.953125 -0.390625 -1.609375 -1.125q-0.640625 -0.75 -0.953125 -1.796875q-0.3125 -1.0625 -0.3125 -2.390625q0 -1.296875 0.328125 -2.375q0.328125 -1.09375 1.0 -1.875q0.6875 -0.78125 1.6875 -1.21875q1.015625 -0.4375 2.359375 -0.4375q1.296875 0 2.265625 0.390625q0.96875 0.390625 1.609375 1.125q0.640625 0.734375 0.96875 1.796875q0.328125 1.046875 0.328125 2.375zm-2.046875 0.125q0 -0.84375 -0.15625 -1.609375q-0.15625 -0.765625 -0.53125 -1.328125q-0.359375 -0.578125 -0.984375 -0.90625q-0.609375 -0.34375 -1.53125 -0.34375q-0.859375 0 -1.484375 0.3125q-0.609375 0.296875 -1.015625 0.859375q-0.390625 0.546875 -0.59375 1.3125q-0.1875 0.765625 -0.1875 1.65625q0 0.875 0.15625 1.640625q0.171875 0.75 0.53125 1.328125q0.375 0.5625 0.984375 0.90625q0.625 0.328125 1.5625 0.328125q0.84375 0 1.453125 -0.296875q0.625 -0.3125 1.015625 -0.859375q0.40625 -0.5625 0.59375 -1.3125q0.1875 -0.765625 0.1875 -1.6875zm11.046875 -4.59375q0 0.265625 -0.015625 0.4375q0 0.171875 -0.046875 0.28125q-0.03125 0.09375 -0.078125 0.15625q-0.046875 0.046875 -0.140625 0.046875q-0.09375 0 -0.234375 -0.046875q-0.140625 -0.0625 -0.3125 -0.109375q-0.15625 -0.0625 -0.375 -0.109375q-0.203125 -0.046875 -0.453125 -0.046875q-0.296875 0 -0.578125 0.125q-0.28125 0.109375 -0.59375 0.390625q-0.3125 0.265625 -0.65625 0.71875q-0.328125 0.4375 -0.734375 1.078125l0 6.9375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -10.546875q0 -0.09375 0.03125 -0.15625q0.03125 -0.0625 0.140625 -0.109375q0.109375 -0.0625 0.265625 -0.078125q0.171875 -0.015625 0.4375 -0.015625q0.265625 0 0.421875 0.015625q0.171875 0.015625 0.265625 0.078125q0.09375 0.046875 0.140625 0.109375q0.046875 0.0625 0.046875 0.15625l0 1.53125q0.421875 -0.625 0.796875 -1.015625q0.390625 -0.40625 0.734375 -0.625q0.34375 -0.234375 0.671875 -0.328125q0.328125 -0.09375 0.671875 -0.09375q0.15625 0 0.34375 0.03125q0.203125 0.015625 0.40625 0.0625q0.21875 0.046875 0.375 0.109375q0.171875 0.046875 0.234375 0.109375q0.078125 0.0625 0.09375 0.109375q0.03125 0.046875 0.046875 0.140625q0.03125 0.078125 0.03125 0.234375q0 0.15625 0 0.421875zm6.9609375 4.234375q0 0.453125 -0.109375 0.640625q-0.109375 0.171875 -0.3125 0.171875l-4.890625 0q-0.21875 0 -0.328125 -0.171875q-0.09375 -0.1875 -0.09375 -0.640625q0 -0.4375 0.09375 -0.609375q0.109375 -0.1875 0.328125 -0.1875l4.890625 0q0.09375 0 0.171875 0.046875q0.078125 0.03125 0.125 0.125q0.0625 0.09375 0.09375 0.25q0.03125 0.15625 0.03125 0.375zm14.175781 5.203125q0.09375 0.265625 0.09375 0.421875q0.015625 0.15625 -0.078125 0.25q-0.09375 0.078125 -0.3125 0.09375q-0.21875 0.03125 -0.578125 0.03125q-0.375 0 -0.59375 -0.03125q-0.203125 -0.015625 -0.328125 -0.046875q-0.109375 -0.046875 -0.15625 -0.109375q-0.046875 -0.078125 -0.09375 -0.1875l-1.3125 -3.6875l-6.296875 0l-1.25 3.640625q-0.03125 0.109375 -0.09375 0.1875q-0.046875 0.078125 -0.171875 0.140625q-0.109375 0.046875 -0.3125 0.0625q-0.203125 0.03125 -0.53125 0.03125q-0.34375 0 -0.5625 -0.03125q-0.203125 -0.03125 -0.296875 -0.109375q-0.09375 -0.09375 -0.09375 -0.25q0.015625 -0.15625 0.109375 -0.421875l5.09375 -14.078125q0.046875 -0.125 0.109375 -0.203125q0.078125 -0.09375 0.21875 -0.140625q0.15625 -0.046875 0.375 -0.0625q0.234375 -0.015625 0.59375 -0.015625q0.375 0 0.609375 0.015625q0.25 0.015625 0.40625 0.0625q0.15625 0.046875 0.234375 0.140625q0.078125 0.078125 0.125 0.21875l5.09375 14.078125zm-6.53125 -12.4375l-0.015625 0l-2.609375 7.5625l5.28125 0l-2.65625 -7.5625zm16.417969 11.25q0 0.203125 -0.015625 0.359375q0 0.140625 -0.03125 0.25q-0.03125 0.09375 -0.078125 0.171875q-0.03125 0.0625 -0.1875 0.21875q-0.140625 0.140625 -0.5 0.359375q-0.34375 0.21875 -0.78125 0.390625q-0.4375 0.171875 -0.953125 0.265625q-0.515625 0.109375 -1.078125 0.109375q-1.125 0 -2.015625 -0.375q-0.875 -0.375 -1.46875 -1.09375q-0.59375 -0.71875 -0.90625 -1.765625q-0.296875 -1.046875 -0.296875 -2.421875q0 -1.5625 0.375 -2.671875q0.375 -1.125 1.03125 -1.84375q0.671875 -0.71875 1.5625 -1.0625q0.90625 -0.34375 1.953125 -0.34375q0.5 0 0.96875 0.09375q0.484375 0.09375 0.875 0.25q0.40625 0.15625 0.703125 0.359375q0.3125 0.1875 0.453125 0.328125q0.140625 0.140625 0.1875 0.234375q0.0625 0.078125 0.09375 0.1875q0.046875 0.109375 0.046875 0.25q0.015625 0.140625 0.015625 0.34375q0 0.46875 -0.109375 0.65625q-0.09375 0.171875 -0.25 0.171875q-0.171875 0 -0.40625 -0.1875q-0.234375 -0.203125 -0.59375 -0.4375q-0.34375 -0.234375 -0.84375 -0.421875q-0.484375 -0.203125 -1.171875 -0.203125q-1.390625 0 -2.140625 1.078125q-0.734375 1.078125 -0.734375 3.109375q0 1.015625 0.1875 1.796875q0.1875 0.765625 0.5625 1.28125q0.375 0.515625 0.921875 0.765625q0.546875 0.25 1.25 0.25q0.671875 0 1.171875 -0.203125q0.5 -0.21875 0.875 -0.46875q0.375 -0.25 0.625 -0.453125q0.25 -0.21875 0.390625 -0.21875q0.078125 0 0.140625 0.046875q0.0625 0.046875 0.09375 0.171875q0.046875 0.109375 0.0625 0.28125q0.015625 0.15625 0.015625 0.390625zm8.0546875 0.84375q0 0.328125 -0.046875 0.53125q-0.046875 0.203125 -0.140625 0.296875q-0.09375 0.09375 -0.28125 0.1875q-0.1875 0.078125 -0.4375 0.125q-0.234375 0.046875 -0.5 0.078125q-0.265625 0.046875 -0.546875 0.046875q-0.8125 0 -1.40625 -0.21875q-0.578125 -0.21875 -0.953125 -0.65625q-0.375 -0.4375 -0.546875 -1.109375q-0.171875 -0.6875 -0.171875 -1.59375l0 -6.171875l-1.46875 0q-0.1875 0 -0.296875 -0.1875q-0.09375 -0.1875 -0.09375 -0.609375q0 -0.21875 0.03125 -0.359375q0.03125 -0.15625 0.078125 -0.25q0.046875 -0.109375 0.109375 -0.140625q0.078125 -0.046875 0.171875 -0.046875l1.46875 0l0 -2.515625q0 -0.078125 0.03125 -0.140625q0.046875 -0.078125 0.15625 -0.125q0.125 -0.0625 0.3125 -0.078125q0.1875 -0.03125 0.46875 -0.03125q0.28125 0 0.46875 0.03125q0.1875 0.015625 0.296875 0.078125q0.109375 0.046875 0.15625 0.125q0.046875 0.0625 0.046875 0.140625l0 2.515625l2.703125 0q0.09375 0 0.15625 0.046875q0.078125 0.03125 0.125 0.140625q0.0625 0.09375 0.078125 0.25q0.03125 0.140625 0.03125 0.359375q0 0.421875 -0.109375 0.609375q-0.109375 0.1875 -0.28125 0.1875l-2.703125 0l0 5.890625q0 1.09375 0.3125 1.65625q0.328125 0.546875 1.15625 0.546875q0.28125 0 0.484375 -0.046875q0.21875 -0.0625 0.375 -0.109375q0.171875 -0.0625 0.28125 -0.109375q0.125 -0.0625 0.21875 -0.0625q0.046875 0 0.09375 0.03125q0.0625 0.03125 0.09375 0.109375q0.03125 0.078125 0.046875 0.21875q0.03125 0.140625 0.03125 0.359375zm12.3671875 -4.625q0 1.296875 -0.34375 2.375q-0.34375 1.078125 -1.015625 1.875q-0.671875 0.78125 -1.6875 1.21875q-1.015625 0.4375 -2.34375 0.4375q-1.3125 0 -2.28125 -0.375q-0.953125 -0.390625 -1.609375 -1.125q-0.640625 -0.75 -0.953125 -1.796875q-0.3125 -1.0625 -0.3125 -2.390625q0 -1.296875 0.328125 -2.375q0.328125 -1.09375 1.0 -1.875q0.6875 -0.78125 1.6875 -1.21875q1.015625 -0.4375 2.359375 -0.4375q1.296875 0 2.265625 0.390625q0.96875 0.390625 1.609375 1.125q0.640625 0.734375 0.96875 1.796875q0.328125 1.046875 0.328125 2.375zm-2.046875 0.125q0 -0.84375 -0.15625 -1.609375q-0.15625 -0.765625 -0.53125 -1.328125q-0.359375 -0.578125 -0.984375 -0.90625q-0.609375 -0.34375 -1.53125 -0.34375q-0.859375 0 -1.484375 0.3125q-0.609375 0.296875 -1.015625 0.859375q-0.390625 0.546875 -0.59375 1.3125q-0.1875 0.765625 -0.1875 1.65625q0 0.875 0.15625 1.640625q0.171875 0.75 0.53125 1.328125q0.375 0.5625 0.984375 0.90625q0.625 0.328125 1.5625 0.328125q0.84375 0 1.453125 -0.296875q0.625 -0.3125 1.015625 -0.859375q0.40625 -0.5625 0.59375 -1.3125q0.1875 -0.765625 0.1875 -1.6875zm11.046875 -4.59375q0 0.265625 -0.015625 0.4375q0 0.171875 -0.046875 0.28125q-0.03125 0.09375 -0.078125 0.15625q-0.046875 0.046875 -0.140625 0.046875q-0.09375 0 -0.234375 -0.046875q-0.140625 -0.0625 -0.3125 -0.109375q-0.15625 -0.0625 -0.375 -0.109375q-0.203125 -0.046875 -0.453125 -0.046875q-0.296875 0 -0.578125 0.125q-0.28125 0.109375 -0.59375 0.390625q-0.3125 0.265625 -0.65625 0.71875q-0.328125 0.4375 -0.734375 1.078125l0 6.9375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -10.546875q0 -0.09375 0.03125 -0.15625q0.03125 -0.0625 0.140625 -0.109375q0.109375 -0.0625 0.265625 -0.078125q0.171875 -0.015625 0.4375 -0.015625q0.265625 0 0.421875 0.015625q0.171875 0.015625 0.265625 0.078125q0.09375 0.046875 0.140625 0.109375q0.046875 0.0625 0.046875 0.15625l0 1.53125q0.421875 -0.625 0.796875 -1.015625q0.390625 -0.40625 0.734375 -0.625q0.34375 -0.234375 0.671875 -0.328125q0.328125 -0.09375 0.671875 -0.09375q0.15625 0 0.34375 0.03125q0.203125 0.015625 0.40625 0.0625q0.21875 0.046875 0.375 0.109375q0.171875 0.046875 0.234375 0.109375q0.078125 0.0625 0.09375 0.109375q0.03125 0.046875 0.046875 0.140625q0.03125 0.078125 0.03125 0.234375q0 0.15625 0 0.421875zm19.261719 4.546875q0 1.390625 -0.40625 2.484375q-0.40625 1.078125 -1.15625 1.828125q-0.75 0.75 -1.828125 1.140625q-1.078125 0.375 -2.453125 0.375q-1.25 0 -2.28125 -0.359375q-1.03125 -0.359375 -1.765625 -1.0625q-0.734375 -0.71875 -1.140625 -1.78125q-0.390625 -1.078125 -0.390625 -2.46875l0 -9.40625q0 -0.09375 0.046875 -0.15625q0.046875 -0.078125 0.15625 -0.109375q0.125 -0.046875 0.3125 -0.078125q0.1875 -0.03125 0.484375 -0.03125q0.28125 0 0.484375 0.03125q0.203125 0.03125 0.3125 0.078125q0.109375 0.03125 0.15625 0.109375q0.046875 0.0625 0.046875 0.15625l0 9.15625q0 1.0625 0.25 1.84375q0.265625 0.78125 0.75 1.3125q0.484375 0.515625 1.171875 0.78125q0.6875 0.265625 1.546875 0.265625q0.875 0 1.5625 -0.25q0.6875 -0.265625 1.15625 -0.78125q0.46875 -0.515625 0.71875 -1.28125q0.265625 -0.765625 0.265625 -1.78125l0 -9.265625q0 -0.09375 0.046875 -0.15625q0.046875 -0.078125 0.15625 -0.109375q0.125 -0.046875 0.3125 -0.078125q0.1875 -0.03125 0.484375 -0.03125q0.28125 0 0.46875 0.03125q0.203125 0.03125 0.3125 0.078125q0.109375 0.03125 0.15625 0.109375q0.0625 0.0625 0.0625 0.15625l0 9.25zm12.8515625 5.3125q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.09375 0.046875 -0.28125 0.0625q-0.1875 0.03125 -0.46875 0.03125q-0.296875 0 -0.484375 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.046875 -0.0625 -0.046875 -0.15625l0 -6.171875q0 -0.90625 -0.140625 -1.453125q-0.140625 -0.546875 -0.40625 -0.9375q-0.265625 -0.40625 -0.703125 -0.609375q-0.421875 -0.21875 -0.984375 -0.21875q-0.71875 0 -1.453125 0.515625q-0.71875 0.515625 -1.515625 1.5l0 7.375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -10.546875q0 -0.09375 0.03125 -0.15625q0.03125 -0.0625 0.140625 -0.109375q0.109375 -0.0625 0.265625 -0.078125q0.171875 -0.015625 0.4375 -0.015625q0.265625 0 0.421875 0.015625q0.171875 0.015625 0.265625 0.078125q0.09375 0.046875 0.140625 0.109375q0.046875 0.0625 0.046875 0.15625l0 1.390625q0.890625 -0.984375 1.765625 -1.453125q0.890625 -0.46875 1.796875 -0.46875q1.046875 0 1.765625 0.359375q0.71875 0.359375 1.15625 0.96875q0.453125 0.59375 0.640625 1.390625q0.203125 0.796875 0.203125 1.921875l0 6.4375zm5.46875 0q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -10.546875q0 -0.078125 0.03125 -0.140625q0.046875 -0.078125 0.15625 -0.125q0.109375 -0.046875 0.296875 -0.0625q0.1875 -0.03125 0.46875 -0.03125q0.296875 0 0.484375 0.03125q0.1875 0.015625 0.296875 0.0625q0.109375 0.046875 0.15625 0.125q0.046875 0.0625 0.046875 0.140625l0 10.546875zm0.21875 -14.109375q0 0.6875 -0.265625 0.9375q-0.25 0.234375 -0.9375 0.234375q-0.6875 0 -0.9375 -0.234375q-0.25 -0.25 -0.25 -0.90625q0 -0.6875 0.25 -0.921875q0.265625 -0.25 0.953125 -0.25q0.6875 0 0.9375 0.234375q0.25 0.234375 0.25 0.90625zm8.8359375 13.34375q0 0.328125 -0.046875 0.53125q-0.046875 0.203125 -0.140625 0.296875q-0.09375 0.09375 -0.28125 0.1875q-0.1875 0.078125 -0.4375 0.125q-0.234375 0.046875 -0.5 0.078125q-0.265625 0.046875 -0.546875 0.046875q-0.8125 0 -1.40625 -0.21875q-0.578125 -0.21875 -0.953125 -0.65625q-0.375 -0.4375 -0.546875 -1.109375q-0.171875 -0.6875 -0.171875 -1.59375l0 -6.171875l-1.46875 0q-0.1875 0 -0.296875 -0.1875q-0.09375 -0.1875 -0.09375 -0.609375q0 -0.21875 0.03125 -0.359375q0.03125 -0.15625 0.078125 -0.25q0.046875 -0.109375 0.109375 -0.140625q0.078125 -0.046875 0.171875 -0.046875l1.46875 0l0 -2.515625q0 -0.078125 0.03125 -0.140625q0.046875 -0.078125 0.15625 -0.125q0.125 -0.0625 0.3125 -0.078125q0.1875 -0.03125 0.46875 -0.03125q0.28125 0 0.46875 0.03125q0.1875 0.015625 0.296875 0.078125q0.109375 0.046875 0.15625 0.125q0.046875 0.0625 0.046875 0.140625l0 2.515625l2.703125 0q0.09375 0 0.15625 0.046875q0.078125 0.03125 0.125 0.140625q0.0625 0.09375 0.078125 0.25q0.03125 0.140625 0.03125 0.359375q0 0.421875 -0.109375 0.609375q-0.109375 0.1875 -0.28125 0.1875l-2.703125 0l0 5.890625q0 1.09375 0.3125 1.65625q0.328125 0.546875 1.15625 0.546875q0.28125 0 0.484375 -0.046875q0.21875 -0.0625 0.375 -0.109375q0.171875 -0.0625 0.28125 -0.109375q0.125 -0.0625 0.21875 -0.0625q0.046875 0 0.09375 0.03125q0.0625 0.03125 0.09375 0.109375q0.03125 0.078125 0.046875 0.21875q0.03125 0.140625 0.03125 0.359375z" fill-rule="nonzero"></path><defs><linearGradient id="p5.3" gradientUnits="userSpaceOnUse" gradientTransform="matrix(14.669052537986385 0.0 0.0 4.650639314589944 483.85729291338583 168.43352047244096)" spreadMethod="pad" x1="14.669052537986381" y1="14.669052537986381" x2="14.669052537986381" y2="0.0"><stop offset="0.0" stop-color="#bedbff"></stop><stop offset="0.35" stop-color="#d1e5fe"></stop><stop offset="1.0" stop-color="#eef5ff"></stop></linearGradient></defs><path fill="url(#p5.3)" d="m483.8573 168.43352l215.18109 0l0 68.220474l-215.18109 0z" fill-rule="nonzero"></path><path stroke="#4a7dbb" stroke-width="1.0" stroke-linejoin="round" stroke-linecap="butt" d="m483.8573 168.43352l215.18109 0l0 68.220474l-215.18109 0z" fill-rule="nonzero"></path><path fill="#000000" d="m546.0924 196.27126q0 0.09375 -0.03125 0.171875q-0.03125 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.328125 0.0625q-0.203125 0.03125 -0.5625 0.03125q-0.296875 0 -0.5 -0.03125q-0.1875 -0.015625 -0.3125 -0.0625q-0.109375 -0.0625 -0.171875 -0.15625q-0.0625 -0.09375 -0.109375 -0.234375l-1.390625 -3.578125q-0.25 -0.609375 -0.515625 -1.109375q-0.265625 -0.515625 -0.625 -0.890625q-0.359375 -0.375 -0.859375 -0.578125q-0.484375 -0.203125 -1.1875 -0.203125l-1.34375 0l0 6.453125q0 0.09375 -0.0625 0.171875q-0.046875 0.0625 -0.15625 0.109375q-0.109375 0.046875 -0.3125 0.078125q-0.1875 0.03125 -0.46875 0.03125q-0.296875 0 -0.5 -0.03125q-0.1875 -0.03125 -0.3125 -0.078125q-0.109375 -0.046875 -0.15625 -0.109375q-0.046875 -0.078125 -0.046875 -0.171875l0 -14.03125q0 -0.453125 0.234375 -0.640625q0.25 -0.1875 0.515625 -0.1875l3.21875 0q0.578125 0 0.953125 0.03125q0.390625 0.03125 0.6875 0.0625q0.890625 0.15625 1.5625 0.484375q0.671875 0.328125 1.125 0.84375q0.453125 0.5 0.6875 1.15625q0.234375 0.640625 0.234375 1.421875q0 0.765625 -0.21875 1.375q-0.203125 0.59375 -0.59375 1.0625q-0.375 0.453125 -0.921875 0.796875q-0.53125 0.34375 -1.203125 0.578125q0.375 0.15625 0.671875 0.421875q0.3125 0.25 0.578125 0.609375q0.265625 0.34375 0.5 0.796875q0.234375 0.453125 0.46875 1.03125l1.359375 3.34375q0.15625 0.421875 0.203125 0.59375q0.046875 0.15625 0.046875 0.25zm-3.03125 -10.640625q0 -0.890625 -0.40625 -1.5q-0.390625 -0.625 -1.328125 -0.890625q-0.296875 -0.09375 -0.671875 -0.125q-0.359375 -0.03125 -0.953125 -0.03125l-1.703125 0l0 5.109375l1.96875 0q0.796875 0 1.375 -0.1875q0.578125 -0.203125 0.96875 -0.546875q0.390625 -0.34375 0.5625 -0.8125q0.1875 -0.46875 0.1875 -1.015625zm15.546875 5.265625q0 1.296875 -0.34375 2.375q-0.34375 1.078125 -1.015625 1.875q-0.671875 0.78125 -1.6875 1.21875q-1.015625 0.4375 -2.34375 0.4375q-1.3125 0 -2.28125 -0.375q-0.953125 -0.390625 -1.609375 -1.125q-0.640625 -0.75 -0.953125 -1.796875q-0.3125 -1.0625 -0.3125 -2.390625q0 -1.296875 0.328125 -2.375q0.328125 -1.09375 1.0 -1.875q0.6875 -0.78125 1.6875 -1.21875q1.015625 -0.4375 2.359375 -0.4375q1.296875 0 2.265625 0.390625q0.96875 0.390625 1.609375 1.125q0.640625 0.734375 0.96875 1.796875q0.328125 1.046875 0.328125 2.375zm-2.046875 0.125q0 -0.84375 -0.15625 -1.609375q-0.15625 -0.765625 -0.53125 -1.328125q-0.359375 -0.578125 -0.984375 -0.90625q-0.609375 -0.34375 -1.53125 -0.34375q-0.859375 0 -1.484375 0.3125q-0.609375 0.296875 -1.015625 0.859375q-0.390625 0.546875 -0.59375 1.3125q-0.1875 0.765625 -0.1875 1.65625q0 0.875 0.15625 1.640625q0.171875 0.75 0.53125 1.328125q0.375 0.5625 0.984375 0.90625q0.625 0.328125 1.5625 0.328125q0.84375 0 1.453125 -0.296875q0.625 -0.3125 1.015625 -0.859375q0.40625 -0.5625 0.59375 -1.3125q0.1875 -0.765625 0.1875 -1.6875zm14.59375 -0.140625q0 1.359375 -0.296875 2.46875q-0.296875 1.09375 -0.890625 1.875q-0.578125 0.765625 -1.421875 1.171875q-0.84375 0.40625 -1.921875 0.40625q-0.515625 0 -0.9375 -0.09375q-0.421875 -0.09375 -0.84375 -0.3125q-0.40625 -0.234375 -0.8125 -0.578125q-0.40625 -0.34375 -0.875 -0.8125l0 1.28125q0 0.09375 -0.046875 0.171875q-0.046875 0.0625 -0.15625 0.109375q-0.09375 0.046875 -0.25 0.0625q-0.15625 0.03125 -0.40625 0.03125q-0.234375 0 -0.40625 -0.03125q-0.15625 -0.015625 -0.265625 -0.0625q-0.109375 -0.046875 -0.140625 -0.109375q-0.03125 -0.078125 -0.03125 -0.171875l0 -15.65625q0 -0.09375 0.03125 -0.15625q0.046875 -0.078125 0.15625 -0.125q0.109375 -0.046875 0.296875 -0.0625q0.1875 -0.03125 0.46875 -0.03125q0.296875 0 0.484375 0.03125q0.1875 0.015625 0.296875 0.0625q0.109375 0.046875 0.15625 0.125q0.046875 0.0625 0.046875 0.15625l0 6.3125q0.46875 -0.46875 0.90625 -0.796875q0.4375 -0.328125 0.859375 -0.53125q0.421875 -0.21875 0.84375 -0.3125q0.421875 -0.09375 0.890625 -0.09375q1.140625 0 1.953125 0.46875q0.828125 0.453125 1.328125 1.21875q0.515625 0.765625 0.75 1.796875q0.234375 1.03125 0.234375 2.1875zm-2.046875 0.21875q0 -0.8125 -0.125 -1.5625q-0.109375 -0.765625 -0.421875 -1.34375q-0.296875 -0.59375 -0.8125 -0.953125q-0.5 -0.359375 -1.25 -0.359375q-0.375 0 -0.734375 0.109375q-0.359375 0.09375 -0.734375 0.34375q-0.375 0.25 -0.78125 0.640625q-0.40625 0.375 -0.859375 0.96875l0 4.203125q0.796875 0.96875 1.515625 1.484375q0.734375 0.515625 1.515625 0.515625q0.71875 0 1.234375 -0.34375q0.515625 -0.359375 0.84375 -0.9375q0.328125 -0.59375 0.46875 -1.3125q0.140625 -0.71875 0.140625 -1.453125zm14.765625 -0.203125q0 1.296875 -0.34375 2.375q-0.34375 1.078125 -1.015625 1.875q-0.671875 0.78125 -1.6875 1.21875q-1.015625 0.4375 -2.34375 0.4375q-1.3125 0 -2.28125 -0.375q-0.953125 -0.390625 -1.609375 -1.125q-0.640625 -0.75 -0.953125 -1.796875q-0.3125 -1.0625 -0.3125 -2.390625q0 -1.296875 0.328125 -2.375q0.328125 -1.09375 1.0 -1.875q0.6875 -0.78125 1.6875 -1.21875q1.015625 -0.4375 2.359375 -0.4375q1.296875 0 2.265625 0.390625q0.96875 0.390625 1.609375 1.125q0.640625 0.734375 0.96875 1.796875q0.328125 1.046875 0.328125 2.375zm-2.046875 0.125q0 -0.84375 -0.15625 -1.609375q-0.15625 -0.765625 -0.53125 -1.328125q-0.359375 -0.578125 -0.984375 -0.90625q-0.609375 -0.34375 -1.53125 -0.34375q-0.859375 0 -1.484375 0.3125q-0.609375 0.296875 -1.015625 0.859375q-0.390625 0.546875 -0.59375 1.3125q-0.1875 0.765625 -0.1875 1.65625q0 0.875 0.15625 1.640625q0.171875 0.75 0.53125 1.328125q0.375 0.5625 0.984375 0.90625q0.625 0.328125 1.5625 0.328125q0.84375 0 1.453125 -0.296875q0.625 -0.3125 1.015625 -0.859375q0.40625 -0.5625 0.59375 -1.3125q0.1875 -0.765625 0.1875 -1.6875zm10.375 4.5q0 0.328125 -0.046875 0.53125q-0.046875 0.203125 -0.140625 0.296875q-0.09375 0.09375 -0.28125 0.1875q-0.1875 0.078125 -0.4375 0.125q-0.234375 0.046875 -0.5 0.078125q-0.265625 0.046875 -0.546875 0.046875q-0.8125 0 -1.40625 -0.21875q-0.578125 -0.21875 -0.953125 -0.65625q-0.375 -0.4375 -0.546875 -1.109375q-0.171875 -0.6875 -0.171875 -1.59375l0 -6.171875l-1.46875 0q-0.1875 0 -0.296875 -0.1875q-0.09375 -0.1875 -0.09375 -0.609375q0 -0.21875 0.03125 -0.359375q0.03125 -0.15625 0.078125 -0.25q0.046875 -0.109375 0.109375 -0.140625q0.078125 -0.046875 0.171875 -0.046875l1.46875 0l0 -2.515625q0 -0.078125 0.03125 -0.140625q0.046875 -0.078125 0.15625 -0.125q0.125 -0.0625 0.3125 -0.078125q0.1875 -0.03125 0.46875 -0.03125q0.28125 0 0.46875 0.03125q0.1875 0.015625 0.296875 0.078125q0.109375 0.046875 0.15625 0.125q0.046875 0.0625 0.046875 0.140625l0 2.515625l2.703125 0q0.09375 0 0.15625 0.046875q0.078125 0.03125 0.125 0.140625q0.0625 0.09375 0.078125 0.25q0.03125 0.140625 0.03125 0.359375q0 0.421875 -0.109375 0.609375q-0.109375 0.1875 -0.28125 0.1875l-2.703125 0l0 5.890625q0 1.09375 0.3125 1.65625q0.328125 0.546875 1.15625 0.546875q0.28125 0 0.484375 -0.046875q0.21875 -0.0625 0.375 -0.109375q0.171875 -0.0625 0.28125 -0.109375q0.125 -0.0625 0.21875 -0.0625q0.046875 0 0.09375 0.03125q0.0625 0.03125 0.09375 0.109375q0.03125 0.078125 0.046875 0.21875q0.03125 0.140625 0.03125 0.359375zm16.339844 -3.1875q0 1.0625 -0.390625 1.890625q-0.390625 0.828125 -1.09375 1.421875q-0.6875 0.578125 -1.640625 0.875q-0.9375 0.28125 -2.03125 0.28125q-0.75 0 -1.40625 -0.125q-0.65625 -0.125 -1.171875 -0.3125q-0.5 -0.1875 -0.84375 -0.390625q-0.34375 -0.203125 -0.484375 -0.34375q-0.125 -0.140625 -0.203125 -0.359375q-0.0625 -0.21875 -0.0625 -0.578125q0 -0.25 0.015625 -0.421875q0.03125 -0.171875 0.078125 -0.28125q0.046875 -0.109375 0.109375 -0.140625q0.078125 -0.046875 0.171875 -0.046875q0.171875 0 0.46875 0.203125q0.296875 0.203125 0.765625 0.4375q0.46875 0.234375 1.125 0.4375q0.671875 0.203125 1.53125 0.203125q0.65625 0 1.203125 -0.171875q0.546875 -0.1875 0.9375 -0.5q0.390625 -0.328125 0.59375 -0.796875q0.21875 -0.46875 0.21875 -1.0625q0 -0.640625 -0.296875 -1.09375q-0.28125 -0.46875 -0.765625 -0.8125q-0.484375 -0.34375 -1.09375 -0.625q-0.609375 -0.296875 -1.265625 -0.59375q-0.640625 -0.296875 -1.25 -0.65625q-0.609375 -0.375 -1.09375 -0.859375q-0.46875 -0.5 -0.78125 -1.15625q-0.296875 -0.65625 -0.296875 -1.59375q0 -0.9375 0.34375 -1.6875q0.359375 -0.75 0.96875 -1.25q0.609375 -0.5 1.453125 -0.765625q0.859375 -0.265625 1.84375 -0.265625q0.5 0 1.015625 0.09375q0.515625 0.078125 0.953125 0.234375q0.453125 0.140625 0.796875 0.328125q0.359375 0.171875 0.46875 0.296875q0.125 0.109375 0.15625 0.171875q0.03125 0.0625 0.046875 0.171875q0.03125 0.09375 0.046875 0.234375q0.015625 0.140625 0.015625 0.359375q0 0.203125 -0.03125 0.375q-0.015625 0.15625 -0.046875 0.28125q-0.03125 0.109375 -0.09375 0.15625q-0.0625 0.046875 -0.15625 0.046875q-0.125 0 -0.40625 -0.15625q-0.265625 -0.171875 -0.671875 -0.375q-0.390625 -0.203125 -0.9375 -0.375q-0.546875 -0.171875 -1.21875 -0.171875q-0.640625 0 -1.109375 0.171875q-0.46875 0.171875 -0.78125 0.453125q-0.296875 0.28125 -0.453125 0.671875q-0.140625 0.390625 -0.140625 0.8125q0 0.640625 0.28125 1.09375q0.296875 0.453125 0.78125 0.8125q0.484375 0.34375 1.109375 0.640625q0.625 0.296875 1.265625 0.59375q0.640625 0.296875 1.265625 0.65625q0.625 0.359375 1.109375 0.84375q0.484375 0.484375 0.78125 1.15625q0.296875 0.65625 0.296875 1.5625zm8.152283 3.1875q0 0.328125 -0.046875 0.53125q-0.046875 0.203125 -0.140625 0.296875q-0.09375 0.09375 -0.28125 0.1875q-0.1875 0.078125 -0.4375 0.125q-0.234375 0.046875 -0.5 0.078125q-0.265625 0.046875 -0.546875 0.046875q-0.8125 0 -1.40625 -0.21875q-0.578125 -0.21875 -0.953125 -0.65625q-0.375 -0.4375 -0.54681396 -1.109375q-0.171875 -0.6875 -0.171875 -1.59375l0 -6.171875l-1.46875 0q-0.1875 0 -0.296875 -0.1875q-0.09375 -0.1875 -0.09375 -0.609375q0 -0.21875 0.03125 -0.359375q0.03125 -0.15625 0.078125 -0.25q0.046875 -0.109375 0.109375 -0.140625q0.078125 -0.046875 0.171875 -0.046875l1.46875 0l0 -2.515625q0 -0.078125 0.03125 -0.140625q0.046875 -0.078125 0.15625 -0.125q0.124938965 -0.0625 0.31243896 -0.078125q0.1875 -0.03125 0.46875 -0.03125q0.28125 0 0.46875 0.03125q0.1875 0.015625 0.296875 0.078125q0.109375 0.046875 0.15625 0.125q0.046875 0.0625 0.046875 0.140625l0 2.515625l2.703125 0q0.09375 0 0.15625 0.046875q0.078125 0.03125 0.125 0.140625q0.0625 0.09375 0.078125 0.25q0.03125 0.140625 0.03125 0.359375q0 0.421875 -0.109375 0.609375q-0.109375 0.1875 -0.28125 0.1875l-2.703125 0l0 5.890625q0 1.09375 0.3125 1.65625q0.328125 0.546875 1.15625 0.546875q0.28125 0 0.484375 -0.046875q0.21875 -0.0625 0.375 -0.109375q0.171875 -0.0625 0.28125 -0.109375q0.125 -0.0625 0.21875 -0.0625q0.046875 0 0.09375 0.03125q0.0625 0.03125 0.09375 0.109375q0.03125 0.078125 0.046875 0.21875q0.03125 0.140625 0.03125 0.359375zm10.4921875 0.78125q0 0.140625 -0.09375 0.21875q-0.09375 0.0625 -0.265625 0.09375q-0.15625 0.046875 -0.46875 0.046875q-0.296875 0 -0.484375 -0.046875q-0.1875 -0.03125 -0.265625 -0.09375q-0.078125 -0.078125 -0.078125 -0.21875l0 -1.0625q-0.6875 0.75 -1.546875 1.15625q-0.84375 0.40625 -1.796875 0.40625q-0.828125 0 -1.5 -0.21875q-0.671875 -0.21875 -1.15625 -0.625q-0.46875 -0.40625 -0.734375 -1.0q-0.265625 -0.609375 -0.265625 -1.359375q0 -0.890625 0.359375 -1.546875q0.375 -0.65625 1.046875 -1.09375q0.6875 -0.4375 1.671875 -0.65625q0.984375 -0.21875 2.203125 -0.21875l1.453125 0l0 -0.8125q0 -0.609375 -0.125 -1.078125q-0.125 -0.46875 -0.421875 -0.78125q-0.28125 -0.3125 -0.734375 -0.46875q-0.453125 -0.15625 -1.125 -0.15625q-0.71875 0 -1.296875 0.171875q-0.5625 0.171875 -0.984375 0.375q-0.421875 0.203125 -0.71875 0.375q-0.28125 0.171875 -0.421875 0.171875q-0.09375 0 -0.171875 -0.046875q-0.0625 -0.046875 -0.125 -0.140625q-0.046875 -0.09375 -0.078125 -0.234375q-0.015625 -0.15625 -0.015625 -0.328125q0 -0.296875 0.03125 -0.46875q0.046875 -0.171875 0.203125 -0.3125q0.171875 -0.15625 0.546875 -0.359375q0.390625 -0.21875 0.890625 -0.375q0.515625 -0.171875 1.109375 -0.28125q0.59375 -0.125 1.203125 -0.125q1.140625 0 1.9375 0.265625q0.796875 0.25 1.28125 0.75q0.5 0.5 0.71875 1.25q0.21875 0.734375 0.21875 1.71875l0 7.109375zm-1.921875 -4.8125l-1.640625 0q-0.796875 0 -1.390625 0.140625q-0.578125 0.125 -0.96875 0.390625q-0.390625 0.265625 -0.578125 0.640625q-0.171875 0.359375 -0.171875 0.84375q0 0.8125 0.515625 1.296875q0.53125 0.484375 1.46875 0.484375q0.75 0 1.40625 -0.375q0.65625 -0.390625 1.359375 -1.1875l0 -2.234375zm10.964844 4.03125q0 0.328125 -0.046875 0.53125q-0.046875 0.203125 -0.140625 0.296875q-0.09375 0.09375 -0.28125 0.1875q-0.1875 0.078125 -0.4375 0.125q-0.234375 0.046875 -0.5 0.078125q-0.265625 0.046875 -0.546875 0.046875q-0.8125 0 -1.40625 -0.21875q-0.578125 -0.21875 -0.953125 -0.65625q-0.375 -0.4375 -0.546875 -1.109375q-0.171875 -0.6875 -0.171875 -1.59375l0 -6.171875l-1.46875 0q-0.1875 0 -0.296875 -0.1875q-0.09375 -0.1875 -0.09375 -0.609375q0 -0.21875 0.03125 -0.359375q0.03125 -0.15625 0.078125 -0.25q0.046875 -0.109375 0.109375 -0.140625q0.078125 -0.046875 0.171875 -0.046875l1.46875 0l0 -2.515625q0 -0.078125 0.03125 -0.140625q0.046875 -0.078125 0.15625 -0.125q0.125 -0.0625 0.3125 -0.078125q0.1875 -0.03125 0.46875 -0.03125q0.28125 0 0.46875 0.03125q0.1875 0.015625 0.296875 0.078125q0.109375 0.046875 0.15625 0.125q0.046875 0.0625 0.046875 0.140625l0 2.515625l2.703125 0q0.09375 0 0.15625 0.046875q0.078125 0.03125 0.125 0.140625q0.0625 0.09375 0.078125 0.25q0.03125 0.140625 0.03125 0.359375q0 0.421875 -0.109375 0.609375q-0.109375 0.1875 -0.28125 0.1875l-2.703125 0l0 5.890625q0 1.09375 0.3125 1.65625q0.328125 0.546875 1.15625 0.546875q0.28125 0 0.484375 -0.046875q0.21875 -0.0625 0.375 -0.109375q0.171875 -0.0625 0.28125 -0.109375q0.125 -0.0625 0.21875 -0.0625q0.046875 0 0.09375 0.03125q0.0625 0.03125 0.09375 0.109375q0.03125 0.078125 0.046875 0.21875q0.03125 0.140625 0.03125 0.359375zm11.5546875 -4.96875q0 0.46875 -0.234375 0.65625q-0.21875 0.1875 -0.515625 0.1875l-6.921875 0q0 0.890625 0.171875 1.59375q0.1875 0.703125 0.59375 1.203125q0.40625 0.5 1.0625 0.78125q0.65625 0.265625 1.609375 0.265625q0.75 0 1.328125 -0.125q0.59375 -0.125 1.015625 -0.28125q0.4375 -0.15625 0.703125 -0.265625q0.28125 -0.125 0.421875 -0.125q0.078125 0 0.140625 0.046875q0.078125 0.03125 0.109375 0.109375q0.03125 0.078125 0.046875 0.234375q0.015625 0.140625 0.015625 0.359375q0 0.140625 -0.015625 0.265625q0 0.109375 -0.015625 0.203125q-0.015625 0.078125 -0.0625 0.15625q-0.046875 0.0625 -0.109375 0.125q-0.0625 0.0625 -0.375 0.21875q-0.3125 0.140625 -0.828125 0.28125q-0.5 0.140625 -1.171875 0.25q-0.65625 0.109375 -1.40625 0.109375q-1.296875 0 -2.28125 -0.359375q-0.96875 -0.359375 -1.640625 -1.078125q-0.671875 -0.71875 -1.015625 -1.796875q-0.328125 -1.078125 -0.328125 -2.5q0 -1.359375 0.34375 -2.4375q0.359375 -1.09375 1.015625 -1.84375q0.671875 -0.765625 1.609375 -1.171875q0.9375 -0.40625 2.09375 -0.40625q1.234375 0 2.109375 0.40625q0.875 0.390625 1.4375 1.078125q0.5625 0.671875 0.828125 1.578125q0.265625 0.90625 0.265625 1.9375l0 0.34375zm-1.953125 -0.5625q0.046875 -1.53125 -0.671875 -2.390625q-0.703125 -0.875 -2.09375 -0.875q-0.71875 0 -1.265625 0.28125q-0.53125 0.265625 -0.90625 0.71875q-0.359375 0.4375 -0.5625 1.03125q-0.1875 0.578125 -0.21875 1.234375l5.71875 0z" fill-rule="nonzero"></path><path fill="#000000" d="m546.0436 223.44313q0 0.1875 -0.015625 0.328125q0 0.140625 -0.03125 0.25q-0.03125 0.09375 -0.078125 0.1875q-0.046875 0.078125 -0.171875 0.203125q-0.109375 0.109375 -0.484375 0.34375q-0.375 0.234375 -0.9375 0.46875q-0.546875 0.234375 -1.28125 0.390625q-0.71875 0.15625 -1.5625 0.15625q-1.484375 0 -2.671875 -0.484375q-1.1875 -0.5 -2.03125 -1.453125q-0.828125 -0.96875 -1.28125 -2.375q-0.453125 -1.421875 -0.453125 -3.265625q0 -1.875 0.484375 -3.34375q0.484375 -1.484375 1.359375 -2.515625q0.890625 -1.03125 2.109375 -1.5625q1.21875 -0.546875 2.71875 -0.546875q0.65625 0 1.265625 0.125q0.625 0.125 1.15625 0.3125q0.53125 0.1875 0.9375 0.4375q0.40625 0.25 0.5625 0.40625q0.15625 0.15625 0.203125 0.234375q0.046875 0.078125 0.078125 0.203125q0.03125 0.109375 0.046875 0.265625q0.015625 0.140625 0.015625 0.359375q0 0.234375 -0.03125 0.40625q-0.015625 0.15625 -0.0625 0.265625q-0.046875 0.109375 -0.109375 0.171875q-0.0625 0.046875 -0.15625 0.046875q-0.15625 0 -0.453125 -0.234375q-0.296875 -0.234375 -0.765625 -0.5q-0.453125 -0.28125 -1.125 -0.5q-0.65625 -0.234375 -1.578125 -0.234375q-1.015625 0 -1.84375 0.40625q-0.8125 0.40625 -1.40625 1.1875q-0.578125 0.78125 -0.90625 1.921875q-0.328125 1.125 -0.328125 2.578125q0 1.4375 0.3125 2.546875q0.3125 1.109375 0.890625 1.859375q0.578125 0.734375 1.421875 1.125q0.84375 0.375 1.921875 0.375q0.890625 0 1.5625 -0.21875q0.6875 -0.234375 1.15625 -0.5q0.46875 -0.28125 0.765625 -0.5q0.3125 -0.21875 0.5 -0.21875q0.078125 0 0.125 0.03125q0.0625 0.03125 0.09375 0.140625q0.046875 0.09375 0.0625 0.265625q0.015625 0.171875 0.015625 0.453125zm12.265625 -3.546875q0 1.296875 -0.34375 2.375q-0.34375 1.078125 -1.015625 1.875q-0.671875 0.78125 -1.6875 1.21875q-1.015625 0.4375 -2.34375 0.4375q-1.3125 0 -2.28125 -0.375q-0.953125 -0.390625 -1.609375 -1.125q-0.640625 -0.75 -0.953125 -1.796875q-0.3125 -1.0625 -0.3125 -2.390625q0 -1.296875 0.328125 -2.375q0.328125 -1.09375 1.0 -1.875q0.6875 -0.78125 1.6875 -1.21875q1.015625 -0.4375 2.359375 -0.4375q1.296875 0 2.265625 0.390625q0.96875 0.390625 1.609375 1.125q0.640625 0.734375 0.96875 1.796875q0.328125 1.046875 0.328125 2.375zm-2.046875 0.125q0 -0.84375 -0.15625 -1.609375q-0.15625 -0.765625 -0.53125 -1.328125q-0.359375 -0.578125 -0.984375 -0.90625q-0.609375 -0.34375 -1.53125 -0.34375q-0.859375 0 -1.484375 0.3125q-0.609375 0.296875 -1.015625 0.859375q-0.390625 0.546875 -0.59375 1.3125q-0.1875 0.765625 -0.1875 1.65625q0 0.875 0.15625 1.640625q0.171875 0.75 0.53125 1.328125q0.375 0.5625 0.984375 0.90625q0.625 0.328125 1.5625 0.328125q0.84375 0 1.453125 -0.296875q0.625 -0.3125 1.015625 -0.859375q0.40625 -0.5625 0.59375 -1.3125q0.1875 -0.765625 0.1875 -1.6875zm20.53125 5.265625q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.09375 0.046875 -0.28125 0.0625q-0.1875 0.03125 -0.46875 0.03125q-0.296875 0 -0.484375 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.046875 -0.0625 -0.046875 -0.15625l0 -6.40625q0 -0.671875 -0.125 -1.21875q-0.109375 -0.546875 -0.375 -0.9375q-0.25 -0.40625 -0.65625 -0.609375q-0.390625 -0.21875 -0.9375 -0.21875q-0.671875 0 -1.34375 0.515625q-0.671875 0.515625 -1.484375 1.5l0 7.375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.46875 0.03125q-0.265625 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -6.40625q0 -0.671875 -0.140625 -1.21875q-0.125 -0.546875 -0.390625 -0.9375q-0.25 -0.40625 -0.640625 -0.609375q-0.390625 -0.21875 -0.9375 -0.21875q-0.65625 0 -1.34375 0.515625q-0.671875 0.515625 -1.46875 1.5l0 7.375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -10.546875q0 -0.09375 0.03125 -0.15625q0.03125 -0.0625 0.140625 -0.109375q0.109375 -0.0625 0.265625 -0.078125q0.171875 -0.015625 0.4375 -0.015625q0.265625 0 0.421875 0.015625q0.171875 0.015625 0.265625 0.078125q0.09375 0.046875 0.140625 0.109375q0.046875 0.0625 0.046875 0.15625l0 1.390625q0.890625 -0.984375 1.71875 -1.453125q0.84375 -0.46875 1.703125 -0.46875q0.65625 0 1.171875 0.15625q0.515625 0.15625 0.90625 0.4375q0.40625 0.265625 0.6875 0.65625q0.28125 0.375 0.46875 0.84375q0.53125 -0.578125 1.0 -0.96875q0.484375 -0.40625 0.921875 -0.640625q0.4375 -0.25 0.84375 -0.359375q0.421875 -0.125 0.84375 -0.125q1.03125 0 1.71875 0.359375q0.6875 0.359375 1.109375 0.96875q0.4375 0.59375 0.609375 1.390625q0.1875 0.796875 0.1875 1.6875l0 6.671875zm13.234375 -5.4375q0 1.390625 -0.296875 2.5q-0.296875 1.09375 -0.890625 1.859375q-0.578125 0.765625 -1.4375 1.1875q-0.84375 0.40625 -1.953125 0.40625q-0.46875 0 -0.875 -0.09375q-0.390625 -0.09375 -0.765625 -0.28125q-0.375 -0.203125 -0.75 -0.5q-0.375 -0.3125 -0.796875 -0.734375l0 5.28125q0 0.09375 -0.046875 0.15625q-0.046875 0.078125 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.046875 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -14.734375q0 -0.109375 0.03125 -0.171875q0.03125 -0.0625 0.140625 -0.109375q0.109375 -0.046875 0.265625 -0.0625q0.171875 -0.015625 0.40625 -0.015625q0.25 0 0.40625 0.015625q0.15625 0.015625 0.25 0.0625q0.109375 0.046875 0.15625 0.109375q0.046875 0.0625 0.046875 0.171875l0 1.421875q0.46875 -0.5 0.90625 -0.859375q0.453125 -0.359375 0.90625 -0.59375q0.453125 -0.25 0.921875 -0.375q0.484375 -0.125 1.015625 -0.125q1.140625 0 1.953125 0.453125q0.8125 0.4375 1.3125 1.21875q0.515625 0.765625 0.75 1.796875q0.234375 1.03125 0.234375 2.171875zm-2.046875 0.21875q0 -0.796875 -0.125 -1.546875q-0.109375 -0.765625 -0.421875 -1.34375q-0.296875 -0.59375 -0.796875 -0.9375q-0.5 -0.359375 -1.25 -0.359375q-0.375 0 -0.75 0.109375q-0.359375 0.109375 -0.734375 0.359375q-0.375 0.234375 -0.78125 0.625q-0.40625 0.390625 -0.859375 0.96875l0 4.1875q0.796875 0.984375 1.5 1.5q0.71875 0.515625 1.5 0.515625q0.734375 0 1.25 -0.34375q0.53125 -0.359375 0.84375 -0.9375q0.328125 -0.59375 0.46875 -1.3125q0.15625 -0.734375 0.15625 -1.484375zm14.765625 -0.171875q0 1.296875 -0.34375 2.375q-0.34375 1.078125 -1.015625 1.875q-0.671875 0.78125 -1.6875 1.21875q-1.015625 0.4375 -2.34375 0.4375q-1.3125 0 -2.28125 -0.375q-0.953125 -0.390625 -1.609375 -1.125q-0.640625 -0.75 -0.953125 -1.796875q-0.3125 -1.0625 -0.3125 -2.390625q0 -1.296875 0.328125 -2.375q0.328125 -1.09375 1.0 -1.875q0.6875 -0.78125 1.6875 -1.21875q1.015625 -0.4375 2.359375 -0.4375q1.296875 0 2.265625 0.390625q0.96875 0.390625 1.609375 1.125q0.640625 0.734375 0.96875 1.796875q0.328125 1.046875 0.328125 2.375zm-2.046875 0.125q0 -0.84375 -0.15625 -1.609375q-0.15625 -0.765625 -0.53125 -1.328125q-0.359375 -0.578125 -0.984375 -0.90625q-0.609375 -0.34375 -1.53125 -0.34375q-0.859375 0 -1.484375 0.3125q-0.609375 0.296875 -1.015625 0.859375q-0.390625 0.546875 -0.59375 1.3125q-0.1875 0.765625 -0.1875 1.65625q0 0.875 0.15625 1.640625q0.171875 0.75 0.53125 1.328125q0.375 0.5625 0.984375 0.90625q0.625 0.328125 1.5625 0.328125q0.84375 0 1.453125 -0.296875q0.625 -0.3125 1.015625 -0.859375q0.40625 -0.5625 0.59375 -1.3125q0.1875 -0.765625 0.1875 -1.6875zm13.968689 5.265625q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.09375 0.046875 -0.28125 0.0625q-0.1875 0.03125 -0.46875 0.03125q-0.296875 0 -0.484375 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.046875 -0.0625 -0.046875 -0.15625l0 -6.171875q0 -0.90625 -0.140625 -1.453125q-0.140625 -0.546875 -0.40625 -0.9375q-0.265625 -0.40625 -0.70306396 -0.609375q-0.421875 -0.21875 -0.984375 -0.21875q-0.71875 0 -1.453125 0.515625q-0.71875 0.515625 -1.515625 1.5l0 7.375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -10.546875q0 -0.09375 0.03125 -0.15625q0.03125 -0.0625 0.140625 -0.109375q0.109375 -0.0625 0.265625 -0.078125q0.171875 -0.015625 0.4375 -0.015625q0.265625 0 0.421875 0.015625q0.171875 0.015625 0.265625 0.078125q0.09375 0.046875 0.140625 0.109375q0.046875 0.0625 0.046875 0.15625l0 1.390625q0.890625 -0.984375 1.765625 -1.453125q0.890625 -0.46875 1.796875 -0.46875q1.046814 0 1.765564 0.359375q0.71875 0.359375 1.15625 0.96875q0.453125 0.59375 0.640625 1.390625q0.203125 0.796875 0.203125 1.921875l0 6.4375zm12.53125 -5.734375q0 0.46875 -0.234375 0.65625q-0.21875 0.1875 -0.515625 0.1875l-6.921875 0q0 0.890625 0.171875 1.59375q0.1875 0.703125 0.59375 1.203125q0.40625 0.5 1.0625 0.78125q0.65625 0.265625 1.609375 0.265625q0.75 0 1.328125 -0.125q0.59375 -0.125 1.015625 -0.28125q0.4375 -0.15625 0.703125 -0.265625q0.28125 -0.125 0.421875 -0.125q0.078125 0 0.140625 0.046875q0.078125 0.03125 0.109375 0.109375q0.03125 0.078125 0.046875 0.234375q0.015625 0.140625 0.015625 0.359375q0 0.140625 -0.015625 0.265625q0 0.109375 -0.015625 0.203125q-0.015625 0.078125 -0.0625 0.15625q-0.046875 0.0625 -0.109375 0.125q-0.0625 0.0625 -0.375 0.21875q-0.3125 0.140625 -0.828125 0.28125q-0.5 0.140625 -1.171875 0.25q-0.65625 0.109375 -1.40625 0.109375q-1.296875 0 -2.28125 -0.359375q-0.96875 -0.359375 -1.640625 -1.078125q-0.671875 -0.71875 -1.015625 -1.796875q-0.328125 -1.078125 -0.328125 -2.5q0 -1.359375 0.34375 -2.4375q0.359375 -1.09375 1.015625 -1.84375q0.671875 -0.765625 1.609375 -1.171875q0.9375 -0.40625 2.09375 -0.40625q1.234375 0 2.109375 0.40625q0.875 0.390625 1.4375 1.078125q0.5625 0.671875 0.828125 1.578125q0.265625 0.90625 0.265625 1.9375l0 0.34375zm-1.953125 -0.5625q0.046875 -1.53125 -0.671875 -2.390625q-0.703125 -0.875 -2.09375 -0.875q-0.71875 0 -1.265625 0.28125q-0.53125 0.265625 -0.90625 0.71875q-0.359375 0.4375 -0.5625 1.03125q-0.1875 0.578125 -0.21875 1.234375l5.71875 0zm13.972656 6.296875q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.09375 0.046875 -0.28125 0.0625q-0.1875 0.03125 -0.46875 0.03125q-0.296875 0 -0.484375 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.046875 -0.0625 -0.046875 -0.15625l0 -6.171875q0 -0.90625 -0.140625 -1.453125q-0.140625 -0.546875 -0.40625 -0.9375q-0.265625 -0.40625 -0.703125 -0.609375q-0.421875 -0.21875 -0.984375 -0.21875q-0.71875 0 -1.453125 0.515625q-0.71875 0.515625 -1.515625 1.5l0 7.375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -10.546875q0 -0.09375 0.03125 -0.15625q0.03125 -0.0625 0.140625 -0.109375q0.109375 -0.0625 0.265625 -0.078125q0.171875 -0.015625 0.4375 -0.015625q0.265625 0 0.421875 0.015625q0.171875 0.015625 0.265625 0.078125q0.09375 0.046875 0.140625 0.109375q0.046875 0.0625 0.046875 0.15625l0 1.390625q0.890625 -0.984375 1.765625 -1.453125q0.890625 -0.46875 1.796875 -0.46875q1.046875 0 1.765625 0.359375q0.71875 0.359375 1.15625 0.96875q0.453125 0.59375 0.640625 1.390625q0.203125 0.796875 0.203125 1.921875l0 6.4375zm9.015625 -0.765625q0 0.328125 -0.046875 0.53125q-0.046875 0.203125 -0.140625 0.296875q-0.09375 0.09375 -0.28125 0.1875q-0.1875 0.078125 -0.4375 0.125q-0.234375 0.046875 -0.5 0.078125q-0.265625 0.046875 -0.546875 0.046875q-0.8125 0 -1.40625 -0.21875q-0.578125 -0.21875 -0.953125 -0.65625q-0.375 -0.4375 -0.546875 -1.109375q-0.171875 -0.6875 -0.171875 -1.59375l0 -6.171875l-1.46875 0q-0.1875 0 -0.296875 -0.1875q-0.09375 -0.1875 -0.09375 -0.609375q0 -0.21875 0.03125 -0.359375q0.03125 -0.15625 0.078125 -0.25q0.046875 -0.109375 0.109375 -0.140625q0.078125 -0.046875 0.171875 -0.046875l1.46875 0l0 -2.515625q0 -0.078125 0.03125 -0.140625q0.046875 -0.078125 0.15625 -0.125q0.125 -0.0625 0.3125 -0.078125q0.1875 -0.03125 0.46875 -0.03125q0.28125 0 0.46875 0.03125q0.1875 0.015625 0.296875 0.078125q0.109375 0.046875 0.15625 0.125q0.046875 0.0625 0.046875 0.140625l0 2.515625l2.703125 0q0.09375 0 0.15625 0.046875q0.078125 0.03125 0.125 0.140625q0.0625 0.09375 0.078125 0.25q0.03125 0.140625 0.03125 0.359375q0 0.421875 -0.109375 0.609375q-0.109375 0.1875 -0.28125 0.1875l-2.703125 0l0 5.890625q0 1.09375 0.3125 1.65625q0.328125 0.546875 1.15625 0.546875q0.28125 0 0.484375 -0.046875q0.21875 -0.0625 0.375 -0.109375q0.171875 -0.0625 0.28125 -0.109375q0.125 -0.0625 0.21875 -0.0625q0.046875 0 0.09375 0.03125q0.0625 0.03125 0.09375 0.109375q0.03125 0.078125 0.046875 0.21875q0.03125 0.140625 0.03125 0.359375z" fill-rule="nonzero"></path><defs><linearGradient id="p5.4" gradientUnits="userSpaceOnUse" gradientTransform="matrix(11.961881715400313 0.0 0.0 5.703155579035236 801.9081146981628 168.43307086614172)" spreadMethod="pad" x1="11.961881715400313" y1="11.961881715400313" x2="11.961881715400313" y2="0.0"><stop offset="0.0" stop-color="#ebffbf"></stop><stop offset="0.35" stop-color="#f0ffd3"></stop><stop offset="1.0" stop-color="#f9ffef"></stop></linearGradient></defs><path fill="url(#p5.4)" d="m801.90814 168.43307l143.08661 0l0 68.220474l-143.08661 0z" fill-rule="nonzero"></path><path stroke="#98b954" stroke-width="1.0" stroke-linejoin="round" stroke-linecap="butt" d="m801.90814 168.43307l143.08661 0l0 68.220474l-143.08661 0z" fill-rule="nonzero"></path><path fill="#000000" d="m854.22876 206.83331q0 1.0625 -0.390625 1.890625q-0.390625 0.828125 -1.09375 1.421875q-0.6875 0.578125 -1.640625 0.875q-0.9375 0.28125 -2.03125 0.28125q-0.75 0 -1.40625 -0.125q-0.65625 -0.125 -1.171875 -0.3125q-0.5 -0.1875 -0.84375 -0.390625q-0.34375 -0.203125 -0.484375 -0.34375q-0.125 -0.140625 -0.203125 -0.359375q-0.0625 -0.21875 -0.0625 -0.578125q0 -0.25 0.015625 -0.421875q0.03125 -0.171875 0.078125 -0.28125q0.046875 -0.109375 0.109375 -0.140625q0.078125 -0.046875 0.171875 -0.046875q0.171875 0 0.46875 0.203125q0.296875 0.203125 0.765625 0.4375q0.46875 0.234375 1.125 0.4375q0.671875 0.203125 1.53125 0.203125q0.65625 0 1.203125 -0.171875q0.546875 -0.1875 0.9375 -0.5q0.390625 -0.328125 0.59375 -0.796875q0.21875 -0.46875 0.21875 -1.0625q0 -0.640625 -0.296875 -1.09375q-0.28125 -0.46875 -0.765625 -0.8125q-0.484375 -0.34375 -1.09375 -0.625q-0.609375 -0.296875 -1.265625 -0.59375q-0.640625 -0.296875 -1.25 -0.65625q-0.609375 -0.375 -1.09375 -0.859375q-0.46875 -0.5 -0.78125 -1.15625q-0.296875 -0.65625 -0.296875 -1.59375q0 -0.9375 0.34375 -1.6875q0.359375 -0.75 0.96875 -1.25q0.609375 -0.5 1.453125 -0.765625q0.859375 -0.265625 1.84375 -0.265625q0.5 0 1.015625 0.09375q0.515625 0.078125 0.953125 0.234375q0.453125 0.140625 0.796875 0.328125q0.359375 0.171875 0.46875 0.296875q0.125 0.109375 0.15625 0.171875q0.03125 0.0625 0.046875 0.171875q0.03125 0.09375 0.046875 0.234375q0.015625 0.140625 0.015625 0.359375q0 0.203125 -0.03125 0.375q-0.015625 0.15625 -0.046875 0.28125q-0.03125 0.109375 -0.09375 0.15625q-0.0625 0.046875 -0.15625 0.046875q-0.125 0 -0.40625 -0.15625q-0.265625 -0.171875 -0.671875 -0.375q-0.390625 -0.203125 -0.9375 -0.375q-0.546875 -0.171875 -1.21875 -0.171875q-0.640625 0 -1.109375 0.171875q-0.46875 0.171875 -0.78125 0.453125q-0.296875 0.28125 -0.453125 0.671875q-0.140625 0.390625 -0.140625 0.8125q0 0.640625 0.28125 1.09375q0.296875 0.453125 0.78125 0.8125q0.484375 0.34375 1.109375 0.640625q0.625 0.296875 1.265625 0.59375q0.640625 0.296875 1.265625 0.65625q0.625 0.359375 1.109375 0.84375q0.484375 0.484375 0.78125 1.15625q0.296875 0.65625 0.296875 1.5625zm4.6054688 3.953125q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -10.546875q0 -0.078125 0.03125 -0.140625q0.046875 -0.078125 0.15625 -0.125q0.109375 -0.046875 0.296875 -0.0625q0.1875 -0.03125 0.46875 -0.03125q0.296875 0 0.484375 0.03125q0.1875 0.015625 0.296875 0.0625q0.109375 0.046875 0.15625 0.125q0.046875 0.0625 0.046875 0.140625l0 10.546875zm0.21875 -14.109375q0 0.6875 -0.265625 0.9375q-0.25 0.234375 -0.9375 0.234375q-0.6875 0 -0.9375 -0.234375q-0.25 -0.25 -0.25 -0.90625q0 -0.6875 0.25 -0.921875q0.265625 -0.25 0.953125 -0.25q0.6875 0 0.9375 0.234375q0.25 0.234375 0.25 0.90625zm18.992188 14.109375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.09375 0.046875 -0.28125 0.0625q-0.1875 0.03125 -0.46875 0.03125q-0.296875 0 -0.484375 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.046875 -0.0625 -0.046875 -0.15625l0 -6.40625q0 -0.671875 -0.125 -1.21875q-0.109375 -0.546875 -0.375 -0.9375q-0.25 -0.40625 -0.65625 -0.609375q-0.390625 -0.21875 -0.9375 -0.21875q-0.671875 0 -1.34375 0.515625q-0.671875 0.515625 -1.484375 1.5l0 7.375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.46875 0.03125q-0.265625 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -6.40625q0 -0.671875 -0.140625 -1.21875q-0.125 -0.546875 -0.390625 -0.9375q-0.25 -0.40625 -0.640625 -0.609375q-0.390625 -0.21875 -0.9375 -0.21875q-0.65625 0 -1.34375 0.515625q-0.671875 0.515625 -1.46875 1.5l0 7.375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -10.546875q0 -0.09375 0.03125 -0.15625q0.03125 -0.0625 0.140625 -0.109375q0.109375 -0.0625 0.265625 -0.078125q0.171875 -0.015625 0.4375 -0.015625q0.265625 0 0.421875 0.015625q0.171875 0.015625 0.265625 0.078125q0.09375 0.046875 0.140625 0.109375q0.046875 0.0625 0.046875 0.15625l0 1.390625q0.890625 -0.984375 1.71875 -1.453125q0.84375 -0.46875 1.703125 -0.46875q0.65625 0 1.171875 0.15625q0.515625 0.15625 0.90625 0.4375q0.40625 0.265625 0.6875 0.65625q0.28125 0.375 0.46875 0.84375q0.53125 -0.578125 1.0 -0.96875q0.484375 -0.40625 0.921875 -0.640625q0.4375 -0.25 0.84375 -0.359375q0.421875 -0.125 0.84375 -0.125q1.03125 0 1.71875 0.359375q0.6875 0.359375 1.109375 0.96875q0.4375 0.59375 0.609375 1.390625q0.1875 0.796875 0.1875 1.6875l0 6.671875zm13.34375 -5.390625q0 1.296875 -0.34375 2.375q-0.34375 1.078125 -1.015625 1.875q-0.671875 0.78125 -1.6875 1.21875q-1.015625 0.4375 -2.34375 0.4375q-1.3125 0 -2.28125 -0.375q-0.953125 -0.390625 -1.609375 -1.125q-0.640625 -0.75 -0.953125 -1.796875q-0.3125 -1.0625 -0.3125 -2.390625q0 -1.296875 0.328125 -2.375q0.328125 -1.09375 1.0 -1.875q0.6875 -0.78125 1.6875 -1.21875q1.015625 -0.4375 2.359375 -0.4375q1.296875 0 2.265625 0.390625q0.96875 0.390625 1.609375 1.125q0.640625 0.734375 0.96875 1.796875q0.328125 1.046875 0.328125 2.375zm-2.046875 0.125q0 -0.84375 -0.15625 -1.609375q-0.15625 -0.765625 -0.53125 -1.328125q-0.359375 -0.578125 -0.984375 -0.90625q-0.609375 -0.34375 -1.53125 -0.34375q-0.859375 0 -1.484375 0.3125q-0.609375 0.296875 -1.015625 0.859375q-0.390625 0.546875 -0.59375 1.3125q-0.1875 0.765625 -0.1875 1.65625q0 0.875 0.15625 1.640625q0.171875 0.75 0.53125 1.328125q0.375 0.5625 0.984375 0.90625q0.625 0.328125 1.5625 0.328125q0.84375 0 1.453125 -0.296875q0.625 -0.3125 1.015625 -0.859375q0.40625 -0.5625 0.59375 -1.3125q0.1875 -0.765625 0.1875 -1.6875zm12.875 5.046875q0.09375 0.15625 0.09375 0.28125q0 0.109375 -0.109375 0.1875q-0.109375 0.0625 -0.34375 0.09375q-0.21875 0.03125 -0.578125 0.03125q-0.359375 0 -0.5625 -0.03125q-0.203125 -0.015625 -0.328125 -0.046875q-0.125 -0.046875 -0.1875 -0.109375q-0.0625 -0.0625 -0.109375 -0.15625l-2.53125 -4.171875l-2.515625 4.171875q-0.046875 0.09375 -0.125 0.15625q-0.0625 0.0625 -0.1875 0.109375q-0.109375 0.03125 -0.3125 0.046875q-0.203125 0.03125 -0.53125 0.03125q-0.34375 0 -0.5625 -0.03125q-0.203125 -0.03125 -0.3125 -0.09375q-0.09375 -0.078125 -0.09375 -0.1875q0.015625 -0.125 0.109375 -0.28125l3.28125 -5.140625l-3.09375 -4.96875q-0.09375 -0.15625 -0.109375 -0.265625q0 -0.109375 0.109375 -0.1875q0.109375 -0.078125 0.328125 -0.09375q0.234375 -0.03125 0.609375 -0.03125q0.34375 0 0.546875 0.015625q0.203125 0.015625 0.3125 0.0625q0.125 0.03125 0.1875 0.09375q0.0625 0.046875 0.109375 0.125l2.40625 3.9375l2.4375 -3.9375q0.046875 -0.0625 0.09375 -0.125q0.0625 -0.0625 0.15625 -0.09375q0.109375 -0.046875 0.28125 -0.0625q0.1875 -0.015625 0.5 -0.015625q0.34375 0 0.5625 0.03125q0.21875 0.015625 0.3125 0.078125q0.109375 0.0625 0.09375 0.1875q0 0.109375 -0.109375 0.28125l-3.078125 4.90625l3.25 5.203125z" fill-rule="nonzero"></path><path fill="#000000" fill-opacity="0.0" d="m699.0384 202.54376l102.86615 0" fill-rule="nonzero"></path><path stroke="#4f81bd" stroke-width="3.0" stroke-linejoin="round" stroke-linecap="butt" d="m717.0384 202.54376l66.86615 0" fill-rule="evenodd"></path><path fill="#4f81bd" stroke="#4f81bd" stroke-width="3.0" stroke-linecap="butt" d="m717.0384 197.58856l-13.614319 4.9552l13.614319 4.9552z" fill-rule="evenodd"></path><path fill="#4f81bd" stroke="#4f81bd" stroke-width="3.0" stroke-linecap="butt" d="m783.90454 207.49896l13.614258 -4.9552l-13.614258 -4.9552z" fill-rule="evenodd"></path><path fill="#000000" fill-opacity="0.0" d="m591.4478 321.91385l0 -85.25986" fill-rule="nonzero"></path><path stroke="#4f81bd" stroke-width="3.0" stroke-linejoin="round" stroke-linecap="butt" d="m591.4478 321.91385l0 -67.25986" fill-rule="evenodd"></path><path fill="#4f81bd" stroke="#4f81bd" stroke-width="3.0" stroke-linecap="butt" d="m596.403 254.65399l-4.9552 -13.614288l-4.9552 13.614288z" fill-rule="evenodd"></path><path fill="#000000" fill-opacity="0.0" d="m591.4478 168.43352l0 -85.25984" fill-rule="nonzero"></path><path stroke="#4f81bd" stroke-width="3.0" stroke-linejoin="round" stroke-linecap="butt" d="m591.4478 168.43352l0 -67.259834" fill-rule="evenodd"></path><path fill="#4f81bd" stroke="#4f81bd" stroke-width="3.0" stroke-linecap="butt" d="m596.403 101.173676l-4.9552 -13.614288l-4.9552 13.614288z" fill-rule="evenodd"></path><defs><linearGradient id="p5.5" gradientUnits="userSpaceOnUse" gradientTransform="matrix(25.952106099960787 0.0 0.0 2.628706594300181 25.490862204724408 14.913346981627297)" spreadMethod="pad" x1="25.95210609996079" y1="25.95210609996079" x2="25.95210609996079" y2="0.0"><stop offset="0.0" stop-color="#bedbff"></stop><stop offset="0.35" stop-color="#d1e5fe"></stop><stop offset="1.0" stop-color="#eef5ff"></stop></linearGradient></defs><path fill="url(#p5.5)" d="m25.490862 14.913347l673.51184 0l0 68.220474l-673.51184 0z" fill-rule="nonzero"></path><path stroke="#4a7dbb" stroke-width="1.0" stroke-linejoin="round" stroke-linecap="butt" d="m25.490862 14.913347l673.51184 0l0 68.220474l-673.51184 0z" fill-rule="nonzero"></path><path fill="#000000" d="m278.49094 56.844833q0.09375 0.265625 0.09375 0.421875q0.015625 0.15625 -0.078125 0.25q-0.09375 0.078125 -0.3125 0.09375q-0.21875 0.03125 -0.578125 0.03125q-0.375 0 -0.59375 -0.03125q-0.203125 -0.015625 -0.328125 -0.046875q-0.109375 -0.046875 -0.15625 -0.109375q-0.046875 -0.078125 -0.09375 -0.1875l-1.3125 -3.6875l-6.296875 0l-1.25 3.640625q-0.03125 0.109375 -0.09375 0.1875q-0.046875 0.078125 -0.171875 0.140625q-0.109375 0.046875 -0.3125 0.0625q-0.203125 0.03125 -0.53125 0.03125q-0.34375 0 -0.5625 -0.03125q-0.203125 -0.03125 -0.296875 -0.109375q-0.09375 -0.09375 -0.09375 -0.25q0.015625 -0.15625 0.109375 -0.421875l5.09375 -14.078125q0.046875 -0.125 0.109375 -0.203125q0.078125 -0.09375 0.21875 -0.140625q0.15625 -0.046875 0.375 -0.0625q0.234375 -0.015625 0.59375 -0.015625q0.375 0 0.609375 0.015625q0.25 0.015625 0.40625 0.0625q0.15625 0.046875 0.234375 0.140625q0.078125 0.078125 0.125 0.21875l5.09375 14.078125zm-6.53125 -12.4375l-0.015625 0l-2.609375 7.5625l5.28125 0l-2.65625 -7.5625zm14.996094 3.0q0 0.265625 -0.015625 0.4375q0 0.171875 -0.046875 0.28125q-0.03125 0.09375 -0.078125 0.15625q-0.046875 0.046875 -0.140625 0.046875q-0.09375 0 -0.234375 -0.046875q-0.140625 -0.0625 -0.3125 -0.109375q-0.15625 -0.0625 -0.375 -0.109375q-0.203125 -0.046875 -0.453125 -0.046875q-0.296875 0 -0.578125 0.125q-0.28125 0.109375 -0.59375 0.390625q-0.3125 0.265625 -0.65625 0.71875q-0.328125 0.4375 -0.734375 1.078125l0 6.9375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -10.546875q0 -0.09375 0.03125 -0.15625q0.03125 -0.0625 0.140625 -0.109375q0.109375 -0.0625 0.265625 -0.078125q0.171875 -0.015625 0.4375 -0.015625q0.265625 0 0.421875 0.015625q0.171875 0.015625 0.265625 0.078125q0.09375 0.046875 0.140625 0.109375q0.046875 0.0625 0.046875 0.15625l0 1.53125q0.421875 -0.625 0.796875 -1.015625q0.390625 -0.40625 0.734375 -0.625q0.34375 -0.234375 0.671875 -0.328125q0.328125 -0.09375 0.671875 -0.09375q0.15625 0 0.34375 0.03125q0.203125 0.015625 0.40625 0.0625q0.21875 0.046875 0.375 0.109375q0.171875 0.046875 0.234375 0.109375q0.078125 0.0625 0.09375 0.109375q0.03125 0.046875 0.046875 0.140625q0.03125 0.078125 0.03125 0.234375q0 0.15625 0 0.421875zm17.851562 9.859375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.09375 0.046875 -0.28125 0.0625q-0.1875 0.03125 -0.46875 0.03125q-0.296875 0 -0.484375 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.046875 -0.0625 -0.046875 -0.15625l0 -6.40625q0 -0.671875 -0.125 -1.21875q-0.109375 -0.546875 -0.375 -0.9375q-0.25 -0.40625 -0.65625 -0.609375q-0.390625 -0.21875 -0.9375 -0.21875q-0.671875 0 -1.34375 0.515625q-0.671875 0.515625 -1.484375 1.5l0 7.375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.46875 0.03125q-0.265625 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -6.40625q0 -0.671875 -0.140625 -1.21875q-0.125 -0.546875 -0.390625 -0.9375q-0.25 -0.40625 -0.640625 -0.609375q-0.390625 -0.21875 -0.9375 -0.21875q-0.65625 0 -1.34375 0.515625q-0.671875 0.515625 -1.46875 1.5l0 7.375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -10.546875q0 -0.09375 0.03125 -0.15625q0.03125 -0.0625 0.140625 -0.109375q0.109375 -0.0625 0.265625 -0.078125q0.171875 -0.015625 0.4375 -0.015625q0.265625 0 0.421875 0.015625q0.171875 0.015625 0.265625 0.078125q0.09375 0.046875 0.140625 0.109375q0.046875 0.0625 0.046875 0.15625l0 1.390625q0.890625 -0.984375 1.71875 -1.453125q0.84375 -0.46875 1.703125 -0.46875q0.65625 0 1.171875 0.15625q0.515625 0.15625 0.90625 0.4375q0.40625 0.265625 0.6875 0.65625q0.28125 0.375 0.46875 0.84375q0.53125 -0.578125 1.0 -0.96875q0.484375 -0.40625 0.921875 -0.640625q0.4375 -0.25 0.84375 -0.359375q0.421875 -0.125 0.84375 -0.125q1.03125 0 1.71875 0.359375q0.6875 0.359375 1.109375 0.96875q0.4375 0.59375 0.609375 1.390625q0.1875 0.796875 0.1875 1.6875l0 6.671875zm11.46875 0.015625q0 0.140625 -0.09375 0.21875q-0.09375 0.0625 -0.265625 0.09375q-0.15625 0.046875 -0.46875 0.046875q-0.296875 0 -0.484375 -0.046875q-0.1875 -0.03125 -0.265625 -0.09375q-0.078125 -0.078125 -0.078125 -0.21875l0 -1.0625q-0.6875 0.75 -1.546875 1.15625q-0.84375 0.40625 -1.796875 0.40625q-0.828125 0 -1.5 -0.21875q-0.671875 -0.21875 -1.15625 -0.625q-0.46875 -0.40625 -0.734375 -1.0q-0.265625 -0.609375 -0.265625 -1.359375q0 -0.890625 0.359375 -1.546875q0.375 -0.65625 1.046875 -1.09375q0.6875 -0.4375 1.671875 -0.65625q0.984375 -0.21875 2.203125 -0.21875l1.453125 0l0 -0.8125q0 -0.609375 -0.125 -1.078125q-0.125 -0.46875 -0.421875 -0.78125q-0.28125 -0.3125 -0.734375 -0.46875q-0.453125 -0.15625 -1.125 -0.15625q-0.71875 0 -1.296875 0.171875q-0.5625 0.171875 -0.984375 0.375q-0.421875 0.203125 -0.71875 0.375q-0.28125 0.171875 -0.421875 0.171875q-0.09375 0 -0.171875 -0.046875q-0.0625 -0.046875 -0.125 -0.140625q-0.046875 -0.09375 -0.078125 -0.234375q-0.015625 -0.15625 -0.015625 -0.328125q0 -0.296875 0.03125 -0.46875q0.046875 -0.171875 0.203125 -0.3125q0.171875 -0.15625 0.546875 -0.359375q0.390625 -0.21875 0.890625 -0.375q0.515625 -0.171875 1.109375 -0.28125q0.59375 -0.125 1.203125 -0.125q1.140625 0 1.9375 0.265625q0.796875 0.25 1.28125 0.75q0.5 0.5 0.71875 1.25q0.21875 0.734375 0.21875 1.71875l0 7.109375zm-1.921875 -4.8125l-1.640625 0q-0.796875 0 -1.390625 0.140625q-0.578125 0.125 -0.96875 0.390625q-0.390625 0.265625 -0.578125 0.640625q-0.171875 0.359375 -0.171875 0.84375q0 0.8125 0.515625 1.296875q0.53125 0.484375 1.46875 0.484375q0.75 0 1.40625 -0.375q0.65625 -0.390625 1.359375 -1.1875l0 -2.234375zm11.636719 -5.0625q0 0.265625 -0.015625 0.4375q0 0.171875 -0.046875 0.28125q-0.03125 0.09375 -0.078125 0.15625q-0.046875 0.046875 -0.140625 0.046875q-0.09375 0 -0.234375 -0.046875q-0.140625 -0.0625 -0.3125 -0.109375q-0.15625 -0.0625 -0.375 -0.109375q-0.203125 -0.046875 -0.453125 -0.046875q-0.296875 0 -0.578125 0.125q-0.28125 0.109375 -0.59375 0.390625q-0.3125 0.265625 -0.65625 0.71875q-0.328125 0.4375 -0.734375 1.078125l0 6.9375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -10.546875q0 -0.09375 0.03125 -0.15625q0.03125 -0.0625 0.140625 -0.109375q0.109375 -0.0625 0.265625 -0.078125q0.171875 -0.015625 0.4375 -0.015625q0.265625 0 0.421875 0.015625q0.171875 0.015625 0.265625 0.078125q0.09375 0.046875 0.140625 0.109375q0.046875 0.0625 0.046875 0.15625l0 1.53125q0.421875 -0.625 0.796875 -1.015625q0.390625 -0.40625 0.734375 -0.625q0.34375 -0.234375 0.671875 -0.328125q0.328125 -0.09375 0.671875 -0.09375q0.15625 0 0.34375 0.03125q0.203125 0.015625 0.40625 0.0625q0.21875 0.046875 0.375 0.109375q0.171875 0.046875 0.234375 0.109375q0.078125 0.0625 0.09375 0.109375q0.03125 0.046875 0.046875 0.140625q0.03125 0.078125 0.03125 0.234375q0 0.15625 0 0.421875zm12.0859375 9.421875q0.15625 0.265625 0.1875 0.421875q0.03125 0.140625 -0.078125 0.234375q-0.109375 0.09375 -0.359375 0.125q-0.234375 0.03125 -0.625 0.03125q-0.375 0 -0.59375 -0.03125q-0.203125 -0.015625 -0.328125 -0.0625q-0.125 -0.046875 -0.1875 -0.109375q-0.0625 -0.0625 -0.109375 -0.171875l-3.375 -6.03125l-3.40625 6.03125q-0.0625 0.109375 -0.140625 0.1875q-0.0625 0.0625 -0.1875 0.109375q-0.125 0.03125 -0.34375 0.046875q-0.203125 0.03125 -0.546875 0.03125q-0.390625 0 -0.625 -0.03125q-0.21875 -0.03125 -0.3125 -0.125q-0.078125 -0.09375 -0.046875 -0.234375q0.03125 -0.15625 0.1875 -0.421875l4.125 -6.96875l-3.9375 -6.734375q-0.140625 -0.265625 -0.1875 -0.421875q-0.046875 -0.15625 0.046875 -0.234375q0.09375 -0.09375 0.328125 -0.109375q0.234375 -0.03125 0.65625 -0.03125q0.34375 0 0.5625 0.015625q0.234375 0.015625 0.359375 0.0625q0.125 0.03125 0.1875 0.109375q0.0625 0.078125 0.125 0.171875l3.265625 5.671875l3.234375 -5.671875q0.046875 -0.09375 0.109375 -0.171875q0.0625 -0.078125 0.171875 -0.109375q0.109375 -0.046875 0.3125 -0.0625q0.203125 -0.015625 0.53125 -0.015625q0.375 0 0.59375 0.03125q0.234375 0.03125 0.328125 0.109375q0.109375 0.078125 0.078125 0.234375q-0.015625 0.15625 -0.15625 0.421875l-3.9375 6.6875l4.09375 7.015625zm18.351562 -1.40625q0 0.1875 -0.015625 0.328125q0 0.140625 -0.03125 0.25q-0.03125 0.09375 -0.078125 0.1875q-0.046875 0.078125 -0.171875 0.203125q-0.109375 0.109375 -0.484375 0.34375q-0.375 0.234375 -0.9375 0.46875q-0.546875 0.234375 -1.28125 0.390625q-0.71875 0.15625 -1.5625 0.15625q-1.484375 0 -2.671875 -0.484375q-1.1875 -0.5 -2.03125 -1.453125q-0.828125 -0.96875 -1.28125 -2.375q-0.453125 -1.421875 -0.453125 -3.265625q0 -1.875 0.484375 -3.34375q0.484375 -1.484375 1.359375 -2.515625q0.890625 -1.03125 2.109375 -1.5625q1.21875 -0.546875 2.71875 -0.546875q0.65625 0 1.265625 0.125q0.625 0.125 1.15625 0.3125q0.53125 0.1875 0.9375 0.4375q0.40625 0.25 0.5625 0.40625q0.15625 0.15625 0.203125 0.234375q0.046875 0.078125 0.078125 0.203125q0.03125 0.109375 0.046875 0.265625q0.015625 0.140625 0.015625 0.359375q0 0.234375 -0.03125 0.40625q-0.015625 0.15625 -0.0625 0.265625q-0.046875 0.109375 -0.109375 0.171875q-0.0625 0.046875 -0.15625 0.046875q-0.15625 0 -0.453125 -0.234375q-0.296875 -0.234375 -0.765625 -0.5q-0.453125 -0.28125 -1.125 -0.5q-0.65625 -0.234375 -1.578125 -0.234375q-1.015625 0 -1.84375 0.40625q-0.8125 0.40625 -1.40625 1.1875q-0.578125 0.78125 -0.90625 1.921875q-0.328125 1.125 -0.328125 2.578125q0 1.4375 0.3125 2.546875q0.3125 1.109375 0.890625 1.859375q0.578125 0.734375 1.421875 1.125q0.84375 0.375 1.921875 0.375q0.890625 0 1.5625 -0.21875q0.6875 -0.234375 1.15625 -0.5q0.46875 -0.28125 0.765625 -0.5q0.3125 -0.21875 0.5 -0.21875q0.078125 0 0.125 0.03125q0.0625 0.03125 0.09375 0.140625q0.046875 0.09375 0.0625 0.265625q0.015625 0.171875 0.015625 0.453125zm12.265625 -3.546875q0 1.296875 -0.34375 2.375q-0.34375 1.078125 -1.015625 1.875q-0.671875 0.78125 -1.6875 1.21875q-1.015625 0.4375 -2.34375 0.4375q-1.3125 0 -2.28125 -0.375q-0.953125 -0.390625 -1.609375 -1.125q-0.640625 -0.75 -0.953125 -1.796875q-0.3125 -1.0625 -0.3125 -2.390625q0 -1.296875 0.328125 -2.375q0.328125 -1.09375 1.0 -1.875q0.6875 -0.78125 1.6875 -1.21875q1.015625 -0.4375 2.359375 -0.4375q1.296875 0 2.265625 0.390625q0.96875 0.390625 1.609375 1.125q0.640625 0.734375 0.96875 1.796875q0.328125 1.046875 0.328125 2.375zm-2.046875 0.125q0 -0.84375 -0.15625 -1.609375q-0.15625 -0.765625 -0.53125 -1.328125q-0.359375 -0.578125 -0.984375 -0.90625q-0.609375 -0.34375 -1.53125 -0.34375q-0.859375 0 -1.484375 0.3125q-0.609375 0.296875 -1.015625 0.859375q-0.390625 0.546875 -0.59375 1.3125q-0.1875 0.765625 -0.1875 1.65625q0 0.875 0.15625 1.640625q0.171875 0.75 0.53125 1.328125q0.375 0.5625 0.984375 0.90625q0.625 0.328125 1.5625 0.328125q0.84375 0 1.453125 -0.296875q0.625 -0.3125 1.015625 -0.859375q0.40625 -0.5625 0.59375 -1.3125q0.1875 -0.765625 0.1875 -1.6875zm20.53125 5.265625q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.09375 0.046875 -0.28125 0.0625q-0.1875 0.03125 -0.46875 0.03125q-0.296875 0 -0.484375 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.046875 -0.0625 -0.046875 -0.15625l0 -6.40625q0 -0.671875 -0.125 -1.21875q-0.109375 -0.546875 -0.375 -0.9375q-0.25 -0.40625 -0.65625 -0.609375q-0.390625 -0.21875 -0.9375 -0.21875q-0.671875 0 -1.34375 0.515625q-0.671875 0.515625 -1.484375 1.5l0 7.375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.46875 0.03125q-0.265625 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -6.40625q0 -0.671875 -0.140625 -1.21875q-0.125 -0.546875 -0.390625 -0.9375q-0.25 -0.40625 -0.640625 -0.609375q-0.390625 -0.21875 -0.9375 -0.21875q-0.65625 0 -1.34375 0.515625q-0.671875 0.515625 -1.46875 1.5l0 7.375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -10.546875q0 -0.09375 0.03125 -0.15625q0.03125 -0.0625 0.140625 -0.109375q0.109375 -0.0625 0.265625 -0.078125q0.171875 -0.015625 0.4375 -0.015625q0.265625 0 0.421875 0.015625q0.171875 0.015625 0.265625 0.078125q0.09375 0.046875 0.140625 0.109375q0.046875 0.0625 0.046875 0.15625l0 1.390625q0.890625 -0.984375 1.71875 -1.453125q0.84375 -0.46875 1.703125 -0.46875q0.65625 0 1.171875 0.15625q0.515625 0.15625 0.90625 0.4375q0.40625 0.265625 0.6875 0.65625q0.28125 0.375 0.46875 0.84375q0.53125 -0.578125 1.0 -0.96875q0.484375 -0.40625 0.921875 -0.640625q0.4375 -0.25 0.84375 -0.359375q0.421875 -0.125 0.84375 -0.125q1.03125 0 1.71875 0.359375q0.6875 0.359375 1.109375 0.96875q0.4375 0.59375 0.609375 1.390625q0.1875 0.796875 0.1875 1.6875l0 6.671875zm13.234375 -5.4375q0 1.390625 -0.296875 2.5q-0.296875 1.09375 -0.890625 1.859375q-0.578125 0.765625 -1.4375 1.1875q-0.84375 0.40625 -1.953125 0.40625q-0.46875 0 -0.875 -0.09375q-0.390625 -0.09375 -0.765625 -0.28125q-0.375 -0.203125 -0.75 -0.5q-0.375 -0.3125 -0.796875 -0.734375l0 5.28125q0 0.09375 -0.046875 0.15625q-0.046875 0.078125 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.046875 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -14.734375q0 -0.109375 0.03125 -0.171875q0.03125 -0.0625 0.140625 -0.109375q0.109375 -0.046875 0.265625 -0.0625q0.171875 -0.015625 0.40625 -0.015625q0.25 0 0.40625 0.015625q0.15625 0.015625 0.25 0.0625q0.109375 0.046875 0.15625 0.109375q0.046875 0.0625 0.046875 0.171875l0 1.421875q0.46875 -0.5 0.90625 -0.859375q0.453125 -0.359375 0.90625 -0.59375q0.453125 -0.25 0.921875 -0.375q0.484375 -0.125 1.015625 -0.125q1.140625 0 1.953125 0.453125q0.8125 0.4375 1.3125 1.21875q0.515625 0.765625 0.75 1.796875q0.234375 1.03125 0.234375 2.171875zm-2.046875 0.21875q0 -0.796875 -0.125 -1.546875q-0.109375 -0.765625 -0.421875 -1.34375q-0.296875 -0.59375 -0.796875 -0.9375q-0.5 -0.359375 -1.25 -0.359375q-0.375 0 -0.75 0.109375q-0.359375 0.109375 -0.734375 0.359375q-0.375 0.234375 -0.78125 0.625q-0.40625 0.390625 -0.859375 0.96875l0 4.1875q0.796875 0.984375 1.5 1.5q0.71875 0.515625 1.5 0.515625q0.734375 0 1.25 -0.34375q0.53125 -0.359375 0.84375 -0.9375q0.328125 -0.59375 0.46875 -1.3125q0.15625 -0.734375 0.15625 -1.484375zm14.765625 -0.171875q0 1.296875 -0.34375 2.375q-0.34375 1.078125 -1.015625 1.875q-0.671875 0.78125 -1.6875 1.21875q-1.015625 0.4375 -2.34375 0.4375q-1.3125 0 -2.28125 -0.375q-0.953125 -0.390625 -1.609375 -1.125q-0.640625 -0.75 -0.953125 -1.796875q-0.3125 -1.0625 -0.3125 -2.390625q0 -1.296875 0.328125 -2.375q0.328125 -1.09375 1.0 -1.875q0.6875 -0.78125 1.6875 -1.21875q1.015625 -0.4375 2.359375 -0.4375q1.296875 0 2.265625 0.390625q0.96875 0.390625 1.609375 1.125q0.640625 0.734375 0.96875 1.796875q0.328125 1.046875 0.328125 2.375zm-2.046875 0.125q0 -0.84375 -0.15625 -1.609375q-0.15625 -0.765625 -0.53125 -1.328125q-0.359375 -0.578125 -0.984375 -0.90625q-0.609375 -0.34375 -1.53125 -0.34375q-0.859375 0 -1.484375 0.3125q-0.609375 0.296875 -1.015625 0.859375q-0.390625 0.546875 -0.59375 1.3125q-0.1875 0.765625 -0.1875 1.65625q0 0.875 0.15625 1.640625q0.171875 0.75 0.53125 1.328125q0.375 0.5625 0.984375 0.90625q0.625 0.328125 1.5625 0.328125q0.84375 0 1.453125 -0.296875q0.625 -0.3125 1.015625 -0.859375q0.40625 -0.5625 0.59375 -1.3125q0.1875 -0.765625 0.1875 -1.6875zm13.96875 5.265625q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.09375 0.046875 -0.28125 0.0625q-0.1875 0.03125 -0.46875 0.03125q-0.296875 0 -0.484375 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.046875 -0.0625 -0.046875 -0.15625l0 -6.171875q0 -0.90625 -0.140625 -1.453125q-0.140625 -0.546875 -0.40625 -0.9375q-0.265625 -0.40625 -0.703125 -0.609375q-0.421875 -0.21875 -0.984375 -0.21875q-0.71875 0 -1.453125 0.515625q-0.71875 0.515625 -1.515625 1.5l0 7.375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -10.546875q0 -0.09375 0.03125 -0.15625q0.03125 -0.0625 0.140625 -0.109375q0.109375 -0.0625 0.265625 -0.078125q0.171875 -0.015625 0.4375 -0.015625q0.265625 0 0.421875 0.015625q0.171875 0.015625 0.265625 0.078125q0.09375 0.046875 0.140625 0.109375q0.046875 0.0625 0.046875 0.15625l0 1.390625q0.890625 -0.984375 1.765625 -1.453125q0.890625 -0.46875 1.796875 -0.46875q1.046875 0 1.765625 0.359375q0.71875 0.359375 1.15625 0.96875q0.453125 0.59375 0.640625 1.390625q0.203125 0.796875 0.203125 1.921875l0 6.4375zm12.53125 -5.734375q0 0.46875 -0.234375 0.65625q-0.21875 0.1875 -0.515625 0.1875l-6.921875 0q0 0.890625 0.171875 1.59375q0.1875 0.703125 0.59375 1.203125q0.40625 0.5 1.0625 0.78125q0.65625 0.265625 1.609375 0.265625q0.75 0 1.328125 -0.125q0.59375 -0.125 1.015625 -0.28125q0.4375 -0.15625 0.703125 -0.265625q0.28125 -0.125 0.421875 -0.125q0.078125 0 0.140625 0.046875q0.078125 0.03125 0.109375 0.109375q0.03125 0.078125 0.046875 0.234375q0.015625 0.140625 0.015625 0.359375q0 0.140625 -0.015625 0.265625q0 0.109375 -0.015625 0.203125q-0.015625 0.078125 -0.0625 0.15625q-0.046875 0.0625 -0.109375 0.125q-0.0625 0.0625 -0.375 0.21875q-0.3125 0.140625 -0.828125 0.28125q-0.5 0.140625 -1.171875 0.25q-0.65625 0.109375 -1.40625 0.109375q-1.296875 0 -2.28125 -0.359375q-0.96875 -0.359375 -1.640625 -1.078125q-0.671875 -0.71875 -1.015625 -1.796875q-0.328125 -1.078125 -0.328125 -2.5q0 -1.359375 0.34375 -2.4375q0.359375 -1.09375 1.015625 -1.84375q0.671875 -0.765625 1.609375 -1.171875q0.9375 -0.40625 2.09375 -0.40625q1.234375 0 2.109375 0.40625q0.875 0.390625 1.4375 1.078125q0.5625 0.671875 0.828125 1.578125q0.265625 0.90625 0.265625 1.9375l0 0.34375zm-1.953125 -0.5625q0.046875 -1.53125 -0.671875 -2.390625q-0.703125 -0.875 -2.09375 -0.875q-0.71875 0 -1.265625 0.28125q-0.53125 0.265625 -0.90625 0.71875q-0.359375 0.4375 -0.5625 1.03125q-0.1875 0.578125 -0.21875 1.234375l5.71875 0zm13.972656 6.296875q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.09375 0.046875 -0.28125 0.0625q-0.1875 0.03125 -0.46875 0.03125q-0.296875 0 -0.484375 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.046875 -0.0625 -0.046875 -0.15625l0 -6.171875q0 -0.90625 -0.140625 -1.453125q-0.140625 -0.546875 -0.40625 -0.9375q-0.265625 -0.40625 -0.703125 -0.609375q-0.421875 -0.21875 -0.984375 -0.21875q-0.71875 0 -1.453125 0.515625q-0.71875 0.515625 -1.515625 1.5l0 7.375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -10.546875q0 -0.09375 0.03125 -0.15625q0.03125 -0.0625 0.140625 -0.109375q0.109375 -0.0625 0.265625 -0.078125q0.171875 -0.015625 0.4375 -0.015625q0.265625 0 0.421875 0.015625q0.171875 0.015625 0.265625 0.078125q0.09375 0.046875 0.140625 0.109375q0.046875 0.0625 0.046875 0.15625l0 1.390625q0.890625 -0.984375 1.765625 -1.453125q0.890625 -0.46875 1.796875 -0.46875q1.046875 0 1.765625 0.359375q0.71875 0.359375 1.15625 0.96875q0.453125 0.59375 0.640625 1.390625q0.203125 0.796875 0.203125 1.921875l0 6.4375zm9.015625 -0.765625q0 0.328125 -0.046875 0.53125q-0.046875 0.203125 -0.140625 0.296875q-0.09375 0.09375 -0.28125 0.1875q-0.1875 0.078125 -0.4375 0.125q-0.234375 0.046875 -0.5 0.078125q-0.265625 0.046875 -0.546875 0.046875q-0.8125 0 -1.40625 -0.21875q-0.578125 -0.21875 -0.953125 -0.65625q-0.375 -0.4375 -0.546875 -1.109375q-0.171875 -0.6875 -0.171875 -1.59375l0 -6.171875l-1.46875 0q-0.1875 0 -0.296875 -0.1875q-0.09375 -0.1875 -0.09375 -0.609375q0 -0.21875 0.03125 -0.359375q0.03125 -0.15625 0.078125 -0.25q0.046875 -0.109375 0.109375 -0.140625q0.078125 -0.046875 0.171875 -0.046875l1.46875 0l0 -2.515625q0 -0.078125 0.03125 -0.140625q0.046875 -0.078125 0.15625 -0.125q0.125 -0.0625 0.3125 -0.078125q0.1875 -0.03125 0.46875 -0.03125q0.28125 0 0.46875 0.03125q0.1875 0.015625 0.296875 0.078125q0.109375 0.046875 0.15625 0.125q0.046875 0.0625 0.046875 0.140625l0 2.515625l2.703125 0q0.09375 0 0.15625 0.046875q0.078125 0.03125 0.125 0.140625q0.0625 0.09375 0.078125 0.25q0.03125 0.140625 0.03125 0.359375q0 0.421875 -0.109375 0.609375q-0.109375 0.1875 -0.28125 0.1875l-2.703125 0l0 5.890625q0 1.09375 0.3125 1.65625q0.328125 0.546875 1.15625 0.546875q0.28125 0 0.484375 -0.046875q0.21875 -0.0625 0.375 -0.109375q0.171875 -0.0625 0.28125 -0.109375q0.125 -0.0625 0.21875 -0.0625q0.046875 0 0.09375 0.03125q0.0625 0.03125 0.09375 0.109375q0.03125 0.078125 0.046875 0.21875q0.03125 0.140625 0.03125 0.359375z" fill-rule="nonzero"></path><defs><linearGradient id="p5.6" gradientUnits="userSpaceOnUse" gradientTransform="matrix(25.952106099960787 0.0 0.0 2.628706594300181 25.490862204724408 458.4161141732284)" spreadMethod="pad" x1="25.95210609996079" y1="25.95210609996079" x2="25.95210609996079" y2="0.0"><stop offset="0.0" stop-color="#ebffbf"></stop><stop offset="0.35" stop-color="#f0ffd3"></stop><stop offset="1.0" stop-color="#f9ffef"></stop></linearGradient></defs><path fill="url(#p5.6)" d="m25.490862 458.4161l673.51184 0l0 68.22049l-673.51184 0z" fill-rule="nonzero"></path><path stroke="#98b954" stroke-width="1.0" stroke-linejoin="round" stroke-linecap="butt" d="m25.490862 458.4161l673.51184 0l0 68.22049l-673.51184 0z" fill-rule="nonzero"></path><path fill="#000000" d="m231.84248 500.75385q0 0.09375 -0.03125 0.171875q-0.03125 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.328125 0.0625q-0.203125 0.03125 -0.5625 0.03125q-0.296875 0 -0.5 -0.03125q-0.1875 -0.015625 -0.3125 -0.0625q-0.109375 -0.0625 -0.171875 -0.15625q-0.0625 -0.09375 -0.109375 -0.234375l-1.390625 -3.578125q-0.25 -0.609375 -0.515625 -1.109375q-0.265625 -0.515625 -0.625 -0.890625q-0.359375 -0.375 -0.859375 -0.578125q-0.484375 -0.203125 -1.1875 -0.203125l-1.34375 0l0 6.453125q0 0.09375 -0.0625 0.171875q-0.046875 0.0625 -0.15625 0.109375q-0.109375 0.046875 -0.3125 0.078125q-0.1875 0.03125 -0.46875 0.03125q-0.296875 0 -0.5 -0.03125q-0.1875 -0.03125 -0.3125 -0.078125q-0.109375 -0.046875 -0.15625 -0.109375q-0.046875 -0.078125 -0.046875 -0.171875l0 -14.03125q0 -0.453125 0.234375 -0.640625q0.25 -0.1875 0.515625 -0.1875l3.21875 0q0.578125 0 0.953125 0.03125q0.390625 0.03125 0.6875 0.0625q0.890625 0.15625 1.5625 0.484375q0.671875 0.328125 1.125 0.84375q0.453125 0.5 0.6875 1.15625q0.234375 0.640625 0.234375 1.421875q0 0.765625 -0.21875 1.375q-0.203125 0.59375 -0.59375 1.0625q-0.375 0.453125 -0.921875 0.796875q-0.53125 0.34375 -1.203125 0.578125q0.375 0.15625 0.671875 0.421875q0.3125 0.25 0.578125 0.609375q0.265625 0.34375 0.5 0.796875q0.234375 0.453125 0.46875 1.03125l1.359375 3.34375q0.15625 0.421875 0.203125 0.59375q0.046875 0.15625 0.046875 0.25zm-3.03125 -10.640625q0 -0.890625 -0.40625 -1.5q-0.390625 -0.625 -1.328125 -0.890625q-0.296875 -0.09375 -0.671875 -0.125q-0.359375 -0.03125 -0.953125 -0.03125l-1.703125 0l0 5.109375l1.96875 0q0.796875 0 1.375 -0.1875q0.578125 -0.203125 0.96875 -0.546875q0.390625 -0.34375 0.5625 -0.8125q0.1875 -0.46875 0.1875 -1.015625zm15.546875 5.265625q0 1.296875 -0.34375 2.375q-0.34375 1.078125 -1.015625 1.875q-0.671875 0.78125 -1.6875 1.21875q-1.015625 0.4375 -2.34375 0.4375q-1.3125 0 -2.28125 -0.375q-0.953125 -0.390625 -1.609375 -1.125q-0.640625 -0.75 -0.953125 -1.796875q-0.3125 -1.0625 -0.3125 -2.390625q0 -1.296875 0.328125 -2.375q0.328125 -1.09375 1.0 -1.875q0.6875 -0.78125 1.6875 -1.21875q1.015625 -0.4375 2.359375 -0.4375q1.296875 0 2.265625 0.390625q0.96875 0.390625 1.609375 1.125q0.640625 0.734375 0.96875 1.796875q0.328125 1.046875 0.328125 2.375zm-2.046875 0.125q0 -0.84375 -0.15625 -1.609375q-0.15625 -0.765625 -0.53125 -1.328125q-0.359375 -0.578125 -0.984375 -0.90625q-0.609375 -0.34375 -1.53125 -0.34375q-0.859375 0 -1.484375 0.3125q-0.609375 0.296875 -1.015625 0.859375q-0.390625 0.546875 -0.59375 1.3125q-0.1875 0.765625 -0.1875 1.65625q0 0.875 0.15625 1.640625q0.171875 0.75 0.53125 1.328125q0.375 0.5625 0.984375 0.90625q0.625 0.328125 1.5625 0.328125q0.84375 0 1.453125 -0.296875q0.625 -0.3125 1.015625 -0.859375q0.40625 -0.5625 0.59375 -1.3125q0.1875 -0.765625 0.1875 -1.6875zm14.593765 -0.140625q0 1.359375 -0.296875 2.46875q-0.296875 1.09375 -0.89064026 1.875q-0.578125 0.765625 -1.421875 1.171875q-0.84375 0.40625 -1.921875 0.40625q-0.515625 0 -0.9375 -0.09375q-0.421875 -0.09375 -0.84375 -0.3125q-0.40625 -0.234375 -0.8125 -0.578125q-0.40625 -0.34375 -0.875 -0.8125l0 1.28125q0 0.09375 -0.046875 0.171875q-0.046875 0.0625 -0.15625 0.109375q-0.09375 0.046875 -0.25 0.0625q-0.15625 0.03125 -0.40625 0.03125q-0.234375 0 -0.40625 -0.03125q-0.15625 -0.015625 -0.265625 -0.0625q-0.109375 -0.046875 -0.140625 -0.109375q-0.03125 -0.078125 -0.03125 -0.171875l0 -15.65625q0 -0.09375 0.03125 -0.15625q0.046875 -0.078125 0.15625 -0.125q0.109375 -0.046875 0.296875 -0.0625q0.1875 -0.03125 0.46875 -0.03125q0.296875 0 0.484375 0.03125q0.1875 0.015625 0.296875 0.0625q0.109375 0.046875 0.15625 0.125q0.046875 0.0625 0.046875 0.15625l0 6.3125q0.46875 -0.46875 0.90625 -0.796875q0.4375 -0.328125 0.859375 -0.53125q0.421875 -0.21875 0.84375 -0.3125q0.421875 -0.09375 0.890625 -0.09375q1.140625 0 1.953125 0.46875q0.828125 0.453125 1.328125 1.21875q0.51564026 0.765625 0.75001526 1.796875q0.234375 1.03125 0.234375 2.1875zm-2.0468903 0.21875q0 -0.8125 -0.125 -1.5625q-0.109375 -0.765625 -0.421875 -1.34375q-0.296875 -0.59375 -0.8125 -0.953125q-0.5 -0.359375 -1.25 -0.359375q-0.375 0 -0.734375 0.109375q-0.359375 0.09375 -0.734375 0.34375q-0.375 0.25 -0.78125 0.640625q-0.40625 0.375 -0.859375 0.96875l0 4.203125q0.796875 0.96875 1.515625 1.484375q0.734375 0.515625 1.515625 0.515625q0.71875 0 1.234375 -0.34375q0.515625 -0.359375 0.84375 -0.9375q0.328125 -0.59375 0.46875 -1.3125q0.140625 -0.71875 0.140625 -1.453125zm14.76564 -0.203125q0 1.296875 -0.34375 2.375q-0.34375 1.078125 -1.015625 1.875q-0.671875 0.78125 -1.6875 1.21875q-1.015625 0.4375 -2.34375 0.4375q-1.3125 0 -2.28125 -0.375q-0.953125 -0.390625 -1.609375 -1.125q-0.640625 -0.75 -0.953125 -1.796875q-0.3125 -1.0625 -0.3125 -2.390625q0 -1.296875 0.328125 -2.375q0.328125 -1.09375 1.0 -1.875q0.6875 -0.78125 1.6875 -1.21875q1.015625 -0.4375 2.359375 -0.4375q1.296875 0 2.265625 0.390625q0.96875 0.390625 1.609375 1.125q0.640625 0.734375 0.96875 1.796875q0.328125 1.046875 0.328125 2.375zm-2.046875 0.125q0 -0.84375 -0.15625 -1.609375q-0.15625 -0.765625 -0.53125 -1.328125q-0.359375 -0.578125 -0.984375 -0.90625q-0.609375 -0.34375 -1.53125 -0.34375q-0.859375 0 -1.484375 0.3125q-0.609375 0.296875 -1.015625 0.859375q-0.390625 0.546875 -0.59375 1.3125q-0.1875 0.765625 -0.1875 1.65625q0 0.875 0.15625 1.640625q0.171875 0.75 0.53125 1.328125q0.375 0.5625 0.984375 0.90625q0.625 0.328125 1.5625 0.328125q0.84375 0 1.453125 -0.296875q0.625 -0.3125 1.015625 -0.859375q0.40625 -0.5625 0.59375 -1.3125q0.1875 -0.765625 0.1875 -1.6875zm10.375 4.5q0 0.328125 -0.046875 0.53125q-0.046875 0.203125 -0.140625 0.296875q-0.09375 0.09375 -0.28125 0.1875q-0.1875 0.078125 -0.4375 0.125q-0.234375 0.046875 -0.5 0.078125q-0.265625 0.046875 -0.546875 0.046875q-0.8125 0 -1.40625 -0.21875q-0.578125 -0.21875 -0.953125 -0.65625q-0.375 -0.4375 -0.546875 -1.109375q-0.171875 -0.6875 -0.171875 -1.59375l0 -6.171875l-1.46875 0q-0.1875 0 -0.296875 -0.1875q-0.09375 -0.1875 -0.09375 -0.609375q0 -0.21875 0.03125 -0.359375q0.03125 -0.15625 0.078125 -0.25q0.046875 -0.109375 0.109375 -0.140625q0.078125 -0.046875 0.171875 -0.046875l1.46875 0l0 -2.515625q0 -0.078125 0.03125 -0.140625q0.046875 -0.078125 0.15625 -0.125q0.125 -0.0625 0.3125 -0.078125q0.1875 -0.03125 0.46875 -0.03125q0.28125 0 0.46875 0.03125q0.1875 0.015625 0.296875 0.078125q0.109375 0.046875 0.15625 0.125q0.046875 0.0625 0.046875 0.140625l0 2.515625l2.703125 0q0.09375 0 0.15625 0.046875q0.078125 0.03125 0.125 0.140625q0.0625 0.09375 0.078125 0.25q0.03125 0.140625 0.03125 0.359375q0 0.421875 -0.109375 0.609375q-0.109375 0.1875 -0.28125 0.1875l-2.703125 0l0 5.890625q0 1.09375 0.3125 1.65625q0.328125 0.546875 1.15625 0.546875q0.28125 0 0.484375 -0.046875q0.21875 -0.0625 0.375 -0.109375q0.171875 -0.0625 0.28125 -0.109375q0.125 -0.0625 0.21875 -0.0625q0.046875 0 0.09375 0.03125q0.0625 0.03125 0.09375 0.109375q0.03125 0.078125 0.046875 0.21875q0.03125 0.140625 0.03125 0.359375zm19.121094 0.75q0 0.09375 -0.046875 0.171875q-0.046875 0.0625 -0.171875 0.109375q-0.109375 0.046875 -0.3125 0.078125q-0.1875 0.03125 -0.46875 0.03125q-0.296875 0 -0.484375 -0.03125q-0.1875 -0.03125 -0.3125 -0.078125q-0.109375 -0.046875 -0.15625 -0.109375q-0.046875 -0.078125 -0.046875 -0.171875l0 -6.71875l-6.90625 0l0 6.71875q0 0.09375 -0.046875 0.171875q-0.046875 0.0625 -0.171875 0.109375q-0.109375 0.046875 -0.3125 0.078125q-0.1875 0.03125 -0.46875 0.03125q-0.28125 0 -0.484375 -0.03125q-0.203125 -0.03125 -0.328125 -0.078125q-0.109375 -0.046875 -0.15625 -0.109375q-0.046875 -0.078125 -0.046875 -0.171875l0 -14.546875q0 -0.09375 0.046875 -0.15625q0.046875 -0.078125 0.15625 -0.109375q0.125 -0.046875 0.328125 -0.078125q0.203125 -0.03125 0.484375 -0.03125q0.28125 0 0.46875 0.03125q0.203125 0.03125 0.3125 0.078125q0.125 0.03125 0.171875 0.109375q0.046875 0.0625 0.046875 0.15625l0 6.0625l6.90625 0l0 -6.0625q0 -0.09375 0.046875 -0.15625q0.046875 -0.078125 0.15625 -0.109375q0.125 -0.046875 0.3125 -0.078125q0.1875 -0.03125 0.484375 -0.03125q0.28125 0 0.46875 0.03125q0.203125 0.03125 0.3125 0.078125q0.125 0.03125 0.171875 0.109375q0.046875 0.0625 0.046875 0.15625l0 14.546875zm11.75 0.03125q0 0.140625 -0.09375 0.21875q-0.09375 0.0625 -0.265625 0.09375q-0.15625 0.046875 -0.46875 0.046875q-0.296875 0 -0.484375 -0.046875q-0.1875 -0.03125 -0.265625 -0.09375q-0.078125 -0.078125 -0.078125 -0.21875l0 -1.0625q-0.6875 0.75 -1.546875 1.15625q-0.84375 0.40625 -1.796875 0.40625q-0.828125 0 -1.5 -0.21875q-0.671875 -0.21875 -1.15625 -0.625q-0.46875 -0.40625 -0.734375 -1.0q-0.265625 -0.609375 -0.265625 -1.359375q0 -0.890625 0.359375 -1.546875q0.375 -0.65625 1.046875 -1.09375q0.6875 -0.4375 1.671875 -0.65625q0.984375 -0.21875 2.203125 -0.21875l1.453125 0l0 -0.8125q0 -0.609375 -0.125 -1.078125q-0.125 -0.46875 -0.421875 -0.78125q-0.28125 -0.3125 -0.734375 -0.46875q-0.453125 -0.15625 -1.125 -0.15625q-0.71875 0 -1.296875 0.171875q-0.5625 0.171875 -0.984375 0.375q-0.421875 0.203125 -0.71875 0.375q-0.28125 0.171875 -0.421875 0.171875q-0.09375 0 -0.171875 -0.046875q-0.0625 -0.046875 -0.125 -0.140625q-0.046875 -0.09375 -0.078125 -0.234375q-0.015625 -0.15625 -0.015625 -0.328125q0 -0.296875 0.03125 -0.46875q0.046875 -0.171875 0.203125 -0.3125q0.171875 -0.15625 0.546875 -0.359375q0.390625 -0.21875 0.890625 -0.375q0.515625 -0.171875 1.109375 -0.28125q0.59375 -0.125 1.203125 -0.125q1.140625 0 1.9375 0.265625q0.796875 0.25 1.28125 0.75q0.5 0.5 0.71875 1.25q0.21875 0.734375 0.21875 1.71875l0 7.109375zm-1.921875 -4.8125l-1.640625 0q-0.796875 0 -1.390625 0.140625q-0.578125 0.125 -0.96875 0.390625q-0.390625 0.265625 -0.578125 0.640625q-0.171875 0.359375 -0.171875 0.84375q0 0.8125 0.515625 1.296875q0.53125 0.484375 1.46875 0.484375q0.75 0 1.40625 -0.375q0.65625 -0.390625 1.359375 -1.1875l0 -2.234375zm11.636719 -5.0625q0 0.265625 -0.015625 0.4375q0 0.171875 -0.046875 0.28125q-0.03125 0.09375 -0.078125 0.15625q-0.046875 0.046875 -0.140625 0.046875q-0.09375 0 -0.234375 -0.046875q-0.140625 -0.0625 -0.3125 -0.109375q-0.15625 -0.0625 -0.375 -0.109375q-0.203125 -0.046875 -0.453125 -0.046875q-0.296875 0 -0.578125 0.125q-0.28125 0.109375 -0.59375 0.390625q-0.3125 0.265625 -0.65625 0.71875q-0.328125 0.4375 -0.734375 1.078125l0 6.9375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -10.546875q0 -0.09375 0.03125 -0.15625q0.03125 -0.0625 0.140625 -0.109375q0.109375 -0.0625 0.265625 -0.078125q0.171875 -0.015625 0.4375 -0.015625q0.265625 0 0.421875 0.015625q0.171875 0.015625 0.265625 0.078125q0.09375 0.046875 0.140625 0.109375q0.046875 0.0625 0.046875 0.15625l0 1.53125q0.421875 -0.625 0.796875 -1.015625q0.390625 -0.40625 0.734375 -0.625q0.34375 -0.234375 0.671875 -0.328125q0.328125 -0.09375 0.671875 -0.09375q0.15625 0 0.34375 0.03125q0.203125 0.015625 0.40625 0.0625q0.21875 0.046875 0.375 0.109375q0.171875 0.046875 0.234375 0.109375q0.078125 0.0625 0.09375 0.109375q0.03125 0.046875 0.046875 0.140625q0.03125 0.078125 0.03125 0.234375q0 0.15625 0 0.421875zm11.2421875 9.859375q0 0.09375 -0.046875 0.171875q-0.03125 0.0625 -0.140625 0.109375q-0.09375 0.046875 -0.265625 0.0625q-0.15625 0.03125 -0.390625 0.03125q-0.25 0 -0.421875 -0.03125q-0.15625 -0.015625 -0.265625 -0.0625q-0.09375 -0.046875 -0.140625 -0.109375q-0.046875 -0.078125 -0.046875 -0.171875l0 -1.390625q-0.828125 0.90625 -1.734375 1.40625q-0.890625 0.5 -1.953125 0.5q-1.171875 0 -2.0 -0.453125q-0.8125 -0.453125 -1.328125 -1.21875q-0.5 -0.765625 -0.734375 -1.796875q-0.234375 -1.046875 -0.234375 -2.1875q0 -1.359375 0.296875 -2.453125q0.296875 -1.09375 0.859375 -1.859375q0.578125 -0.78125 1.421875 -1.203125q0.859375 -0.421875 1.96875 -0.421875q0.921875 0 1.6875 0.40625q0.78125 0.40625 1.53125 1.1875l0 -6.125q0 -0.078125 0.03125 -0.15625q0.046875 -0.078125 0.15625 -0.109375q0.125 -0.046875 0.296875 -0.078125q0.1875 -0.03125 0.46875 -0.03125q0.296875 0 0.484375 0.03125q0.1875 0.03125 0.28125 0.078125q0.109375 0.03125 0.15625 0.109375q0.0625 0.078125 0.0625 0.15625l0 15.609375zm-1.9375 -7.421875q-0.796875 -0.96875 -1.53125 -1.46875q-0.71875 -0.515625 -1.515625 -0.515625q-0.75 0 -1.265625 0.359375q-0.515625 0.34375 -0.84375 0.921875q-0.3125 0.5625 -0.46875 1.296875q-0.140625 0.71875 -0.140625 1.46875q0 0.796875 0.125 1.5625q0.125 0.765625 0.421875 1.359375q0.3125 0.59375 0.8125 0.953125q0.515625 0.34375 1.265625 0.34375q0.390625 0 0.75 -0.09375q0.359375 -0.109375 0.734375 -0.359375q0.375 -0.25 0.78125 -0.640625q0.40625 -0.390625 0.875 -0.96875l0 -4.21875zm20.265625 -3.140625q0 0.078125 -0.03125 0.203125q-0.015625 0.109375 -0.078125 0.28125l-3.09375 10.015625q-0.046875 0.140625 -0.125 0.21875q-0.0625 0.078125 -0.203125 0.125q-0.140625 0.046875 -0.375 0.0625q-0.234375 0.03125 -0.578125 0.03125q-0.359375 0 -0.609375 -0.03125q-0.25 -0.015625 -0.40625 -0.0625q-0.140625 -0.0625 -0.21875 -0.140625q-0.0625 -0.078125 -0.09375 -0.203125l-2.21875 -7.640625l-0.015625 -0.109375l-0.03125 0.109375l-2.046875 7.640625q-0.03125 0.140625 -0.109375 0.21875q-0.078125 0.078125 -0.234375 0.125q-0.140625 0.046875 -0.390625 0.0625q-0.234375 0.03125 -0.59375 0.03125q-0.359375 0 -0.59375 -0.03125q-0.21875 -0.015625 -0.375 -0.0625q-0.140625 -0.0625 -0.21875 -0.140625q-0.0625 -0.078125 -0.09375 -0.203125l-3.078125 -10.015625q-0.0625 -0.171875 -0.09375 -0.28125q-0.015625 -0.125 -0.015625 -0.203125q0 -0.109375 0.046875 -0.171875q0.046875 -0.0625 0.15625 -0.109375q0.109375 -0.046875 0.296875 -0.046875q0.1875 -0.015625 0.453125 -0.015625q0.328125 0 0.53125 0.015625q0.203125 0.015625 0.296875 0.0625q0.109375 0.03125 0.15625 0.109375q0.046875 0.078125 0.09375 0.1875l2.53125 8.6875l0.03125 0.109375l0.015625 -0.109375l2.34375 -8.6875q0.015625 -0.109375 0.0625 -0.1875q0.0625 -0.078125 0.15625 -0.109375q0.109375 -0.046875 0.296875 -0.0625q0.1875 -0.015625 0.46875 -0.015625q0.28125 0 0.46875 0.015625q0.1875 0.015625 0.28125 0.0625q0.109375 0.03125 0.15625 0.109375q0.046875 0.0625 0.078125 0.15625l2.515625 8.71875l0.015625 0.109375l0.015625 -0.109375l2.515625 -8.6875q0.015625 -0.109375 0.0625 -0.1875q0.0625 -0.078125 0.171875 -0.109375q0.109375 -0.046875 0.296875 -0.0625q0.203125 -0.015625 0.5 -0.015625q0.28125 0 0.453125 0.015625q0.171875 0 0.265625 0.046875q0.109375 0.046875 0.140625 0.109375q0.046875 0.0625 0.046875 0.171875zm10.34375 10.578125q0 0.140625 -0.09375 0.21875q-0.09375 0.0625 -0.265625 0.09375q-0.15625 0.046875 -0.46875 0.046875q-0.296875 0 -0.484375 -0.046875q-0.1875 -0.03125 -0.265625 -0.09375q-0.078125 -0.078125 -0.078125 -0.21875l0 -1.0625q-0.6875 0.75 -1.546875 1.15625q-0.84375 0.40625 -1.796875 0.40625q-0.828125 0 -1.5 -0.21875q-0.671875 -0.21875 -1.15625 -0.625q-0.46875 -0.40625 -0.734375 -1.0q-0.265625 -0.609375 -0.265625 -1.359375q0 -0.890625 0.359375 -1.546875q0.375 -0.65625 1.046875 -1.09375q0.6875 -0.4375 1.671875 -0.65625q0.984375 -0.21875 2.203125 -0.21875l1.453125 0l0 -0.8125q0 -0.609375 -0.125 -1.078125q-0.125 -0.46875 -0.421875 -0.78125q-0.28125 -0.3125 -0.734375 -0.46875q-0.453125 -0.15625 -1.125 -0.15625q-0.71875 0 -1.296875 0.171875q-0.5625 0.171875 -0.984375 0.375q-0.421875 0.203125 -0.71875 0.375q-0.28125 0.171875 -0.421875 0.171875q-0.09375 0 -0.171875 -0.046875q-0.0625 -0.046875 -0.125 -0.140625q-0.046875 -0.09375 -0.078125 -0.234375q-0.015625 -0.15625 -0.015625 -0.328125q0 -0.296875 0.03125 -0.46875q0.046875 -0.171875 0.203125 -0.3125q0.171875 -0.15625 0.546875 -0.359375q0.390625 -0.21875 0.890625 -0.375q0.515625 -0.171875 1.109375 -0.28125q0.59375 -0.125 1.203125 -0.125q1.140625 0 1.9375 0.265625q0.796875 0.25 1.28125 0.75q0.5 0.5 0.71875 1.25q0.21875 0.734375 0.21875 1.71875l0 7.109375zm-1.921875 -4.8125l-1.640625 0q-0.796875 0 -1.390625 0.140625q-0.578125 0.125 -0.96875 0.390625q-0.390625 0.265625 -0.578125 0.640625q-0.171875 0.359375 -0.171875 0.84375q0 0.8125 0.515625 1.296875q0.53125 0.484375 1.46875 0.484375q0.75 0 1.40625 -0.375q0.65625 -0.390625 1.359375 -1.1875l0 -2.234375zm11.636719 -5.0625q0 0.265625 -0.015625 0.4375q0 0.171875 -0.046875 0.28125q-0.03125 0.09375 -0.078125 0.15625q-0.046875 0.046875 -0.140625 0.046875q-0.09375 0 -0.234375 -0.046875q-0.140625 -0.0625 -0.3125 -0.109375q-0.15625 -0.0625 -0.375 -0.109375q-0.203125 -0.046875 -0.453125 -0.046875q-0.296875 0 -0.578125 0.125q-0.28125 0.109375 -0.59375 0.390625q-0.3125 0.265625 -0.65625 0.71875q-0.328125 0.4375 -0.734375 1.078125l0 6.9375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -10.546875q0 -0.09375 0.03125 -0.15625q0.03125 -0.0625 0.140625 -0.109375q0.109375 -0.0625 0.265625 -0.078125q0.171875 -0.015625 0.4375 -0.015625q0.265625 0 0.421875 0.015625q0.171875 0.015625 0.265625 0.078125q0.09375 0.046875 0.140625 0.109375q0.046875 0.0625 0.046875 0.15625l0 1.53125q0.421875 -0.625 0.796875 -1.015625q0.390625 -0.40625 0.734375 -0.625q0.34375 -0.234375 0.671875 -0.328125q0.328125 -0.09375 0.671875 -0.09375q0.15625 0 0.34375 0.03125q0.203125 0.015625 0.40625 0.0625q0.21875 0.046875 0.375 0.109375q0.171875 0.046875 0.234375 0.109375q0.078125 0.0625 0.09375 0.109375q0.03125 0.046875 0.046875 0.140625q0.03125 0.078125 0.03125 0.234375q0 0.15625 0 0.421875zm11.2109375 4.125q0 0.46875 -0.234375 0.65625q-0.21875 0.1875 -0.515625 0.1875l-6.921875 0q0 0.890625 0.171875 1.59375q0.1875 0.703125 0.59375 1.203125q0.40625 0.5 1.0625 0.78125q0.65625 0.265625 1.609375 0.265625q0.75 0 1.328125 -0.125q0.59375 -0.125 1.015625 -0.28125q0.4375 -0.15625 0.703125 -0.265625q0.28125 -0.125 0.421875 -0.125q0.078125 0 0.140625 0.046875q0.078125 0.03125 0.109375 0.109375q0.03125 0.078125 0.046875 0.234375q0.015625 0.140625 0.015625 0.359375q0 0.140625 -0.015625 0.265625q0 0.109375 -0.015625 0.203125q-0.015625 0.078125 -0.0625 0.15625q-0.046875 0.0625 -0.109375 0.125q-0.0625 0.0625 -0.375 0.21875q-0.3125 0.140625 -0.828125 0.28125q-0.5 0.140625 -1.171875 0.25q-0.65625 0.109375 -1.40625 0.109375q-1.296875 0 -2.28125 -0.359375q-0.96875 -0.359375 -1.640625 -1.078125q-0.671875 -0.71875 -1.015625 -1.796875q-0.328125 -1.078125 -0.328125 -2.5q0 -1.359375 0.34375 -2.4375q0.359375 -1.09375 1.015625 -1.84375q0.671875 -0.765625 1.609375 -1.171875q0.9375 -0.40625 2.09375 -0.40625q1.234375 0 2.109375 0.40625q0.875 0.390625 1.4375 1.078125q0.5625 0.671875 0.828125 1.578125q0.265625 0.90625 0.265625 1.9375l0 0.34375zm-1.953125 -0.5625q0.046875 -1.53125 -0.671875 -2.390625q-0.703125 -0.875 -2.09375 -0.875q-0.71875 0 -1.265625 0.28125q-0.53125 0.265625 -0.90625 0.71875q-0.359375 0.4375 -0.5625 1.03125q-0.1875 0.578125 -0.21875 1.234375l5.71875 0zm10.4921875 9.421875q-0.046875 0.15625 -0.125 0.234375q-0.078125 0.09375 -0.203125 0.140625q-0.109375 0.046875 -0.28125 0.0625q-0.15625 0.03125 -0.40625 0.03125q-0.296875 0 -0.5 -0.046875q-0.1875 -0.03125 -0.296875 -0.109375q-0.09375 -0.078125 -0.125 -0.1875q-0.015625 -0.109375 0.046875 -0.265625l7.09375 -19.453125q0.046875 -0.140625 0.125 -0.234375q0.078125 -0.09375 0.1875 -0.140625q0.109375 -0.046875 0.28125 -0.0625q0.1875 -0.03125 0.421875 -0.03125q0.296875 0 0.484375 0.046875q0.1875 0.046875 0.296875 0.125q0.109375 0.0625 0.125 0.1875q0.03125 0.109375 -0.03125 0.25l-7.09375 19.453125zm22.882812 -7.078125q0 1.0625 -0.390625 1.890625q-0.390625 0.828125 -1.09375 1.421875q-0.6875 0.578125 -1.640625 0.875q-0.9375 0.28125 -2.03125 0.28125q-0.75 0 -1.40625 -0.125q-0.65625 -0.125 -1.171875 -0.3125q-0.5 -0.1875 -0.84375 -0.390625q-0.34375 -0.203125 -0.484375 -0.34375q-0.125 -0.140625 -0.203125 -0.359375q-0.0625 -0.21875 -0.0625 -0.578125q0 -0.25 0.015625 -0.421875q0.03125 -0.171875 0.078125 -0.28125q0.046875 -0.109375 0.109375 -0.140625q0.078125 -0.046875 0.171875 -0.046875q0.171875 0 0.46875 0.203125q0.296875 0.203125 0.765625 0.4375q0.46875 0.234375 1.125 0.4375q0.671875 0.203125 1.53125 0.203125q0.65625 0 1.203125 -0.171875q0.546875 -0.1875 0.9375 -0.5q0.390625 -0.328125 0.59375 -0.796875q0.21875 -0.46875 0.21875 -1.0625q0 -0.640625 -0.296875 -1.09375q-0.28125 -0.46875 -0.765625 -0.8125q-0.484375 -0.34375 -1.09375 -0.625q-0.609375 -0.296875 -1.265625 -0.59375q-0.640625 -0.296875 -1.25 -0.65625q-0.609375 -0.375 -1.09375 -0.859375q-0.46875 -0.5 -0.78125 -1.15625q-0.296875 -0.65625 -0.296875 -1.59375q0 -0.9375 0.34375 -1.6875q0.359375 -0.75 0.96875 -1.25q0.609375 -0.5 1.453125 -0.765625q0.859375 -0.265625 1.84375 -0.265625q0.5 0 1.015625 0.09375q0.515625 0.078125 0.953125 0.234375q0.453125 0.140625 0.796875 0.328125q0.359375 0.171875 0.46875 0.296875q0.125 0.109375 0.15625 0.171875q0.03125 0.0625 0.046875 0.171875q0.03125 0.09375 0.046875 0.234375q0.015625 0.140625 0.015625 0.359375q0 0.203125 -0.03125 0.375q-0.015625 0.15625 -0.046875 0.28125q-0.03125 0.109375 -0.09375 0.15625q-0.0625 0.046875 -0.15625 0.046875q-0.125 0 -0.40625 -0.15625q-0.265625 -0.171875 -0.671875 -0.375q-0.390625 -0.203125 -0.9375 -0.375q-0.546875 -0.171875 -1.21875 -0.171875q-0.640625 0 -1.109375 0.171875q-0.46875 0.171875 -0.78125 0.453125q-0.296875 0.28125 -0.453125 0.671875q-0.140625 0.390625 -0.140625 0.8125q0 0.640625 0.28125 1.09375q0.296875 0.453125 0.78125 0.8125q0.484375 0.34375 1.109375 0.640625q0.625 0.296875 1.265625 0.59375q0.640625 0.296875 1.265625 0.65625q0.625 0.359375 1.109375 0.84375q0.484375 0.484375 0.78125 1.15625q0.296875 0.65625 0.296875 1.5625zm4.6054688 3.953125q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -10.546875q0 -0.078125 0.03125 -0.140625q0.046875 -0.078125 0.15625 -0.125q0.109375 -0.046875 0.296875 -0.0625q0.1875 -0.03125 0.46875 -0.03125q0.296875 0 0.484375 0.03125q0.1875 0.015625 0.296875 0.0625q0.109375 0.046875 0.15625 0.125q0.046875 0.0625 0.046875 0.140625l0 10.546875zm0.21875 -14.109375q0 0.6875 -0.265625 0.9375q-0.25 0.234375 -0.9375 0.234375q-0.6875 0 -0.9375 -0.234375q-0.25 -0.25 -0.25 -0.90625q0 -0.6875 0.25 -0.921875q0.265625 -0.25 0.953125 -0.25q0.6875 0 0.9375 0.234375q0.25 0.234375 0.25 0.90625zm18.992188 14.109375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.09375 0.046875 -0.28125 0.0625q-0.1875 0.03125 -0.46875 0.03125q-0.296875 0 -0.484375 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.046875 -0.0625 -0.046875 -0.15625l0 -6.40625q0 -0.671875 -0.125 -1.21875q-0.109375 -0.546875 -0.375 -0.9375q-0.25 -0.40625 -0.65625 -0.609375q-0.390625 -0.21875 -0.9375 -0.21875q-0.671875 0 -1.34375 0.515625q-0.671875 0.515625 -1.484375 1.5l0 7.375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.46875 0.03125q-0.265625 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -6.40625q0 -0.671875 -0.140625 -1.21875q-0.125 -0.546875 -0.390625 -0.9375q-0.25 -0.40625 -0.640625 -0.609375q-0.390625 -0.21875 -0.9375 -0.21875q-0.65625 0 -1.34375 0.515625q-0.671875 0.515625 -1.46875 1.5l0 7.375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -10.546875q0 -0.09375 0.03125 -0.15625q0.03125 -0.0625 0.140625 -0.109375q0.109375 -0.0625 0.265625 -0.078125q0.171875 -0.015625 0.4375 -0.015625q0.265625 0 0.421875 0.015625q0.171875 0.015625 0.265625 0.078125q0.09375 0.046875 0.140625 0.109375q0.046875 0.0625 0.046875 0.15625l0 1.390625q0.890625 -0.984375 1.71875 -1.453125q0.84375 -0.46875 1.703125 -0.46875q0.65625 0 1.171875 0.15625q0.515625 0.15625 0.90625 0.4375q0.40625 0.265625 0.6875 0.65625q0.28125 0.375 0.46875 0.84375q0.53125 -0.578125 1.0 -0.96875q0.484375 -0.40625 0.921875 -0.640625q0.4375 -0.25 0.84375 -0.359375q0.421875 -0.125 0.84375 -0.125q1.03125 0 1.71875 0.359375q0.6875 0.359375 1.109375 0.96875q0.4375 0.59375 0.609375 1.390625q0.1875 0.796875 0.1875 1.6875l0 6.671875zm12.5625 0q0 0.09375 -0.046875 0.15625q-0.03125 0.0625 -0.140625 0.125q-0.109375 0.046875 -0.28125 0.0625q-0.15625 0.03125 -0.40625 0.03125q-0.265625 0 -0.4375 -0.03125q-0.171875 -0.015625 -0.28125 -0.0625q-0.09375 -0.0625 -0.125 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -1.390625q-0.90625 1.0 -1.796875 1.453125q-0.875 0.453125 -1.765625 0.453125q-1.0625 0 -1.78125 -0.34375q-0.71875 -0.359375 -1.171875 -0.953125q-0.4375 -0.609375 -0.640625 -1.40625q-0.1875 -0.8125 -0.1875 -1.953125l0 -6.40625q0 -0.09375 0.03125 -0.15625q0.046875 -0.0625 0.15625 -0.109375q0.125 -0.0625 0.3125 -0.078125q0.1875 -0.015625 0.46875 -0.015625q0.28125 0 0.46875 0.015625q0.1875 0.015625 0.296875 0.078125q0.125 0.046875 0.171875 0.109375q0.046875 0.0625 0.046875 0.15625l0 6.140625q0 0.921875 0.125 1.484375q0.140625 0.5625 0.40625 0.953125q0.28125 0.390625 0.703125 0.609375q0.421875 0.21875 0.984375 0.21875q0.734375 0 1.453125 -0.515625q0.71875 -0.515625 1.53125 -1.515625l0 -7.375q0 -0.09375 0.03125 -0.15625q0.046875 -0.0625 0.15625 -0.109375q0.125 -0.0625 0.296875 -0.078125q0.1875 -0.015625 0.484375 -0.015625q0.28125 0 0.46875 0.015625q0.1875 0.015625 0.28125 0.078125q0.109375 0.046875 0.15625 0.109375q0.0625 0.0625 0.0625 0.15625l0 10.546875zm5.515625 0q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -15.65625q0 -0.09375 0.03125 -0.15625q0.046875 -0.078125 0.15625 -0.125q0.109375 -0.046875 0.296875 -0.0625q0.1875 -0.03125 0.46875 -0.03125q0.296875 0 0.484375 0.03125q0.1875 0.015625 0.296875 0.0625q0.109375 0.046875 0.15625 0.125q0.046875 0.0625 0.046875 0.15625l0 15.65625zm11.5078125 0.015625q0 0.140625 -0.09375 0.21875q-0.09375 0.0625 -0.265625 0.09375q-0.15625 0.046875 -0.46875 0.046875q-0.296875 0 -0.484375 -0.046875q-0.1875 -0.03125 -0.265625 -0.09375q-0.078125 -0.078125 -0.078125 -0.21875l0 -1.0625q-0.6875 0.75 -1.546875 1.15625q-0.84375 0.40625 -1.796875 0.40625q-0.828125 0 -1.5 -0.21875q-0.671875 -0.21875 -1.15625 -0.625q-0.46875 -0.40625 -0.734375 -1.0q-0.265625 -0.609375 -0.265625 -1.359375q0 -0.890625 0.359375 -1.546875q0.375 -0.65625 1.046875 -1.09375q0.6875 -0.4375 1.671875 -0.65625q0.984375 -0.21875 2.203125 -0.21875l1.453125 0l0 -0.8125q0 -0.609375 -0.125 -1.078125q-0.125 -0.46875 -0.421875 -0.78125q-0.28125 -0.3125 -0.734375 -0.46875q-0.453125 -0.15625 -1.125 -0.15625q-0.71875 0 -1.296875 0.171875q-0.5625 0.171875 -0.984375 0.375q-0.421875 0.203125 -0.71875 0.375q-0.28125 0.171875 -0.421875 0.171875q-0.09375 0 -0.171875 -0.046875q-0.0625 -0.046875 -0.125 -0.140625q-0.046875 -0.09375 -0.078125 -0.234375q-0.015625 -0.15625 -0.015625 -0.328125q0 -0.296875 0.03125 -0.46875q0.046875 -0.171875 0.203125 -0.3125q0.171875 -0.15625 0.546875 -0.359375q0.390625 -0.21875 0.890625 -0.375q0.515625 -0.171875 1.109375 -0.28125q0.59375 -0.125 1.203125 -0.125q1.140625 0 1.9375 0.265625q0.796875 0.25 1.28125 0.75q0.5 0.5 0.71875 1.25q0.21875 0.734375 0.21875 1.71875l0 7.109375zm-1.921875 -4.8125l-1.640625 0q-0.796875 0 -1.390625 0.140625q-0.578125 0.125 -0.96875 0.390625q-0.390625 0.265625 -0.578125 0.640625q-0.171875 0.359375 -0.171875 0.84375q0 0.8125 0.515625 1.296875q0.53125 0.484375 1.46875 0.484375q0.75 0 1.40625 -0.375q0.65625 -0.390625 1.359375 -1.1875l0 -2.234375zm10.964844 4.03125q0 0.328125 -0.046875 0.53125q-0.046875 0.203125 -0.140625 0.296875q-0.09375 0.09375 -0.28125 0.1875q-0.1875 0.078125 -0.4375 0.125q-0.234375 0.046875 -0.5 0.078125q-0.265625 0.046875 -0.546875 0.046875q-0.8125 0 -1.40625 -0.21875q-0.578125 -0.21875 -0.953125 -0.65625q-0.375 -0.4375 -0.546875 -1.109375q-0.171875 -0.6875 -0.171875 -1.59375l0 -6.171875l-1.46875 0q-0.1875 0 -0.296875 -0.1875q-0.09375 -0.1875 -0.09375 -0.609375q0 -0.21875 0.03125 -0.359375q0.03125 -0.15625 0.078125 -0.25q0.046875 -0.109375 0.109375 -0.140625q0.078125 -0.046875 0.171875 -0.046875l1.46875 0l0 -2.515625q0 -0.078125 0.03125 -0.140625q0.046875 -0.078125 0.15625 -0.125q0.125 -0.0625 0.3125 -0.078125q0.1875 -0.03125 0.46875 -0.03125q0.28125 0 0.46875 0.03125q0.1875 0.015625 0.296875 0.078125q0.109375 0.046875 0.15625 0.125q0.046875 0.0625 0.046875 0.140625l0 2.515625l2.703125 0q0.09375 0 0.15625 0.046875q0.078125 0.03125 0.125 0.140625q0.0625 0.09375 0.078125 0.25q0.03125 0.140625 0.03125 0.359375q0 0.421875 -0.109375 0.609375q-0.109375 0.1875 -0.28125 0.1875l-2.703125 0l0 5.890625q0 1.09375 0.3125 1.65625q0.328125 0.546875 1.15625 0.546875q0.28125 0 0.484375 -0.046875q0.21875 -0.0625 0.375 -0.109375q0.171875 -0.0625 0.28125 -0.109375q0.125 -0.0625 0.21875 -0.0625q0.046875 0 0.09375 0.03125q0.0625 0.03125 0.09375 0.109375q0.03125 0.078125 0.046875 0.21875q0.03125 0.140625 0.03125 0.359375zm4.4921875 0.765625q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -10.546875q0 -0.078125 0.03125 -0.140625q0.046875 -0.078125 0.15625 -0.125q0.109375 -0.046875 0.296875 -0.0625q0.1875 -0.03125 0.46875 -0.03125q0.296875 0 0.484375 0.03125q0.1875 0.015625 0.296875 0.0625q0.109375 0.046875 0.15625 0.125q0.046875 0.0625 0.046875 0.140625l0 10.546875zm0.21875 -14.109375q0 0.6875 -0.265625 0.9375q-0.25 0.234375 -0.9375 0.234375q-0.6875 0 -0.9375 -0.234375q-0.25 -0.25 -0.25 -0.90625q0 -0.6875 0.25 -0.921875q0.265625 -0.25 0.953125 -0.25q0.6875 0 0.9375 0.234375q0.25 0.234375 0.25 0.90625zm13.1640625 8.71875q0 1.296875 -0.34375 2.375q-0.34375 1.078125 -1.015625 1.875q-0.671875 0.78125 -1.6875 1.21875q-1.015625 0.4375 -2.34375 0.4375q-1.3125 0 -2.28125 -0.375q-0.953125 -0.390625 -1.609375 -1.125q-0.640625 -0.75 -0.953125 -1.796875q-0.3125 -1.0625 -0.3125 -2.390625q0 -1.296875 0.328125 -2.375q0.328125 -1.09375 1.0 -1.875q0.6875 -0.78125 1.6875 -1.21875q1.015625 -0.4375 2.359375 -0.4375q1.296875 0 2.265625 0.390625q0.96875 0.390625 1.609375 1.125q0.640625 0.734375 0.96875 1.796875q0.328125 1.046875 0.328125 2.375zm-2.046875 0.125q0 -0.84375 -0.15625 -1.609375q-0.15625 -0.765625 -0.53125 -1.328125q-0.359375 -0.578125 -0.984375 -0.90625q-0.609375 -0.34375 -1.53125 -0.34375q-0.859375 0 -1.484375 0.3125q-0.609375 0.296875 -1.015625 0.859375q-0.390625 0.546875 -0.59375 1.3125q-0.1875 0.765625 -0.1875 1.65625q0 0.875 0.15625 1.640625q0.171875 0.75 0.53125 1.328125q0.375 0.5625 0.984375 0.90625q0.625 0.328125 1.5625 0.328125q0.84375 0 1.453125 -0.296875q0.625 -0.3125 1.015625 -0.859375q0.40625 -0.5625 0.59375 -1.3125q0.1875 -0.765625 0.1875 -1.6875zm13.96875 5.265625q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.09375 0.046875 -0.28125 0.0625q-0.1875 0.03125 -0.46875 0.03125q-0.296875 0 -0.484375 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.046875 -0.0625 -0.046875 -0.15625l0 -6.171875q0 -0.90625 -0.140625 -1.453125q-0.140625 -0.546875 -0.40625 -0.9375q-0.265625 -0.40625 -0.703125 -0.609375q-0.421875 -0.21875 -0.984375 -0.21875q-0.71875 0 -1.453125 0.515625q-0.71875 0.515625 -1.515625 1.5l0 7.375q0 0.09375 -0.046875 0.15625q-0.046875 0.0625 -0.15625 0.125q-0.109375 0.046875 -0.296875 0.0625q-0.1875 0.03125 -0.484375 0.03125q-0.28125 0 -0.46875 -0.03125q-0.1875 -0.015625 -0.296875 -0.0625q-0.109375 -0.0625 -0.15625 -0.125q-0.03125 -0.0625 -0.03125 -0.15625l0 -10.546875q0 -0.09375 0.03125 -0.15625q0.03125 -0.0625 0.140625 -0.109375q0.109375 -0.0625 0.265625 -0.078125q0.171875 -0.015625 0.4375 -0.015625q0.265625 0 0.421875 0.015625q0.171875 0.015625 0.265625 0.078125q0.09375 0.046875 0.140625 0.109375q0.046875 0.0625 0.046875 0.15625l0 1.390625q0.890625 -0.984375 1.765625 -1.453125q0.890625 -0.46875 1.796875 -0.46875q1.046875 0 1.765625 0.359375q0.71875 0.359375 1.15625 0.96875q0.453125 0.59375 0.640625 1.390625q0.203125 0.796875 0.203125 1.921875l0 6.4375z" fill-rule="nonzero"></path><path fill="#000000" fill-opacity="0.0" d="m362.24677 390.1742l0 68.25195" fill-rule="nonzero"></path><path stroke="#4f81bd" stroke-width="3.0" stroke-linejoin="round" stroke-linecap="butt" d="m362.24677 408.17416l0 32.251984" fill-rule="evenodd"></path><path fill="#4f81bd" stroke="#4f81bd" stroke-width="3.0" stroke-linecap="butt" d="m367.20197 408.17416l-4.9552 -13.614288l-4.9552 13.614288z" fill-rule="evenodd"></path><path fill="#4f81bd" stroke="#4f81bd" stroke-width="3.0" stroke-linecap="butt" d="m357.29156 440.42615l4.9552 13.614288l4.9552 -13.614288z" fill-rule="evenodd"></path><path fill="#000000" fill-opacity="0.0" d="m100.3262 83.14455l0 238.80315" fill-rule="nonzero"></path><path stroke="#4f81bd" stroke-width="3.0" stroke-linejoin="round" stroke-linecap="butt" d="m100.326195 101.14454l0 202.80316" fill-rule="evenodd"></path><path fill="#4f81bd" stroke="#4f81bd" stroke-width="3.0" stroke-linecap="butt" d="m105.281395 101.14455l-4.9552 -13.614296l-4.9551926 13.614296z" fill-rule="evenodd"></path><path fill="#4f81bd" stroke="#4f81bd" stroke-width="3.0" stroke-linecap="butt" d="m95.371 303.9477l4.9551926 13.614288l4.9552 -13.614288z" fill-rule="evenodd"></path></g></svg>
+
diff --git a/etc/doxygen/images/sensoractorunits2.svg b/etc/doxygen/images/sensoractorunits2.svg
new file mode 100644
index 0000000000000000000000000000000000000000..d85f2ed4e93066cbc64006728acf550e3b49ca46
--- /dev/null
+++ b/etc/doxygen/images/sensoractorunits2.svg
@@ -0,0 +1,4 @@
+<?xml version="1.0" standalone="yes"?>
+
+<svg version="1.1" viewBox="0.0 0.0 960.0 540.0" fill="none" stroke="none" stroke-linecap="square" stroke-miterlimit="10" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink"><clipPath id="gdd34d662f_0_0.0"><path d="m0 0l960.0 0l0 540.0l-960.0 0l0 -540.0z" clip-rule="nonzero"></path></clipPath><g clip-path="url(#gdd34d662f_0_0.0)"><path fill="#ffffff" d="m0 0l960.0 0l0 540.0l-960.0 0z" fill-rule="nonzero"></path><defs><linearGradient id="gdd34d662f_0_0.1" gradientUnits="userSpaceOnUse" gradientTransform="matrix(21.31145760879976 0.0 0.0 5.765325667956162 253.55367874015747 15.391076115485564)" spreadMethod="pad" x1="21.31122313092855" y1="21.311457609880964" x2="21.311457609880964" y2="2.3711293843030903E-9"><stop offset="0.0" stop-color="#bedbff"></stop><stop offset="0.35" stop-color="#d1e5fe"></stop><stop offset="1.0" stop-color="#eef5ff"></stop></linearGradient></defs><path fill="url(#gdd34d662f_0_0.1)" d="m253.55368 15.391076l454.17325 0l0 122.86614l-454.17325 0z" fill-rule="nonzero"></path><path stroke="#4a7dbb" stroke-width="1.0" stroke-linejoin="round" stroke-linecap="butt" d="m253.55368 15.391076l454.17325 0l0 122.86614l-454.17325 0z" fill-rule="nonzero"></path><path fill="#000000" d="m363.7106 84.130394q0 1.78125 -0.65625 3.171875q-0.65625 1.375 -1.828125 2.34375q-1.15625 0.96875 -2.734375 1.46875q-1.5625 0.484375 -3.375 0.484375q-1.265625 0 -2.359375 -0.21875q-1.078125 -0.21875 -1.9375 -0.53125q-0.84375 -0.3125 -1.421875 -0.640625q-0.578125 -0.328125 -0.796875 -0.5625q-0.21875 -0.234375 -0.328125 -0.59375q-0.109375 -0.375 -0.109375 -0.96875q0 -0.4375 0.03125 -0.71875q0.046875 -0.28125 0.125 -0.453125q0.078125 -0.1875 0.1875 -0.25q0.125 -0.0625 0.28125 -0.0625q0.265625 0 0.765625 0.328125q0.5 0.328125 1.28125 0.71875q0.78125 0.390625 1.875 0.734375q1.109375 0.34375 2.5625 0.34375q1.09375 0 2.0 -0.296875q0.90625 -0.296875 1.5625 -0.828125q0.65625 -0.53125 1.0 -1.3125q0.359375 -0.78125 0.359375 -1.78125q0 -1.078125 -0.5 -1.828125q-0.484375 -0.765625 -1.28125 -1.34375q-0.796875 -0.578125 -1.828125 -1.046875q-1.015625 -0.484375 -2.09375 -0.984375q-1.078125 -0.5 -2.09375 -1.109375q-1.015625 -0.609375 -1.8125 -1.421875q-0.796875 -0.828125 -1.296875 -1.921875q-0.5 -1.109375 -0.5 -2.65625q0 -1.578125 0.578125 -2.8125q0.578125 -1.25 1.59375 -2.078125q1.03125 -0.84375 2.4375 -1.28125q1.421875 -0.4375 3.0625 -0.4375q0.84375 0 1.6875 0.140625q0.859375 0.140625 1.609375 0.390625q0.75 0.25 1.328125 0.546875q0.59375 0.296875 0.78125 0.484375q0.1875 0.1875 0.234375 0.296875q0.0625 0.109375 0.09375 0.28125q0.046875 0.15625 0.0625 0.390625q0.03125 0.234375 0.03125 0.609375q0 0.34375 -0.03125 0.625q-0.03125 0.265625 -0.09375 0.453125q-0.0625 0.1875 -0.171875 0.28125q-0.09375 0.078125 -0.234375 0.078125q-0.21875 0 -0.6875 -0.265625q-0.453125 -0.28125 -1.125 -0.609375q-0.65625 -0.34375 -1.5625 -0.625q-0.90625 -0.296875 -2.03125 -0.296875q-1.0625 0 -1.84375 0.296875q-0.78125 0.28125 -1.296875 0.75q-0.5 0.46875 -0.75 1.109375q-0.25 0.640625 -0.25 1.359375q0 1.0625 0.484375 1.828125q0.484375 0.75 1.296875 1.34375q0.8125 0.578125 1.84375 1.078125q1.03125 0.484375 2.109375 0.984375q1.078125 0.5 2.109375 1.09375q1.03125 0.59375 1.84375 1.40625q0.8125 0.8125 1.3125 1.921875q0.5 1.09375 0.5 2.59375zm19.425781 -2.953125q0 0.765625 -0.375 1.09375q-0.375 0.3125 -0.875 0.3125l-11.515625 0q0 1.46875 0.28125 2.640625q0.296875 1.171875 0.984375 2.015625q0.6875 0.84375 1.78125 1.296875q1.09375 0.4375 2.671875 0.4375q1.25 0 2.21875 -0.203125q0.984375 -0.203125 1.6875 -0.453125q0.71875 -0.265625 1.171875 -0.46875q0.46875 -0.203125 0.703125 -0.203125q0.140625 0 0.25 0.078125q0.109375 0.0625 0.15625 0.203125q0.0625 0.125 0.09375 0.375q0.03125 0.25 0.03125 0.59375q0 0.25 -0.03125 0.4375q-0.015625 0.1875 -0.046875 0.34375q-0.015625 0.140625 -0.09375 0.265625q-0.0625 0.109375 -0.171875 0.21875q-0.109375 0.109375 -0.640625 0.359375q-0.515625 0.234375 -1.359375 0.46875q-0.84375 0.234375 -1.953125 0.421875q-1.09375 0.1875 -2.34375 0.1875q-2.171875 0 -3.8125 -0.609375q-1.625 -0.609375 -2.734375 -1.796875q-1.109375 -1.1875 -1.6875 -2.984375q-0.5625 -1.796875 -0.5625 -4.1875q0 -2.265625 0.578125 -4.0625q0.59375 -1.8125 1.703125 -3.0625q1.109375 -1.265625 2.671875 -1.9375q1.5625 -0.6875 3.484375 -0.6875q2.078125 0 3.53125 0.671875q1.453125 0.65625 2.390625 1.78125q0.9375 1.125 1.375 2.640625q0.4375 1.515625 0.4375 3.234375l0 0.578125zm-3.234375 -0.953125q0.0625 -2.53125 -1.125 -3.96875q-1.1875 -1.453125 -3.5 -1.453125q-1.203125 0 -2.109375 0.453125q-0.890625 0.4375 -1.5 1.1875q-0.59375 0.734375 -0.9375 1.71875q-0.328125 0.984375 -0.359375 2.0625l9.53125 0zm23.277344 10.515625q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.25 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.78125 0.046875q-0.5 0 -0.8125 -0.046875q-0.3125 -0.03125 -0.484375 -0.109375q-0.171875 -0.09375 -0.25 -0.1875q-0.078125 -0.109375 -0.078125 -0.265625l0 -10.296875q0 -1.5 -0.234375 -2.421875q-0.234375 -0.921875 -0.6875 -1.578125q-0.453125 -0.671875 -1.171875 -1.015625q-0.703125 -0.359375 -1.640625 -0.359375q-1.203125 0 -2.421875 0.859375q-1.203125 0.859375 -2.53125 2.515625l0 12.296875q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -17.578125q0 -0.15625 0.0625 -0.265625q0.0625 -0.109375 0.234375 -0.1875q0.171875 -0.09375 0.4375 -0.125q0.28125 -0.03125 0.734375 -0.03125q0.4375 0 0.71875 0.03125q0.28125 0.03125 0.4375 0.125q0.15625 0.078125 0.21875 0.1875q0.078125 0.109375 0.078125 0.265625l0 2.3125q1.484375 -1.65625 2.953125 -2.421875q1.46875 -0.78125 2.984375 -0.78125q1.75 0 2.953125 0.609375q1.203125 0.59375 1.9375 1.59375q0.75 0.984375 1.0625 2.328125q0.328125 1.328125 0.328125 3.203125l0 10.734375zm16.921875 -4.796875q0 1.359375 -0.5 2.421875q-0.5 1.046875 -1.421875 1.765625q-0.921875 0.71875 -2.1875 1.09375q-1.265625 0.375 -2.796875 0.375q-0.9375 0 -1.78125 -0.15625q-0.84375 -0.140625 -1.53125 -0.359375q-0.671875 -0.234375 -1.140625 -0.46875q-0.46875 -0.25 -0.6875 -0.4375q-0.203125 -0.203125 -0.3125 -0.546875q-0.09375 -0.359375 -0.09375 -0.96875q0 -0.375 0.03125 -0.625q0.046875 -0.25 0.109375 -0.40625q0.0625 -0.15625 0.171875 -0.21875q0.109375 -0.078125 0.234375 -0.078125q0.21875 0 0.640625 0.265625q0.421875 0.265625 1.03125 0.578125q0.625 0.3125 1.453125 0.578125q0.84375 0.265625 1.9375 0.265625q0.828125 0 1.484375 -0.171875q0.671875 -0.1875 1.15625 -0.53125q0.484375 -0.34375 0.75 -0.859375q0.265625 -0.53125 0.265625 -1.25q0 -0.75 -0.390625 -1.25q-0.375 -0.515625 -1.0 -0.90625q-0.625 -0.390625 -1.40625 -0.6875q-0.78125 -0.3125 -1.609375 -0.640625q-0.828125 -0.328125 -1.625 -0.75q-0.78125 -0.421875 -1.40625 -1.015625q-0.625 -0.609375 -1.015625 -1.453125q-0.375 -0.84375 -0.375 -2.015625q0 -1.03125 0.390625 -1.96875q0.40625 -0.953125 1.203125 -1.671875q0.8125 -0.71875 2.0 -1.140625q1.203125 -0.4375 2.8125 -0.4375q0.703125 0 1.40625 0.125q0.703125 0.109375 1.265625 0.296875q0.5625 0.171875 0.96875 0.375q0.40625 0.203125 0.609375 0.359375q0.203125 0.15625 0.265625 0.28125q0.078125 0.109375 0.09375 0.265625q0.03125 0.140625 0.0625 0.359375q0.03125 0.203125 0.03125 0.515625q0 0.34375 -0.03125 0.59375q-0.03125 0.234375 -0.09375 0.390625q-0.0625 0.15625 -0.171875 0.234375q-0.09375 0.0625 -0.203125 0.0625q-0.1875 0 -0.515625 -0.21875q-0.328125 -0.21875 -0.859375 -0.453125q-0.53125 -0.25 -1.25 -0.46875q-0.703125 -0.21875 -1.625 -0.21875q-0.8125 0 -1.4375 0.1875q-0.625 0.1875 -1.03125 0.53125q-0.390625 0.34375 -0.609375 0.8125q-0.203125 0.46875 -0.203125 1.015625q0 0.765625 0.390625 1.28125q0.390625 0.515625 1.015625 0.90625q0.625 0.390625 1.421875 0.703125q0.8125 0.3125 1.640625 0.640625q0.828125 0.328125 1.640625 0.75q0.8125 0.40625 1.4375 1.0q0.625 0.578125 1.0 1.40625q0.390625 0.8125 0.390625 1.9375zm20.957031 -4.1875q0 2.140625 -0.578125 3.953125q-0.5625 1.796875 -1.6875 3.109375q-1.125 1.3125 -2.8125 2.046875q-1.6875 0.734375 -3.90625 0.734375q-2.171875 0 -3.78125 -0.640625q-1.609375 -0.65625 -2.6875 -1.875q-1.078125 -1.234375 -1.609375 -2.984375q-0.515625 -1.765625 -0.515625 -4.0q0 -2.140625 0.546875 -3.953125q0.5625 -1.8125 1.6875 -3.109375q1.125 -1.3125 2.796875 -2.03125q1.6875 -0.734375 3.921875 -0.734375q2.171875 0 3.78125 0.65625q1.609375 0.640625 2.6875 1.875q1.078125 1.21875 1.609375 2.984375q0.546875 1.75 0.546875 3.96875zm-3.40625 0.203125q0 -1.421875 -0.265625 -2.6875q-0.265625 -1.265625 -0.875 -2.21875q-0.59375 -0.96875 -1.640625 -1.515625q-1.03125 -0.5625 -2.5625 -0.5625q-1.4375 0 -2.46875 0.515625q-1.015625 0.5 -1.6875 1.4375q-0.65625 0.921875 -0.984375 2.1875q-0.3125 1.265625 -0.3125 2.765625q0 1.453125 0.265625 2.71875q0.265625 1.265625 0.875 2.21875q0.609375 0.953125 1.640625 1.515625q1.046875 0.546875 2.59375 0.546875q1.40625 0 2.4375 -0.5q1.03125 -0.515625 1.6875 -1.4375q0.671875 -0.921875 0.984375 -2.1875q0.3125 -1.265625 0.3125 -2.796875zm18.421875 -7.65625q0 0.4375 -0.03125 0.734375q-0.015625 0.28125 -0.078125 0.453125q-0.046875 0.171875 -0.140625 0.265625q-0.078125 0.078125 -0.234375 0.078125q-0.15625 0 -0.390625 -0.078125q-0.21875 -0.09375 -0.5 -0.1875q-0.28125 -0.09375 -0.640625 -0.171875q-0.34375 -0.078125 -0.765625 -0.078125q-0.484375 0 -0.953125 0.203125q-0.46875 0.1875 -0.984375 0.640625q-0.515625 0.453125 -1.09375 1.203125q-0.5625 0.734375 -1.234375 1.8125l0 11.5625q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -17.578125q0 -0.15625 0.0625 -0.265625q0.0625 -0.109375 0.234375 -0.1875q0.171875 -0.09375 0.4375 -0.125q0.28125 -0.03125 0.734375 -0.03125q0.4375 0 0.71875 0.03125q0.28125 0.03125 0.4375 0.125q0.15625 0.078125 0.21875 0.1875q0.078125 0.109375 0.078125 0.265625l0 2.546875q0.71875 -1.046875 1.34375 -1.703125q0.640625 -0.671875 1.203125 -1.046875q0.578125 -0.390625 1.125 -0.53125q0.5625 -0.15625 1.125 -0.15625q0.25 0 0.578125 0.03125q0.328125 0.03125 0.671875 0.109375q0.359375 0.078125 0.640625 0.1875q0.28125 0.09375 0.390625 0.1875q0.125 0.09375 0.15625 0.1875q0.046875 0.078125 0.078125 0.21875q0.03125 0.140625 0.03125 0.40625q0.015625 0.265625 0.015625 0.703125zm22.960938 15.734375q0.15625 0.421875 0.171875 0.6875q0.015625 0.265625 -0.140625 0.40625q-0.15625 0.140625 -0.53125 0.171875q-0.359375 0.046875 -0.953125 0.046875q-0.609375 0 -0.96875 -0.03125q-0.359375 -0.03125 -0.546875 -0.09375q-0.1875 -0.078125 -0.28125 -0.1875q-0.078125 -0.125 -0.15625 -0.296875l-2.171875 -6.15625l-10.515625 0l-2.0625 6.078125q-0.0625 0.171875 -0.15625 0.296875q-0.09375 0.125 -0.28125 0.21875q-0.1875 0.09375 -0.53125 0.125q-0.34375 0.046875 -0.890625 0.046875q-0.5625 0 -0.921875 -0.0625q-0.359375 -0.046875 -0.515625 -0.171875q-0.140625 -0.140625 -0.140625 -0.40625q0.015625 -0.265625 0.171875 -0.703125l8.484375 -23.46875q0.078125 -0.21875 0.203125 -0.34375q0.125 -0.140625 0.359375 -0.21875q0.25 -0.078125 0.625 -0.109375q0.390625 -0.03125 0.96875 -0.03125q0.625 0 1.03125 0.03125q0.421875 0.03125 0.671875 0.109375q0.25 0.078125 0.390625 0.21875q0.140625 0.140625 0.21875 0.359375l8.46875 23.484375zm-10.875 -20.734375l-0.015625 0l-4.359375 12.609375l8.796875 0l-4.421875 -12.609375zm27.363281 18.75q0 0.34375 -0.015625 0.59375q-0.015625 0.234375 -0.078125 0.40625q-0.046875 0.15625 -0.109375 0.28125q-0.0625 0.125 -0.3125 0.375q-0.25 0.25 -0.84375 0.609375q-0.578125 0.359375 -1.3125 0.640625q-0.71875 0.28125 -1.578125 0.453125q-0.859375 0.1875 -1.78125 0.1875q-1.890625 0 -3.359375 -0.625q-1.46875 -0.625 -2.453125 -1.828125q-0.984375 -1.203125 -1.5 -2.953125q-0.515625 -1.75 -0.515625 -4.03125q0 -2.59375 0.625 -4.453125q0.640625 -1.875 1.734375 -3.0625q1.109375 -1.203125 2.59375 -1.765625q1.5 -0.578125 3.25 -0.578125q0.828125 0 1.625 0.15625q0.796875 0.15625 1.453125 0.40625q0.671875 0.25 1.1875 0.59375q0.515625 0.328125 0.75 0.5625q0.234375 0.234375 0.3125 0.375q0.09375 0.125 0.15625 0.3125q0.0625 0.1875 0.078125 0.421875q0.015625 0.234375 0.015625 0.578125q0 0.765625 -0.171875 1.078125q-0.171875 0.296875 -0.4375 0.296875q-0.28125 0 -0.671875 -0.3125q-0.375 -0.328125 -0.96875 -0.71875q-0.578125 -0.390625 -1.40625 -0.71875q-0.828125 -0.328125 -1.96875 -0.328125q-2.328125 0 -3.5625 1.796875q-1.234375 1.78125 -1.234375 5.1875q0 1.6875 0.3125 2.96875q0.328125 1.28125 0.953125 2.140625q0.625 0.859375 1.53125 1.28125q0.90625 0.421875 2.078125 0.421875q1.109375 0 1.953125 -0.34375q0.84375 -0.359375 1.453125 -0.78125q0.625 -0.421875 1.03125 -0.765625q0.421875 -0.34375 0.65625 -0.34375q0.140625 0 0.234375 0.078125q0.109375 0.078125 0.171875 0.265625q0.0625 0.1875 0.09375 0.46875q0.03125 0.28125 0.03125 0.671875zm13.4140625 1.390625q0 0.5625 -0.078125 0.90625q-0.078125 0.328125 -0.234375 0.484375q-0.15625 0.15625 -0.46875 0.296875q-0.3125 0.140625 -0.71875 0.21875q-0.390625 0.09375 -0.84375 0.140625q-0.4375 0.0625 -0.890625 0.0625q-1.375 0 -2.359375 -0.359375q-0.96875 -0.359375 -1.59375 -1.09375q-0.625 -0.734375 -0.90625 -1.859375q-0.28125 -1.125 -0.28125 -2.640625l0 -10.28125l-2.453125 0q-0.296875 0 -0.484375 -0.3125q-0.171875 -0.3125 -0.171875 -1.015625q0 -0.359375 0.046875 -0.609375q0.0625 -0.265625 0.140625 -0.421875q0.078125 -0.171875 0.203125 -0.234375q0.125 -0.078125 0.28125 -0.078125l2.4375 0l0 -4.171875q0 -0.140625 0.0625 -0.25q0.078125 -0.125 0.265625 -0.203125q0.1875 -0.09375 0.5 -0.125q0.3125 -0.046875 0.78125 -0.046875q0.484375 0 0.796875 0.046875q0.3125 0.03125 0.484375 0.125q0.171875 0.078125 0.25 0.203125q0.078125 0.109375 0.078125 0.25l0 4.171875l4.515625 0q0.15625 0 0.265625 0.078125q0.125 0.0625 0.203125 0.234375q0.09375 0.15625 0.125 0.421875q0.046875 0.25 0.046875 0.609375q0 0.703125 -0.171875 1.015625q-0.171875 0.3125 -0.46875 0.3125l-4.515625 0l0 9.8125q0 1.8125 0.53125 2.75q0.546875 0.921875 1.9375 0.921875q0.453125 0 0.796875 -0.078125q0.359375 -0.09375 0.625 -0.1875q0.28125 -0.109375 0.46875 -0.1875q0.203125 -0.09375 0.359375 -0.09375q0.09375 0 0.171875 0.046875q0.09375 0.046875 0.140625 0.1875q0.046875 0.140625 0.078125 0.375q0.046875 0.234375 0.046875 0.578125zm20.617157 -7.6875q0 2.140625 -0.578125 3.953125q-0.5625 1.796875 -1.6875 3.109375q-1.125 1.3125 -2.8125 2.046875q-1.6875 0.734375 -3.90625 0.734375q-2.171875 0 -3.78125 -0.640625q-1.609375 -0.65625 -2.6875 -1.875q-1.078125 -1.234375 -1.609375 -2.984375q-0.5155945 -1.765625 -0.5155945 -4.0q0 -2.140625 0.5468445 -3.953125q0.5625 -1.8125 1.6875 -3.109375q1.125 -1.3125 2.796875 -2.03125q1.6875 -0.734375 3.921875 -0.734375q2.171875 0 3.78125 0.65625q1.609375 0.640625 2.6875 1.875q1.078125 1.21875 1.609375 2.984375q0.546875 1.75 0.546875 3.96875zm-3.40625 0.203125q0 -1.421875 -0.265625 -2.6875q-0.265625 -1.265625 -0.875 -2.21875q-0.59375 -0.96875 -1.640625 -1.515625q-1.03125 -0.5625 -2.5625 -0.5625q-1.4375 0 -2.46875 0.515625q-1.015625 0.5 -1.6875 1.4375q-0.65625 0.921875 -0.984375 2.1875q-0.3125 1.265625 -0.3125 2.765625q0 1.453125 0.265625 2.71875q0.265625 1.265625 0.875 2.21875q0.609375 0.953125 1.640625 1.515625q1.046875 0.546875 2.59375 0.546875q1.40625 0 2.4375 -0.5q1.03125 -0.515625 1.6875 -1.4375q0.671875 -0.921875 0.984375 -2.1875q0.3125 -1.265625 0.3125 -2.796875zm18.421875 -7.65625q0 0.4375 -0.03125 0.734375q-0.015625 0.28125 -0.078125 0.453125q-0.046875 0.171875 -0.140625 0.265625q-0.078125 0.078125 -0.234375 0.078125q-0.15625 0 -0.390625 -0.078125q-0.21875 -0.09375 -0.5 -0.1875q-0.28125 -0.09375 -0.640625 -0.171875q-0.34375 -0.078125 -0.765625 -0.078125q-0.484375 0 -0.953125 0.203125q-0.46875 0.1875 -0.984375 0.640625q-0.515625 0.453125 -1.09375 1.203125q-0.5625 0.734375 -1.234375 1.8125l0 11.5625q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -17.578125q0 -0.15625 0.0625 -0.265625q0.0625 -0.109375 0.234375 -0.1875q0.171875 -0.09375 0.4375 -0.125q0.28125 -0.03125 0.734375 -0.03125q0.4375 0 0.71875 0.03125q0.28125 0.03125 0.4375 0.125q0.15625 0.078125 0.21875 0.1875q0.078125 0.109375 0.078125 0.265625l0 2.546875q0.71875 -1.046875 1.34375 -1.703125q0.640625 -0.671875 1.203125 -1.046875q0.578125 -0.390625 1.125 -0.53125q0.5625 -0.15625 1.125 -0.15625q0.25 0 0.578125 0.03125q0.328125 0.03125 0.671875 0.109375q0.359375 0.078125 0.640625 0.1875q0.28125 0.09375 0.390625 0.1875q0.125 0.09375 0.15625 0.1875q0.046875 0.078125 0.078125 0.21875q0.03125 0.140625 0.03125 0.40625q0.015625 0.265625 0.015625 0.703125zm23.039062 7.578125q0 2.3125 -0.671875 4.125q-0.671875 1.796875 -1.921875 3.046875q-1.25 1.25 -3.046875 1.90625q-1.796875 0.640625 -4.078125 0.640625q-2.09375 0 -3.8125 -0.609375q-1.71875 -0.609375 -2.953125 -1.78125q-1.21875 -1.1875 -1.890625 -2.96875q-0.65625 -1.78125 -0.65625 -4.09375l0 -15.6875q0 -0.15625 0.078125 -0.265625q0.078125 -0.125 0.265625 -0.1875q0.203125 -0.078125 0.515625 -0.125q0.3125 -0.046875 0.8125 -0.046875q0.46875 0 0.796875 0.046875q0.34375 0.046875 0.515625 0.125q0.1875 0.0625 0.265625 0.1875q0.078125 0.109375 0.078125 0.265625l0 15.265625q0 1.765625 0.421875 3.078125q0.4375 1.296875 1.25 2.171875q0.8125 0.875 1.953125 1.3125q1.140625 0.4375 2.578125 0.4375q1.453125 0 2.59375 -0.421875q1.15625 -0.4375 1.9375 -1.296875q0.796875 -0.859375 1.21875 -2.125q0.421875 -1.28125 0.421875 -2.96875l0 -15.453125q0 -0.15625 0.078125 -0.265625q0.078125 -0.125 0.265625 -0.1875q0.203125 -0.078125 0.515625 -0.125q0.328125 -0.046875 0.8125 -0.046875q0.46875 0 0.78125 0.046875q0.328125 0.046875 0.515625 0.125q0.1875 0.0625 0.265625 0.1875q0.09375 0.109375 0.09375 0.265625l0 15.421875zm21.429688 8.859375q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.25 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.78125 0.046875q-0.5 0 -0.8125 -0.046875q-0.3125 -0.03125 -0.484375 -0.109375q-0.171875 -0.09375 -0.25 -0.1875q-0.078125 -0.109375 -0.078125 -0.265625l0 -10.296875q0 -1.5 -0.234375 -2.421875q-0.234375 -0.921875 -0.6875 -1.578125q-0.453125 -0.671875 -1.171875 -1.015625q-0.703125 -0.359375 -1.640625 -0.359375q-1.203125 0 -2.421875 0.859375q-1.203125 0.859375 -2.53125 2.515625l0 12.296875q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -17.578125q0 -0.15625 0.0625 -0.265625q0.0625 -0.109375 0.234375 -0.1875q0.171875 -0.09375 0.4375 -0.125q0.28125 -0.03125 0.734375 -0.03125q0.4375 0 0.71875 0.03125q0.28125 0.03125 0.4375 0.125q0.15625 0.078125 0.21875 0.1875q0.078125 0.109375 0.078125 0.265625l0 2.3125q1.484375 -1.65625 2.953125 -2.421875q1.46875 -0.78125 2.984375 -0.78125q1.75 0 2.953125 0.609375q1.203125 0.59375 1.9375 1.59375q0.75 0.984375 1.0625 2.328125q0.328125 1.328125 0.328125 3.203125l0 10.734375zm9.109375 0q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -17.578125q0 -0.140625 0.0625 -0.25q0.078125 -0.125 0.265625 -0.203125q0.1875 -0.078125 0.5 -0.109375q0.3125 -0.046875 0.78125 -0.046875q0.484375 0 0.796875 0.046875q0.3125 0.03125 0.484375 0.109375q0.1875 0.078125 0.265625 0.203125q0.078125 0.109375 0.078125 0.25l0 17.578125zm0.359375 -23.515625q0 1.125 -0.4375 1.546875q-0.421875 0.40625 -1.5625 0.40625q-1.140625 0 -1.5625 -0.40625q-0.421875 -0.40625 -0.421875 -1.515625q0 -1.125 0.421875 -1.53125q0.4375 -0.421875 1.59375 -0.421875q1.140625 0 1.546875 0.40625q0.421875 0.390625 0.421875 1.515625zm14.7265625 22.21875q0 0.5625 -0.078125 0.90625q-0.078125 0.328125 -0.234375 0.484375q-0.15625 0.15625 -0.46875 0.296875q-0.3125 0.140625 -0.71875 0.21875q-0.390625 0.09375 -0.84375 0.140625q-0.4375 0.0625 -0.890625 0.0625q-1.375 0 -2.359375 -0.359375q-0.96875 -0.359375 -1.59375 -1.09375q-0.625 -0.734375 -0.90625 -1.859375q-0.28125 -1.125 -0.28125 -2.640625l0 -10.28125l-2.453125 0q-0.296875 0 -0.484375 -0.3125q-0.171875 -0.3125 -0.171875 -1.015625q0 -0.359375 0.046875 -0.609375q0.0625 -0.265625 0.140625 -0.421875q0.078125 -0.171875 0.203125 -0.234375q0.125 -0.078125 0.28125 -0.078125l2.4375 0l0 -4.171875q0 -0.140625 0.0625 -0.25q0.078125 -0.125 0.265625 -0.203125q0.1875 -0.09375 0.5 -0.125q0.3125 -0.046875 0.78125 -0.046875q0.484375 0 0.796875 0.046875q0.3125 0.03125 0.484375 0.125q0.171875 0.078125 0.25 0.203125q0.078125 0.109375 0.078125 0.25l0 4.171875l4.515625 0q0.15625 0 0.265625 0.078125q0.125 0.0625 0.203125 0.234375q0.09375 0.15625 0.125 0.421875q0.046875 0.25 0.046875 0.609375q0 0.703125 -0.171875 1.015625q-0.171875 0.3125 -0.46875 0.3125l-4.515625 0l0 9.8125q0 1.8125 0.53125 2.75q0.546875 0.921875 1.9375 0.921875q0.453125 0 0.796875 -0.078125q0.359375 -0.09375 0.625 -0.1875q0.28125 -0.109375 0.46875 -0.1875q0.203125 -0.09375 0.359375 -0.09375q0.09375 0 0.171875 0.046875q0.09375 0.046875 0.140625 0.1875q0.046875 0.140625 0.078125 0.375q0.046875 0.234375 0.046875 0.578125z" fill-rule="nonzero"></path><defs><linearGradient id="gdd34d662f_0_0.2" gradientUnits="userSpaceOnUse" gradientTransform="matrix(21.31145760879976 0.0 0.0 5.765325667956162 253.55367296587926 211.34603569553806)" spreadMethod="pad" x1="21.31122313092855" y1="21.311457609880964" x2="21.311457609880964" y2="2.3711293843030903E-9"><stop offset="0.0" stop-color="#bedbff"></stop><stop offset="0.35" stop-color="#d1e5fe"></stop><stop offset="1.0" stop-color="#eef5ff"></stop></linearGradient></defs><path fill="url(#gdd34d662f_0_0.2)" d="m253.55368 211.34604l454.17325 0l0 122.86615l-454.17325 0z" fill-rule="nonzero"></path><path stroke="#4a7dbb" stroke-width="1.0" stroke-linejoin="round" stroke-linecap="butt" d="m253.55368 211.34604l454.17325 0l0 122.86615l-454.17325 0z" fill-rule="nonzero"></path><path fill="#000000" d="m385.11295 286.63223q0 0.15625 -0.078125 0.28125q-0.0625 0.125 -0.265625 0.203125q-0.1875 0.078125 -0.515625 0.125q-0.328125 0.0625 -0.859375 0.0625q-0.6875 0 -1.125 -0.0625q-0.421875 -0.0625 -0.640625 -0.21875q-0.203125 -0.15625 -0.34375 -0.359375l-9.296875 -12.625l0 12.625q0 0.140625 -0.078125 0.265625q-0.078125 0.125 -0.28125 0.203125q-0.1875 0.0625 -0.515625 0.109375q-0.3125 0.0625 -0.796875 0.0625q-0.46875 0 -0.8125 -0.0625q-0.328125 -0.046875 -0.53125 -0.109375q-0.1875 -0.078125 -0.265625 -0.203125q-0.078125 -0.125 -0.078125 -0.265625l0 -24.25q0 -0.15625 0.078125 -0.265625q0.078125 -0.125 0.265625 -0.1875q0.203125 -0.078125 0.53125 -0.125q0.34375 -0.046875 0.8125 -0.046875q0.484375 0 0.796875 0.046875q0.328125 0.046875 0.515625 0.125q0.203125 0.0625 0.28125 0.1875q0.078125 0.109375 0.078125 0.265625l0 11.234375l8.953125 -11.234375q0.109375 -0.171875 0.265625 -0.28125q0.15625 -0.125 0.375 -0.1875q0.234375 -0.078125 0.546875 -0.109375q0.328125 -0.046875 0.84375 -0.046875q0.5 0 0.8125 0.046875q0.3125 0.046875 0.5 0.125q0.1875 0.078125 0.25 0.203125q0.078125 0.109375 0.078125 0.25q0 0.25 -0.140625 0.515625q-0.125 0.25 -0.46875 0.6875l-8.375 10.03125l9.015625 11.984375q0.328125 0.515625 0.390625 0.703125q0.078125 0.171875 0.078125 0.296875zm7.15625 0.0625q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -17.578125q0 -0.140625 0.0625 -0.25q0.078125 -0.125 0.265625 -0.203125q0.1875 -0.078125 0.5 -0.109375q0.3125 -0.046875 0.78125 -0.046875q0.484375 0 0.796875 0.046875q0.3125 0.03125 0.484375 0.109375q0.1875 0.078125 0.265625 0.203125q0.078125 0.109375 0.078125 0.25l0 17.578125zm0.359375 -23.515625q0 1.125 -0.4375 1.546875q-0.421875 0.40625 -1.5625 0.40625q-1.140625 0 -1.5625 -0.40625q-0.421875 -0.40625 -0.421875 -1.515625q0 -1.125 0.421875 -1.53125q0.4375 -0.421875 1.59375 -0.421875q1.140625 0 1.546875 0.40625q0.421875 0.390625 0.421875 1.515625zm20.726562 23.515625q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.25 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.78125 0.046875q-0.5 0 -0.8125 -0.046875q-0.3125 -0.03125 -0.484375 -0.109375q-0.171875 -0.09375 -0.25 -0.1875q-0.078125 -0.109375 -0.078125 -0.265625l0 -10.296875q0 -1.5 -0.234375 -2.421875q-0.234375 -0.921875 -0.6875 -1.578125q-0.453125 -0.671875 -1.171875 -1.015625q-0.703125 -0.359375 -1.640625 -0.359375q-1.203125 0 -2.421875 0.859375q-1.203125 0.859375 -2.53125 2.515625l0 12.296875q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -17.578125q0 -0.15625 0.0625 -0.265625q0.0625 -0.109375 0.234375 -0.1875q0.171875 -0.09375 0.4375 -0.125q0.28125 -0.03125 0.734375 -0.03125q0.4375 0 0.71875 0.03125q0.28125 0.03125 0.4375 0.125q0.15625 0.078125 0.21875 0.1875q0.078125 0.109375 0.078125 0.265625l0 2.3125q1.484375 -1.65625 2.953125 -2.421875q1.46875 -0.78125 2.984375 -0.78125q1.75 0 2.953125 0.609375q1.203125 0.59375 1.9375 1.59375q0.75 0.984375 1.0625 2.328125q0.328125 1.328125 0.328125 3.203125l0 10.734375zm20.875 -9.5625q0 0.765625 -0.375 1.09375q-0.375 0.3125 -0.875 0.3125l-11.515625 0q0 1.46875 0.28125 2.640625q0.296875 1.171875 0.984375 2.015625q0.6875 0.84375 1.78125 1.296875q1.09375 0.4375 2.671875 0.4375q1.25 0 2.21875 -0.203125q0.984375 -0.203125 1.6875 -0.453125q0.71875 -0.265625 1.171875 -0.46875q0.46875 -0.203125 0.703125 -0.203125q0.140625 0 0.25 0.078125q0.109375 0.0625 0.15625 0.203125q0.0625 0.125 0.09375 0.375q0.03125 0.25 0.03125 0.59375q0 0.25 -0.03125 0.4375q-0.015625 0.1875 -0.046875 0.34375q-0.015625 0.140625 -0.09375 0.265625q-0.0625 0.109375 -0.171875 0.21875q-0.109375 0.109375 -0.640625 0.359375q-0.515625 0.234375 -1.359375 0.46875q-0.84375 0.234375 -1.953125 0.421875q-1.09375 0.1875 -2.34375 0.1875q-2.171875 0 -3.8125 -0.609375q-1.625 -0.609375 -2.734375 -1.796875q-1.109375 -1.1875 -1.6875 -2.984375q-0.5625 -1.796875 -0.5625 -4.1875q0 -2.265625 0.578125 -4.0625q0.59375 -1.8125 1.703125 -3.0625q1.109375 -1.265625 2.671875 -1.9375q1.5625 -0.6875 3.484375 -0.6875q2.078125 0 3.53125 0.671875q1.453125 0.65625 2.390625 1.78125q0.9375 1.125 1.375 2.640625q0.4375 1.515625 0.4375 3.234375l0 0.578125zm-3.234375 -0.953125q0.0625 -2.53125 -1.125 -3.96875q-1.1875 -1.453125 -3.5 -1.453125q-1.203125 0 -2.109375 0.453125q-0.890625 0.4375 -1.5 1.1875q-0.59375 0.734375 -0.9375 1.71875q-0.328125 0.984375 -0.359375 2.0625l9.53125 0zm34.214844 10.515625q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.25 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.78125 0.046875q-0.5 0 -0.8125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.171875 -0.09375 -0.25 -0.1875q-0.078125 -0.109375 -0.078125 -0.265625l0 -10.6875q0 -1.109375 -0.203125 -2.03125q-0.1875 -0.921875 -0.625 -1.578125q-0.421875 -0.671875 -1.09375 -1.015625q-0.65625 -0.359375 -1.5625 -0.359375q-1.109375 0 -2.234375 0.859375q-1.125 0.859375 -2.46875 2.515625l0 12.296875q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.1875 0.078125 -0.5 0.109375q-0.3125 0.046875 -0.78125 0.046875q-0.453125 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.25 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -10.6875q0 -1.109375 -0.21875 -2.03125q-0.21875 -0.921875 -0.65625 -1.578125q-0.421875 -0.671875 -1.078125 -1.015625q-0.65625 -0.359375 -1.546875 -0.359375q-1.109375 0 -2.25 0.859375q-1.125 0.859375 -2.453125 2.515625l0 12.296875q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -17.578125q0 -0.15625 0.0625 -0.265625q0.0625 -0.109375 0.234375 -0.1875q0.171875 -0.09375 0.4375 -0.125q0.28125 -0.03125 0.734375 -0.03125q0.4375 0 0.71875 0.03125q0.28125 0.03125 0.4375 0.125q0.15625 0.078125 0.21875 0.1875q0.078125 0.109375 0.078125 0.265625l0 2.3125q1.484375 -1.65625 2.875 -2.421875q1.390625 -0.78125 2.828125 -0.78125q1.09375 0 1.953125 0.265625q0.875 0.25 1.53125 0.71875q0.671875 0.453125 1.140625 1.09375q0.46875 0.625 0.78125 1.40625q0.875 -0.953125 1.65625 -1.609375q0.796875 -0.671875 1.53125 -1.078125q0.734375 -0.421875 1.421875 -0.609375q0.703125 -0.1875 1.40625 -0.1875q1.703125 0 2.84375 0.609375q1.15625 0.59375 1.859375 1.59375q0.71875 0.984375 1.015625 2.328125q0.3125 1.328125 0.3125 2.8125l0 11.125zm19.125 0.015625q0 0.234375 -0.15625 0.359375q-0.15625 0.109375 -0.4375 0.171875q-0.265625 0.0625 -0.796875 0.0625q-0.5 0 -0.8125 -0.0625q-0.296875 -0.0625 -0.4375 -0.171875q-0.140625 -0.125 -0.140625 -0.359375l0 -1.765625q-1.140625 1.234375 -2.5625 1.921875q-1.421875 0.6875 -3.0 0.6875q-1.390625 0 -2.515625 -0.375q-1.109375 -0.359375 -1.90625 -1.03125q-0.796875 -0.6875 -1.234375 -1.6875q-0.4375 -1.0 -0.4375 -2.265625q0 -1.484375 0.609375 -2.578125q0.609375 -1.09375 1.734375 -1.8125q1.140625 -0.71875 2.78125 -1.078125q1.640625 -0.375 3.6875 -0.375l2.421875 0l0 -1.359375q0 -1.015625 -0.21875 -1.796875q-0.21875 -0.78125 -0.703125 -1.296875q-0.46875 -0.515625 -1.234375 -0.78125q-0.75 -0.265625 -1.875 -0.265625q-1.1875 0 -2.140625 0.28125q-0.9375 0.28125 -1.65625 0.625q-0.703125 0.34375 -1.1875 0.625q-0.484375 0.28125 -0.71875 0.28125q-0.15625 0 -0.28125 -0.078125q-0.109375 -0.078125 -0.203125 -0.234375q-0.078125 -0.15625 -0.125 -0.390625q-0.03125 -0.25 -0.03125 -0.546875q0 -0.484375 0.0625 -0.765625q0.078125 -0.28125 0.34375 -0.53125q0.265625 -0.265625 0.90625 -0.609375q0.640625 -0.34375 1.484375 -0.625q0.84375 -0.28125 1.828125 -0.46875q1.0 -0.1875 2.015625 -0.1875q1.890625 0 3.21875 0.4375q1.328125 0.421875 2.140625 1.265625q0.828125 0.828125 1.203125 2.0625q0.375 1.21875 0.375 2.859375l0 11.859375zm-3.203125 -8.03125l-2.75 0q-1.328125 0 -2.3125 0.234375q-0.96875 0.21875 -1.625 0.65625q-0.640625 0.4375 -0.953125 1.0625q-0.296875 0.609375 -0.296875 1.40625q0 1.375 0.875 2.1875q0.875 0.796875 2.4375 0.796875q1.265625 0 2.34375 -0.640625q1.09375 -0.640625 2.28125 -1.96875l0 -3.734375zm18.253906 6.71875q0 0.5625 -0.078125 0.90625q-0.078125 0.328125 -0.234375 0.484375q-0.15625 0.15625 -0.46875 0.296875q-0.3125 0.140625 -0.71875 0.21875q-0.390625 0.09375 -0.84375 0.140625q-0.4375 0.0625 -0.890625 0.0625q-1.375 0 -2.359375 -0.359375q-0.96875 -0.359375 -1.59375 -1.09375q-0.625 -0.734375 -0.90625 -1.859375q-0.28125 -1.125 -0.28125 -2.640625l0 -10.28125l-2.453125 0q-0.296875 0 -0.484375 -0.3125q-0.171875 -0.3125 -0.171875 -1.015625q0 -0.359375 0.046875 -0.609375q0.0625 -0.265625 0.140625 -0.421875q0.078125 -0.171875 0.203125 -0.234375q0.125 -0.078125 0.28125 -0.078125l2.4375 0l0 -4.171875q0 -0.140625 0.0625 -0.25q0.078125 -0.125 0.265625 -0.203125q0.1875 -0.09375 0.5 -0.125q0.3125 -0.046875 0.78125 -0.046875q0.484375 0 0.796875 0.046875q0.3125 0.03125 0.484375 0.125q0.171875 0.078125 0.25 0.203125q0.078125 0.109375 0.078125 0.25l0 4.171875l4.515625 0q0.15625 0 0.265625 0.078125q0.125 0.0625 0.203125 0.234375q0.09375 0.15625 0.125 0.421875q0.046875 0.25 0.046875 0.609375q0 0.703125 -0.171875 1.015625q-0.171875 0.3125 -0.46875 0.3125l-4.515625 0l0 9.8125q0 1.8125 0.53125 2.75q0.546875 0.921875 1.9375 0.921875q0.453125 0 0.796875 -0.078125q0.359375 -0.09375 0.625 -0.1875q0.28125 -0.109375 0.46875 -0.1875q0.203125 -0.09375 0.359375 -0.09375q0.09375 0 0.171875 0.046875q0.09375 0.046875 0.140625 0.1875q0.046875 0.140625 0.078125 0.375q0.046875 0.234375 0.046875 0.578125zm7.4921875 1.296875q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -17.578125q0 -0.140625 0.0625 -0.25q0.078125 -0.125 0.265625 -0.203125q0.1875 -0.078125 0.5 -0.109375q0.3125 -0.046875 0.78125 -0.046875q0.484375 0 0.796875 0.046875q0.3125 0.03125 0.484375 0.109375q0.1875 0.078125 0.265625 0.203125q0.078125 0.109375 0.078125 0.25l0 17.578125zm0.359375 -23.515625q0 1.125 -0.4375 1.546875q-0.421875 0.40625 -1.5625 0.40625q-1.140625 0 -1.5625 -0.40625q-0.421875 -0.40625 -0.421875 -1.515625q0 -1.125 0.421875 -1.53125q0.4375 -0.421875 1.59375 -0.421875q1.140625 0 1.546875 0.40625q0.421875 0.390625 0.421875 1.515625zm18.226532 20.828125q0 0.34375 -0.015625 0.59375q-0.015625 0.234375 -0.078125 0.40625q-0.046875 0.15625 -0.109375 0.28125q-0.0625 0.125 -0.3125 0.375q-0.25 0.25 -0.84375 0.609375q-0.578125 0.359375 -1.3125 0.640625q-0.71875 0.28125 -1.578125 0.453125q-0.859375 0.1875 -1.78125 0.1875q-1.890625 0 -3.359375 -0.625q-1.46875 -0.625 -2.453125 -1.828125q-0.984375 -1.203125 -1.5 -2.953125q-0.5155945 -1.75 -0.5155945 -4.03125q0 -2.59375 0.6249695 -4.453125q0.640625 -1.875 1.734375 -3.0625q1.109375 -1.203125 2.59375 -1.765625q1.5 -0.578125 3.25 -0.578125q0.828125 0 1.625 0.15625q0.796875 0.15625 1.453125 0.40625q0.671875 0.25 1.1875 0.59375q0.515625 0.328125 0.75 0.5625q0.234375 0.234375 0.3125 0.375q0.09375 0.125 0.15625 0.3125q0.0625 0.1875 0.078125 0.421875q0.015625 0.234375 0.015625 0.578125q0 0.765625 -0.171875 1.078125q-0.171875 0.296875 -0.4375 0.296875q-0.28125 0 -0.671875 -0.3125q-0.375 -0.328125 -0.96875 -0.71875q-0.578125 -0.390625 -1.40625 -0.71875q-0.828125 -0.328125 -1.96875 -0.328125q-2.328125 0 -3.5625 1.796875q-1.234375 1.78125 -1.234375 5.1875q0 1.6875 0.3125 2.96875q0.328125 1.28125 0.953125 2.140625q0.625 0.859375 1.53125 1.28125q0.90625 0.421875 2.078125 0.421875q1.109375 0 1.953125 -0.34375q0.84375 -0.359375 1.453125 -0.78125q0.625 -0.421875 1.03125 -0.765625q0.421875 -0.34375 0.65625 -0.34375q0.140625 0 0.234375 0.078125q0.109375 0.078125 0.171875 0.265625q0.0625 0.1875 0.09375 0.46875q0.03125 0.28125 0.03125 0.671875zm23.648438 -6.171875q0 2.3125 -0.671875 4.125q-0.671875 1.796875 -1.921875 3.046875q-1.25 1.25 -3.046875 1.90625q-1.796875 0.640625 -4.078125 0.640625q-2.09375 0 -3.8125 -0.609375q-1.71875 -0.609375 -2.953125 -1.78125q-1.21875 -1.1875 -1.890625 -2.96875q-0.65625 -1.78125 -0.65625 -4.09375l0 -15.6875q0 -0.15625 0.078125 -0.265625q0.078125 -0.125 0.265625 -0.1875q0.203125 -0.078125 0.515625 -0.125q0.3125 -0.046875 0.8125 -0.046875q0.46875 0 0.796875 0.046875q0.34375 0.046875 0.515625 0.125q0.1875 0.0625 0.265625 0.1875q0.078125 0.109375 0.078125 0.265625l0 15.265625q0 1.765625 0.421875 3.078125q0.4375 1.296875 1.25 2.171875q0.8125 0.875 1.953125 1.3125q1.140625 0.4375 2.578125 0.4375q1.453125 0 2.59375 -0.421875q1.15625 -0.4375 1.9375 -1.296875q0.796875 -0.859375 1.21875 -2.125q0.421875 -1.28125 0.421875 -2.96875l0 -15.453125q0 -0.15625 0.078125 -0.265625q0.078125 -0.125 0.265625 -0.1875q0.203125 -0.078125 0.515625 -0.125q0.328125 -0.046875 0.8125 -0.046875q0.46875 0 0.78125 0.046875q0.328125 0.046875 0.515625 0.125q0.1875 0.0625 0.265625 0.1875q0.09375 0.109375 0.09375 0.265625l0 15.421875zm21.429688 8.859375q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.25 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.78125 0.046875q-0.5 0 -0.8125 -0.046875q-0.3125 -0.03125 -0.484375 -0.109375q-0.171875 -0.09375 -0.25 -0.1875q-0.078125 -0.109375 -0.078125 -0.265625l0 -10.296875q0 -1.5 -0.234375 -2.421875q-0.234375 -0.921875 -0.6875 -1.578125q-0.453125 -0.671875 -1.171875 -1.015625q-0.703125 -0.359375 -1.640625 -0.359375q-1.203125 0 -2.421875 0.859375q-1.203125 0.859375 -2.53125 2.515625l0 12.296875q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -17.578125q0 -0.15625 0.0625 -0.265625q0.0625 -0.109375 0.234375 -0.1875q0.171875 -0.09375 0.4375 -0.125q0.28125 -0.03125 0.734375 -0.03125q0.4375 0 0.71875 0.03125q0.28125 0.03125 0.4375 0.125q0.15625 0.078125 0.21875 0.1875q0.078125 0.109375 0.078125 0.265625l0 2.3125q1.484375 -1.65625 2.953125 -2.421875q1.46875 -0.78125 2.984375 -0.78125q1.75 0 2.953125 0.609375q1.203125 0.59375 1.9375 1.59375q0.75 0.984375 1.0625 2.328125q0.328125 1.328125 0.328125 3.203125l0 10.734375zm9.109375 0q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -17.578125q0 -0.140625 0.0625 -0.25q0.078125 -0.125 0.265625 -0.203125q0.1875 -0.078125 0.5 -0.109375q0.3125 -0.046875 0.78125 -0.046875q0.484375 0 0.796875 0.046875q0.3125 0.03125 0.484375 0.109375q0.1875 0.078125 0.265625 0.203125q0.078125 0.109375 0.078125 0.25l0 17.578125zm0.359375 -23.515625q0 1.125 -0.4375 1.546875q-0.421875 0.40625 -1.5625 0.40625q-1.140625 0 -1.5625 -0.40625q-0.421875 -0.40625 -0.421875 -1.515625q0 -1.125 0.421875 -1.53125q0.4375 -0.421875 1.59375 -0.421875q1.140625 0 1.546875 0.40625q0.421875 0.390625 0.421875 1.515625zm14.7265625 22.21875q0 0.5625 -0.078125 0.90625q-0.078125 0.328125 -0.234375 0.484375q-0.15625 0.15625 -0.46875 0.296875q-0.3125 0.140625 -0.71875 0.21875q-0.390625 0.09375 -0.84375 0.140625q-0.4375 0.0625 -0.890625 0.0625q-1.375 0 -2.359375 -0.359375q-0.96875 -0.359375 -1.59375 -1.09375q-0.625 -0.734375 -0.90625 -1.859375q-0.28125 -1.125 -0.28125 -2.640625l0 -10.28125l-2.453125 0q-0.296875 0 -0.484375 -0.3125q-0.171875 -0.3125 -0.171875 -1.015625q0 -0.359375 0.046875 -0.609375q0.0625 -0.265625 0.140625 -0.421875q0.078125 -0.171875 0.203125 -0.234375q0.125 -0.078125 0.28125 -0.078125l2.4375 0l0 -4.171875q0 -0.140625 0.0625 -0.25q0.078125 -0.125 0.265625 -0.203125q0.1875 -0.09375 0.5 -0.125q0.3125 -0.046875 0.78125 -0.046875q0.484375 0 0.796875 0.046875q0.3125 0.03125 0.484375 0.125q0.171875 0.078125 0.25 0.203125q0.078125 0.109375 0.078125 0.25l0 4.171875l4.515625 0q0.15625 0 0.265625 0.078125q0.125 0.0625 0.203125 0.234375q0.09375 0.15625 0.125 0.421875q0.046875 0.25 0.046875 0.609375q0 0.703125 -0.171875 1.015625q-0.171875 0.3125 -0.46875 0.3125l-4.515625 0l0 9.8125q0 1.8125 0.53125 2.75q0.546875 0.921875 1.9375 0.921875q0.453125 0 0.796875 -0.078125q0.359375 -0.09375 0.625 -0.1875q0.28125 -0.109375 0.46875 -0.1875q0.203125 -0.09375 0.359375 -0.09375q0.09375 0 0.171875 0.046875q0.09375 0.046875 0.140625 0.1875q0.046875 0.140625 0.078125 0.375q0.046875 0.234375 0.046875 0.578125z" fill-rule="nonzero"></path><defs><linearGradient id="gdd34d662f_0_0.3" gradientUnits="userSpaceOnUse" gradientTransform="matrix(21.31145760879976 0.0 0.0 5.765325667956162 17.440944881889763 407.3009950131234)" spreadMethod="pad" x1="21.31122313092855" y1="21.311457609880964" x2="21.311457609880964" y2="2.3711293843030903E-9"><stop offset="0.0" stop-color="#bedbff"></stop><stop offset="0.35" stop-color="#d1e5fe"></stop><stop offset="1.0" stop-color="#eef5ff"></stop></linearGradient></defs><path fill="url(#gdd34d662f_0_0.3)" d="m17.440945 407.301l454.17322 0l0 122.86612l-454.17322 0z" fill-rule="nonzero"></path><path stroke="#4a7dbb" stroke-width="1.0" stroke-linejoin="round" stroke-linecap="butt" d="m17.440945 407.301l454.17322 0l0 122.86612l-454.17322 0z" fill-rule="nonzero"></path><path fill="#000000" d="m87.789276 482.5872q0 0.15625 -0.078125 0.28125q-0.0625 0.125 -0.265625 0.203125q-0.1875 0.078125 -0.515625 0.125q-0.328125 0.0625 -0.859375 0.0625q-0.6875 0 -1.125 -0.0625q-0.421875 -0.0625 -0.640625 -0.21875q-0.203125 -0.15625 -0.34375 -0.359375l-9.296875 -12.625l0 12.625q0 0.140625 -0.078125 0.265625q-0.078125 0.125 -0.28125 0.203125q-0.1875 0.0625 -0.515625 0.109375q-0.3125 0.0625 -0.796875 0.0625q-0.46875 0 -0.8125 -0.0625q-0.328125 -0.046875 -0.53125 -0.109375q-0.1875 -0.078125 -0.265625 -0.203125q-0.078125 -0.125 -0.078125 -0.265625l0 -24.25q0 -0.15625 0.078125 -0.265625q0.078125 -0.125 0.265625 -0.1875q0.203125 -0.078125 0.53125 -0.125q0.34375 -0.046875 0.8125 -0.046875q0.484375 0 0.796875 0.046875q0.328125 0.046875 0.515625 0.125q0.203125 0.0625 0.28125 0.1875q0.078125 0.109375 0.078125 0.265625l0 11.234375l8.953125 -11.234375q0.109375 -0.171875 0.265625 -0.28125q0.15625 -0.125 0.375 -0.1875q0.234375 -0.078125 0.546875 -0.109375q0.328125 -0.046875 0.84375 -0.046875q0.5 0 0.8125 0.046875q0.3125 0.046875 0.5 0.125q0.1875 0.078125 0.25 0.203125q0.078125 0.109375 0.078125 0.25q0 0.25 -0.140625 0.515625q-0.125 0.25 -0.46875 0.6875l-8.375 10.03125l9.015625 11.984375q0.328125 0.515625 0.390625 0.703125q0.078125 0.171875 0.078125 0.296875zm7.15625 0.0625q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -17.578125q0 -0.140625 0.0625 -0.25q0.078125 -0.125 0.265625 -0.203125q0.1875 -0.078125 0.5 -0.109375q0.3125 -0.046875 0.78125 -0.046875q0.484375 0 0.796875 0.046875q0.3125 0.03125 0.484375 0.109375q0.1875 0.078125 0.265625 0.203125q0.078125 0.109375 0.078125 0.25l0 17.578125zm0.359375 -23.515625q0 1.125 -0.4375 1.546875q-0.421875 0.40625 -1.5625 0.40625q-1.140625 0 -1.5625 -0.40625q-0.421875 -0.40625 -0.421875 -1.515625q0 -1.125 0.421875 -1.53125q0.4375 -0.421875 1.59375 -0.421875q1.140625 0 1.546875 0.40625q0.421875 0.390625 0.421875 1.515625zm20.726562 23.515625q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.25 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.78125 0.046875q-0.5 0 -0.8125 -0.046875q-0.3125 -0.03125 -0.484375 -0.109375q-0.171875 -0.09375 -0.25 -0.1875q-0.078125 -0.109375 -0.078125 -0.265625l0 -10.296875q0 -1.5 -0.234375 -2.421875q-0.234375 -0.921875 -0.6875 -1.578125q-0.453125 -0.671875 -1.171875 -1.015625q-0.703125 -0.359375 -1.640625 -0.359375q-1.203125 0 -2.421875 0.859375q-1.203125 0.859375 -2.53125 2.515625l0 12.296875q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -17.578125q0 -0.15625 0.0625 -0.265625q0.0625 -0.109375 0.234375 -0.1875q0.171875 -0.09375 0.4375 -0.125q0.28125 -0.03125 0.734375 -0.03125q0.4375 0 0.71875 0.03125q0.28125 0.03125 0.4375 0.125q0.15625 0.078125 0.21875 0.1875q0.078125 0.109375 0.078125 0.265625l0 2.3125q1.484375 -1.65625 2.953125 -2.421875q1.46875 -0.78125 2.984375 -0.78125q1.75 0 2.953125 0.609375q1.203125 0.59375 1.9375 1.59375q0.75 0.984375 1.0625 2.328125q0.328125 1.328125 0.328125 3.203125l0 10.734375zm20.875 -9.5625q0 0.765625 -0.375 1.09375q-0.375 0.3125 -0.875 0.3125l-11.515625 0q0 1.46875 0.28125 2.640625q0.296875 1.171875 0.984375 2.015625q0.6875 0.84375 1.78125 1.296875q1.09375 0.4375 2.671875 0.4375q1.25 0 2.21875 -0.203125q0.984375 -0.203125 1.6875 -0.453125q0.71875 -0.265625 1.171875 -0.46875q0.46875 -0.203125 0.703125 -0.203125q0.140625 0 0.25 0.078125q0.109375 0.0625 0.15625 0.203125q0.0625 0.125 0.09375 0.375q0.03125 0.25 0.03125 0.59375q0 0.25 -0.03125 0.4375q-0.015625 0.1875 -0.046875 0.34375q-0.015625 0.140625 -0.09375 0.265625q-0.0625 0.109375 -0.171875 0.21875q-0.109375 0.109375 -0.640625 0.359375q-0.515625 0.234375 -1.359375 0.46875q-0.84375 0.234375 -1.953125 0.421875q-1.09375 0.1875 -2.34375 0.1875q-2.171875 0 -3.8125 -0.609375q-1.625 -0.609375 -2.734375 -1.796875q-1.109375 -1.1875 -1.6875 -2.984375q-0.5625 -1.796875 -0.5625 -4.1875q0 -2.265625 0.578125 -4.0625q0.59375 -1.8125 1.703125 -3.0625q1.109375 -1.265625 2.671875 -1.9375q1.5625 -0.6875 3.484375 -0.6875q2.078125 0 3.53125 0.671875q1.453125 0.65625 2.390625 1.78125q0.9375 1.125 1.375 2.640625q0.4375 1.515625 0.4375 3.234375l0 0.578125zm-3.234375 -0.953125q0.0625 -2.53125 -1.125 -3.96875q-1.1875 -1.453125 -3.5 -1.453125q-1.203125 0 -2.109375 0.453125q-0.890625 0.4375 -1.5 1.1875q-0.59375 0.734375 -0.9375 1.71875q-0.328125 0.984375 -0.359375 2.0625l9.53125 0zm34.214844 10.515625q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.25 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.78125 0.046875q-0.5 0 -0.8125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.171875 -0.09375 -0.25 -0.1875q-0.078125 -0.109375 -0.078125 -0.265625l0 -10.6875q0 -1.109375 -0.203125 -2.03125q-0.1875 -0.921875 -0.625 -1.578125q-0.421875 -0.671875 -1.09375 -1.015625q-0.65625 -0.359375 -1.5625 -0.359375q-1.109375 0 -2.234375 0.859375q-1.125 0.859375 -2.46875 2.515625l0 12.296875q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.1875 0.078125 -0.5 0.109375q-0.3125 0.046875 -0.78125 0.046875q-0.453125 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.25 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -10.6875q0 -1.109375 -0.21875 -2.03125q-0.21875 -0.921875 -0.65625 -1.578125q-0.421875 -0.671875 -1.078125 -1.015625q-0.65625 -0.359375 -1.546875 -0.359375q-1.109375 0 -2.25 0.859375q-1.125 0.859375 -2.453125 2.515625l0 12.296875q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -17.578125q0 -0.15625 0.0625 -0.265625q0.0625 -0.109375 0.234375 -0.1875q0.171875 -0.09375 0.4375 -0.125q0.28125 -0.03125 0.734375 -0.03125q0.4375 0 0.71875 0.03125q0.28125 0.03125 0.4375 0.125q0.15625 0.078125 0.21875 0.1875q0.078125 0.109375 0.078125 0.265625l0 2.3125q1.484375 -1.65625 2.875 -2.421875q1.390625 -0.78125 2.828125 -0.78125q1.09375 0 1.953125 0.265625q0.875 0.25 1.53125 0.71875q0.671875 0.453125 1.140625 1.09375q0.46875 0.625 0.78125 1.40625q0.875 -0.953125 1.65625 -1.609375q0.796875 -0.671875 1.53125 -1.078125q0.734375 -0.421875 1.421875 -0.609375q0.703125 -0.1875 1.40625 -0.1875q1.703125 0 2.84375 0.609375q1.15625 0.59375 1.859375 1.59375q0.71875 0.984375 1.015625 2.328125q0.3125 1.328125 0.3125 2.8125l0 11.125zm19.125 0.015625q0 0.234375 -0.15625 0.359375q-0.15625 0.109375 -0.4375 0.171875q-0.265625 0.0625 -0.796875 0.0625q-0.5 0 -0.8125 -0.0625q-0.296875 -0.0625 -0.4375 -0.171875q-0.140625 -0.125 -0.140625 -0.359375l0 -1.765625q-1.140625 1.234375 -2.5625 1.921875q-1.421875 0.6875 -3.0 0.6875q-1.390625 0 -2.515625 -0.375q-1.109375 -0.359375 -1.90625 -1.03125q-0.796875 -0.6875 -1.234375 -1.6875q-0.4375 -1.0 -0.4375 -2.265625q0 -1.484375 0.609375 -2.578125q0.609375 -1.09375 1.734375 -1.8125q1.140625 -0.71875 2.78125 -1.078125q1.640625 -0.375 3.6875 -0.375l2.421875 0l0 -1.359375q0 -1.015625 -0.21875 -1.796875q-0.21875 -0.78125 -0.703125 -1.296875q-0.46875 -0.515625 -1.234375 -0.78125q-0.75 -0.265625 -1.875 -0.265625q-1.1875 0 -2.140625 0.28125q-0.9375 0.28125 -1.65625 0.625q-0.703125 0.34375 -1.1875 0.625q-0.484375 0.28125 -0.71875 0.28125q-0.15625 0 -0.28125 -0.078125q-0.109375 -0.078125 -0.203125 -0.234375q-0.078125 -0.15625 -0.125 -0.390625q-0.03125 -0.25 -0.03125 -0.546875q0 -0.484375 0.0625 -0.765625q0.078125 -0.28125 0.34375 -0.53125q0.265625 -0.265625 0.90625 -0.609375q0.640625 -0.34375 1.484375 -0.625q0.84375 -0.28125 1.828125 -0.46875q1.0 -0.1875 2.015625 -0.1875q1.890625 0 3.21875 0.4375q1.328125 0.421875 2.140625 1.265625q0.828125 0.828125 1.203125 2.0625q0.375 1.21875 0.375 2.859375l0 11.859375zm-3.203125 -8.03125l-2.75 0q-1.328125 0 -2.3125 0.234375q-0.96875 0.21875 -1.625 0.65625q-0.640625 0.4375 -0.953125 1.0625q-0.296875 0.609375 -0.296875 1.40625q0 1.375 0.875 2.1875q0.875 0.796875 2.4375 0.796875q1.265625 0 2.34375 -0.640625q1.09375 -0.640625 2.28125 -1.96875l0 -3.734375zm18.253906 6.71875q0 0.5625 -0.078125 0.90625q-0.078125 0.328125 -0.234375 0.484375q-0.15625 0.15625 -0.46875 0.296875q-0.3125 0.140625 -0.71875 0.21875q-0.390625 0.09375 -0.84375 0.140625q-0.4375 0.0625 -0.890625 0.0625q-1.375 0 -2.359375 -0.359375q-0.96875 -0.359375 -1.59375 -1.09375q-0.625 -0.734375 -0.90625 -1.859375q-0.28125 -1.125 -0.28125 -2.640625l0 -10.28125l-2.453125 0q-0.296875 0 -0.484375 -0.3125q-0.171875 -0.3125 -0.171875 -1.015625q0 -0.359375 0.046875 -0.609375q0.0625 -0.265625 0.140625 -0.421875q0.078125 -0.171875 0.203125 -0.234375q0.125 -0.078125 0.28125 -0.078125l2.4375 0l0 -4.171875q0 -0.140625 0.0625 -0.25q0.078125 -0.125 0.265625 -0.203125q0.1875 -0.09375 0.5 -0.125q0.3125 -0.046875 0.78125 -0.046875q0.484375 0 0.796875 0.046875q0.3125 0.03125 0.484375 0.125q0.171875 0.078125 0.25 0.203125q0.078125 0.109375 0.078125 0.25l0 4.171875l4.515625 0q0.15625 0 0.265625 0.078125q0.125 0.0625 0.203125 0.234375q0.09375 0.15625 0.125 0.421875q0.046875 0.25 0.046875 0.609375q0 0.703125 -0.171875 1.015625q-0.171875 0.3125 -0.46875 0.3125l-4.515625 0l0 9.8125q0 1.8125 0.53125 2.75q0.546875 0.921875 1.9375 0.921875q0.453125 0 0.796875 -0.078125q0.359375 -0.09375 0.625 -0.1875q0.28125 -0.109375 0.46875 -0.1875q0.203125 -0.09375 0.359375 -0.09375q0.09375 0 0.171875 0.046875q0.09375 0.046875 0.140625 0.1875q0.046875 0.140625 0.078125 0.375q0.046875 0.234375 0.046875 0.578125zm7.4921875 1.296875q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -17.578125q0 -0.140625 0.0625 -0.25q0.078125 -0.125 0.265625 -0.203125q0.1875 -0.078125 0.5 -0.109375q0.3125 -0.046875 0.78125 -0.046875q0.484375 0 0.796875 0.046875q0.3125 0.03125 0.484375 0.109375q0.1875 0.078125 0.265625 0.203125q0.078125 0.109375 0.078125 0.25l0 17.578125zm0.359375 -23.515625q0 1.125 -0.4375 1.546875q-0.421875 0.40625 -1.5625 0.40625q-1.140625 0 -1.5625 -0.40625q-0.421875 -0.40625 -0.421875 -1.515625q0 -1.125 0.421875 -1.53125q0.4375 -0.421875 1.59375 -0.421875q1.140625 0 1.546875 0.40625q0.421875 0.390625 0.421875 1.515625zm18.226562 20.828125q0 0.34375 -0.015625 0.59375q-0.015625 0.234375 -0.078125 0.40625q-0.046875 0.15625 -0.109375 0.28125q-0.0625 0.125 -0.3125 0.375q-0.25 0.25 -0.84375 0.609375q-0.578125 0.359375 -1.3125 0.640625q-0.71875 0.28125 -1.578125 0.453125q-0.859375 0.1875 -1.78125 0.1875q-1.890625 0 -3.359375 -0.625q-1.46875 -0.625 -2.453125 -1.828125q-0.984375 -1.203125 -1.5 -2.953125q-0.515625 -1.75 -0.515625 -4.03125q0 -2.59375 0.625 -4.453125q0.640625 -1.875 1.734375 -3.0625q1.109375 -1.203125 2.59375 -1.765625q1.5 -0.578125 3.25 -0.578125q0.828125 0 1.625 0.15625q0.796875 0.15625 1.453125 0.40625q0.671875 0.25 1.1875 0.59375q0.515625 0.328125 0.75 0.5625q0.234375 0.234375 0.3125 0.375q0.09375 0.125 0.15625 0.3125q0.0625 0.1875 0.078125 0.421875q0.015625 0.234375 0.015625 0.578125q0 0.765625 -0.171875 1.078125q-0.171875 0.296875 -0.4375 0.296875q-0.28125 0 -0.671875 -0.3125q-0.375 -0.328125 -0.96875 -0.71875q-0.578125 -0.390625 -1.40625 -0.71875q-0.828125 -0.328125 -1.96875 -0.328125q-2.328125 0 -3.5625 1.796875q-1.234375 1.78125 -1.234375 5.1875q0 1.6875 0.3125 2.96875q0.328125 1.28125 0.953125 2.140625q0.625 0.859375 1.53125 1.28125q0.90625 0.421875 2.078125 0.421875q1.109375 0 1.953125 -0.34375q0.84375 -0.359375 1.453125 -0.78125q0.625 -0.421875 1.03125 -0.765625q0.421875 -0.34375 0.65625 -0.34375q0.140625 0 0.234375 0.078125q0.109375 0.078125 0.171875 0.265625q0.0625 0.1875 0.09375 0.46875q0.03125 0.28125 0.03125 0.671875zm23.648438 -6.171875q0 2.3125 -0.671875 4.125q-0.671875 1.796875 -1.921875 3.046875q-1.25 1.25 -3.046875 1.90625q-1.796875 0.640625 -4.078125 0.640625q-2.09375 0 -3.8125 -0.609375q-1.71875 -0.609375 -2.953125 -1.78125q-1.21875 -1.1875 -1.890625 -2.96875q-0.65625 -1.78125 -0.65625 -4.09375l0 -15.6875q0 -0.15625 0.078125 -0.265625q0.078125 -0.125 0.265625 -0.1875q0.203125 -0.078125 0.515625 -0.125q0.3125 -0.046875 0.8125 -0.046875q0.46875 0 0.796875 0.046875q0.34375 0.046875 0.515625 0.125q0.1875 0.0625 0.265625 0.1875q0.078125 0.109375 0.078125 0.265625l0 15.265625q0 1.765625 0.421875 3.078125q0.4375 1.296875 1.25 2.171875q0.8125 0.875 1.953125 1.3125q1.140625 0.4375 2.578125 0.4375q1.453125 0 2.59375 -0.421875q1.15625 -0.4375 1.9375 -1.296875q0.796875 -0.859375 1.21875 -2.125q0.421875 -1.28125 0.421875 -2.96875l0 -15.453125q0 -0.15625 0.078125 -0.265625q0.078125 -0.125 0.265625 -0.1875q0.203125 -0.078125 0.515625 -0.125q0.328125 -0.046875 0.8125 -0.046875q0.46875 0 0.78125 0.046875q0.328125 0.046875 0.515625 0.125q0.1875 0.0625 0.265625 0.1875q0.09375 0.109375 0.09375 0.265625l0 15.421875zm21.429688 8.859375q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.25 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.78125 0.046875q-0.5 0 -0.8125 -0.046875q-0.3125 -0.03125 -0.484375 -0.109375q-0.171875 -0.09375 -0.25 -0.1875q-0.078125 -0.109375 -0.078125 -0.265625l0 -10.296875q0 -1.5 -0.234375 -2.421875q-0.234375 -0.921875 -0.6875 -1.578125q-0.453125 -0.671875 -1.171875 -1.015625q-0.703125 -0.359375 -1.640625 -0.359375q-1.203125 0 -2.421875 0.859375q-1.203125 0.859375 -2.53125 2.515625l0 12.296875q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -17.578125q0 -0.15625 0.0625 -0.265625q0.0625 -0.109375 0.234375 -0.1875q0.171875 -0.09375 0.4375 -0.125q0.28125 -0.03125 0.734375 -0.03125q0.4375 0 0.71875 0.03125q0.28125 0.03125 0.4375 0.125q0.15625 0.078125 0.21875 0.1875q0.078125 0.109375 0.078125 0.265625l0 2.3125q1.484375 -1.65625 2.953125 -2.421875q1.46875 -0.78125 2.984375 -0.78125q1.75 0 2.953125 0.609375q1.203125 0.59375 1.9375 1.59375q0.75 0.984375 1.0625 2.328125q0.328125 1.328125 0.328125 3.203125l0 10.734375zm9.109375 0q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -17.578125q0 -0.140625 0.0625 -0.25q0.078125 -0.125 0.265625 -0.203125q0.1875 -0.078125 0.5 -0.109375q0.3125 -0.046875 0.78125 -0.046875q0.484375 0 0.796875 0.046875q0.3125 0.03125 0.484375 0.109375q0.1875 0.078125 0.265625 0.203125q0.078125 0.109375 0.078125 0.25l0 17.578125zm0.359375 -23.515625q0 1.125 -0.4375 1.546875q-0.421875 0.40625 -1.5625 0.40625q-1.140625 0 -1.5625 -0.40625q-0.421875 -0.40625 -0.421875 -1.515625q0 -1.125 0.421875 -1.53125q0.4375 -0.421875 1.59375 -0.421875q1.140625 0 1.546875 0.40625q0.421875 0.390625 0.421875 1.515625zm14.7265625 22.21875q0 0.5625 -0.078125 0.90625q-0.078125 0.328125 -0.234375 0.484375q-0.15625 0.15625 -0.46875 0.296875q-0.3125 0.140625 -0.71875 0.21875q-0.390625 0.09375 -0.84375 0.140625q-0.4375 0.0625 -0.890625 0.0625q-1.375 0 -2.359375 -0.359375q-0.96875 -0.359375 -1.59375 -1.09375q-0.625 -0.734375 -0.90625 -1.859375q-0.28125 -1.125 -0.28125 -2.640625l0 -10.28125l-2.453125 0q-0.296875 0 -0.484375 -0.3125q-0.171875 -0.3125 -0.171875 -1.015625q0 -0.359375 0.046875 -0.609375q0.0625 -0.265625 0.140625 -0.421875q0.078125 -0.171875 0.203125 -0.234375q0.125 -0.078125 0.28125 -0.078125l2.4375 0l0 -4.171875q0 -0.140625 0.0625 -0.25q0.078125 -0.125 0.265625 -0.203125q0.1875 -0.09375 0.5 -0.125q0.3125 -0.046875 0.78125 -0.046875q0.484375 0 0.796875 0.046875q0.3125 0.03125 0.484375 0.125q0.171875 0.078125 0.25 0.203125q0.078125 0.109375 0.078125 0.25l0 4.171875l4.515625 0q0.15625 0 0.265625 0.078125q0.125 0.0625 0.203125 0.234375q0.09375 0.15625 0.125 0.421875q0.046875 0.25 0.046875 0.609375q0 0.703125 -0.171875 1.015625q-0.171875 0.3125 -0.46875 0.3125l-4.515625 0l0 9.8125q0 1.8125 0.53125 2.75q0.546875 0.921875 1.9375 0.921875q0.453125 0 0.796875 -0.078125q0.359375 -0.09375 0.625 -0.1875q0.28125 -0.109375 0.46875 -0.1875q0.203125 -0.09375 0.359375 -0.09375q0.09375 0 0.171875 0.046875q0.09375 0.046875 0.140625 0.1875q0.046875 0.140625 0.078125 0.375q0.046875 0.234375 0.046875 0.578125zm23.554688 0.59375q0.15625 0.421875 0.171875 0.6875q0.015625 0.265625 -0.140625 0.40625q-0.15625 0.140625 -0.53125 0.171875q-0.359375 0.046875 -0.953125 0.046875q-0.609375 0 -0.96875 -0.03125q-0.359375 -0.03125 -0.546875 -0.09375q-0.1875 -0.078125 -0.28125 -0.1875q-0.078125 -0.125 -0.15625 -0.296875l-2.171875 -6.15625l-10.515625 0l-2.0625 6.078125q-0.0625 0.171875 -0.15625 0.296875q-0.09375 0.125 -0.28125 0.21875q-0.1875 0.09375 -0.53125 0.125q-0.34375 0.046875 -0.890625 0.046875q-0.5625 0 -0.921875 -0.0625q-0.359375 -0.046875 -0.515625 -0.171875q-0.140625 -0.140625 -0.140625 -0.40625q0.015625 -0.265625 0.171875 -0.703125l8.484375 -23.46875q0.078125 -0.21875 0.203125 -0.34375q0.125 -0.140625 0.359375 -0.21875q0.25 -0.078125 0.625 -0.109375q0.390625 -0.03125 0.96875 -0.03125q0.625 0 1.03125 0.03125q0.421875 0.03125 0.671875 0.109375q0.25 0.078125 0.390625 0.21875q0.140625 0.140625 0.21875 0.359375l8.46875 23.484375zm-10.875 -20.734375l-0.015625 0l-4.359375 12.609375l8.796875 0l-4.421875 -12.609375zm25.003906 5.0q0 0.4375 -0.03125 0.734375q-0.015625 0.28125 -0.078125 0.453125q-0.046875 0.171875 -0.140625 0.265625q-0.078125 0.078125 -0.234375 0.078125q-0.15625 0 -0.390625 -0.078125q-0.21875 -0.09375 -0.5 -0.1875q-0.28125 -0.09375 -0.640625 -0.171875q-0.34375 -0.078125 -0.765625 -0.078125q-0.484375 0 -0.953125 0.203125q-0.46875 0.1875 -0.984375 0.640625q-0.515625 0.453125 -1.09375 1.203125q-0.5625 0.734375 -1.234375 1.8125l0 11.5625q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -17.578125q0 -0.15625 0.0625 -0.265625q0.0625 -0.109375 0.234375 -0.1875q0.171875 -0.09375 0.4375 -0.125q0.28125 -0.03125 0.734375 -0.03125q0.4375 0 0.71875 0.03125q0.28125 0.03125 0.4375 0.125q0.15625 0.078125 0.21875 0.1875q0.078125 0.109375 0.078125 0.265625l0 2.546875q0.71875 -1.046875 1.34375 -1.703125q0.640625 -0.671875 1.203125 -1.046875q0.578125 -0.390625 1.125 -0.53125q0.5625 -0.15625 1.125 -0.15625q0.25 0 0.578125 0.03125q0.328125 0.03125 0.671875 0.109375q0.359375 0.078125 0.640625 0.1875q0.28125 0.09375 0.390625 0.1875q0.125 0.09375 0.15625 0.1875q0.046875 0.078125 0.078125 0.21875q0.03125 0.140625 0.03125 0.40625q0.015625 0.265625 0.015625 0.703125zm29.742188 16.4375q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.25 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.78125 0.046875q-0.5 0 -0.8125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.171875 -0.09375 -0.25 -0.1875q-0.078125 -0.109375 -0.078125 -0.265625l0 -10.6875q0 -1.109375 -0.203125 -2.03125q-0.1875 -0.921875 -0.625 -1.578125q-0.421875 -0.671875 -1.09375 -1.015625q-0.65625 -0.359375 -1.5625 -0.359375q-1.109375 0 -2.234375 0.859375q-1.125 0.859375 -2.46875 2.515625l0 12.296875q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.1875 0.078125 -0.5 0.109375q-0.3125 0.046875 -0.78125 0.046875q-0.453125 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.25 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -10.6875q0 -1.109375 -0.21875 -2.03125q-0.21875 -0.921875 -0.65625 -1.578125q-0.421875 -0.671875 -1.078125 -1.015625q-0.65625 -0.359375 -1.546875 -0.359375q-1.109375 0 -2.25 0.859375q-1.125 0.859375 -2.453125 2.515625l0 12.296875q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -17.578125q0 -0.15625 0.0625 -0.265625q0.0625 -0.109375 0.234375 -0.1875q0.171875 -0.09375 0.4375 -0.125q0.28125 -0.03125 0.734375 -0.03125q0.4375 0 0.71875 0.03125q0.28125 0.03125 0.4375 0.125q0.15625 0.078125 0.21875 0.1875q0.078125 0.109375 0.078125 0.265625l0 2.3125q1.484375 -1.65625 2.875 -2.421875q1.390625 -0.78125 2.828125 -0.78125q1.09375 0 1.953125 0.265625q0.875 0.25 1.53125 0.71875q0.671875 0.453125 1.140625 1.09375q0.46875 0.625 0.78125 1.40625q0.875 -0.953125 1.65625 -1.609375q0.796875 -0.671875 1.53125 -1.078125q0.734375 -0.421875 1.421875 -0.609375q0.703125 -0.1875 1.40625 -0.1875q1.703125 0 2.84375 0.609375q1.15625 0.59375 1.859375 1.59375q0.71875 0.984375 1.015625 2.328125q0.3125 1.328125 0.3125 2.8125l0 11.125zm19.125 0.015625q0 0.234375 -0.15625 0.359375q-0.15625 0.109375 -0.4375 0.171875q-0.265625 0.0625 -0.796875 0.0625q-0.5 0 -0.8125 -0.0625q-0.296875 -0.0625 -0.4375 -0.171875q-0.140625 -0.125 -0.140625 -0.359375l0 -1.765625q-1.140625 1.234375 -2.5625 1.921875q-1.421875 0.6875 -3.0 0.6875q-1.390625 0 -2.515625 -0.375q-1.109375 -0.359375 -1.90625 -1.03125q-0.796875 -0.6875 -1.234375 -1.6875q-0.4375 -1.0 -0.4375 -2.265625q0 -1.484375 0.609375 -2.578125q0.609375 -1.09375 1.734375 -1.8125q1.140625 -0.71875 2.78125 -1.078125q1.640625 -0.375 3.6875 -0.375l2.421875 0l0 -1.359375q0 -1.015625 -0.21875 -1.796875q-0.21875 -0.78125 -0.703125 -1.296875q-0.46875 -0.515625 -1.234375 -0.78125q-0.75 -0.265625 -1.875 -0.265625q-1.1875 0 -2.140625 0.28125q-0.9375 0.28125 -1.65625 0.625q-0.703125 0.34375 -1.1875 0.625q-0.484375 0.28125 -0.71875 0.28125q-0.15625 0 -0.28125 -0.078125q-0.109375 -0.078125 -0.203125 -0.234375q-0.078125 -0.15625 -0.125 -0.390625q-0.03125 -0.25 -0.03125 -0.546875q0 -0.484375 0.0625 -0.765625q0.078125 -0.28125 0.34375 -0.53125q0.265625 -0.265625 0.90625 -0.609375q0.640625 -0.34375 1.484375 -0.625q0.84375 -0.28125 1.828125 -0.46875q1.0 -0.1875 2.015625 -0.1875q1.890625 0 3.21875 0.4375q1.328125 0.421875 2.140625 1.265625q0.828125 0.828125 1.203125 2.0625q0.375 1.21875 0.375 2.859375l0 11.859375zm-3.203125 -8.03125l-2.75 0q-1.328125 0 -2.3125 0.234375q-0.96875 0.21875 -1.625 0.65625q-0.640625 0.4375 -0.953125 1.0625q-0.296875 0.609375 -0.296875 1.40625q0 1.375 0.875 2.1875q0.875 0.796875 2.4375 0.796875q1.265625 0 2.34375 -0.640625q1.09375 -0.640625 2.28125 -1.96875l0 -3.734375zm19.394531 -8.421875q0 0.4375 -0.03125 0.734375q-0.015625 0.28125 -0.078125 0.453125q-0.046875 0.171875 -0.140625 0.265625q-0.078125 0.078125 -0.234375 0.078125q-0.15625 0 -0.390625 -0.078125q-0.21875 -0.09375 -0.5 -0.1875q-0.28125 -0.09375 -0.640625 -0.171875q-0.34375 -0.078125 -0.765625 -0.078125q-0.484375 0 -0.953125 0.203125q-0.46875 0.1875 -0.984375 0.640625q-0.515625 0.453125 -1.09375 1.203125q-0.5625 0.734375 -1.234375 1.8125l0 11.5625q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -17.578125q0 -0.15625 0.0625 -0.265625q0.0625 -0.109375 0.234375 -0.1875q0.171875 -0.09375 0.4375 -0.125q0.28125 -0.03125 0.734375 -0.03125q0.4375 0 0.71875 0.03125q0.28125 0.03125 0.4375 0.125q0.15625 0.078125 0.21875 0.1875q0.078125 0.109375 0.078125 0.265625l0 2.546875q0.71875 -1.046875 1.34375 -1.703125q0.640625 -0.671875 1.203125 -1.046875q0.578125 -0.390625 1.125 -0.53125q0.5625 -0.15625 1.125 -0.15625q0.25 0 0.578125 0.03125q0.328125 0.03125 0.671875 0.109375q0.359375 0.078125 0.640625 0.1875q0.28125 0.09375 0.390625 0.1875q0.125 0.09375 0.15625 0.1875q0.046875 0.078125 0.078125 0.21875q0.03125 0.140625 0.03125 0.40625q0.015625 0.265625 0.015625 0.703125zm18.539062 9.6875q0 1.75 -0.609375 3.140625q-0.609375 1.390625 -1.75 2.390625q-1.125 1.0 -2.78125 1.546875q-1.65625 0.53125 -3.75 0.53125q-1.265625 0 -2.375 -0.21875q-1.109375 -0.203125 -1.96875 -0.484375q-0.859375 -0.28125 -1.421875 -0.578125q-0.5625 -0.3125 -0.71875 -0.4375q-0.140625 -0.140625 -0.21875 -0.28125q-0.078125 -0.140625 -0.140625 -0.328125q-0.046875 -0.203125 -0.078125 -0.484375q-0.03125 -0.28125 -0.03125 -0.6875q0 -0.703125 0.125 -0.96875q0.140625 -0.28125 0.40625 -0.28125q0.171875 0 0.6875 0.3125q0.515625 0.3125 1.328125 0.671875q0.8125 0.359375 1.890625 0.671875q1.09375 0.3125 2.421875 0.3125q1.28125 0 2.25 -0.328125q0.984375 -0.328125 1.640625 -0.9375q0.671875 -0.609375 1.0 -1.4375q0.34375 -0.828125 0.34375 -1.8125q0 -1.0625 -0.421875 -1.921875q-0.421875 -0.859375 -1.234375 -1.484375q-0.8125 -0.625 -2.0 -0.953125q-1.171875 -0.34375 -2.671875 -0.34375l-2.40625 0q-0.15625 0 -0.3125 -0.0625q-0.140625 -0.078125 -0.25 -0.234375q-0.109375 -0.15625 -0.171875 -0.40625q-0.0625 -0.25 -0.0625 -0.65625q0 -0.375 0.046875 -0.609375q0.0625 -0.25 0.171875 -0.390625q0.109375 -0.15625 0.234375 -0.21875q0.140625 -0.078125 0.328125 -0.078125l2.203125 0q1.28125 0 2.3125 -0.328125q1.03125 -0.328125 1.734375 -0.953125q0.71875 -0.625 1.09375 -1.5q0.390625 -0.875 0.390625 -1.9375q0 -0.78125 -0.265625 -1.5q-0.25 -0.71875 -0.765625 -1.234375q-0.5 -0.53125 -1.296875 -0.828125q-0.78125 -0.3125 -1.8125 -0.3125q-1.140625 0 -2.09375 0.34375q-0.9375 0.34375 -1.6875 0.734375q-0.734375 0.390625 -1.234375 0.734375q-0.484375 0.34375 -0.671875 0.34375q-0.140625 0 -0.25 -0.046875q-0.109375 -0.0625 -0.171875 -0.203125q-0.0625 -0.140625 -0.09375 -0.40625q-0.03125 -0.265625 -0.03125 -0.703125q0 -0.28125 0.015625 -0.5q0.015625 -0.234375 0.078125 -0.390625q0.0625 -0.171875 0.140625 -0.3125q0.078125 -0.140625 0.265625 -0.328125q0.1875 -0.1875 0.75 -0.53125q0.5625 -0.359375 1.390625 -0.6875q0.828125 -0.34375 1.90625 -0.578125q1.09375 -0.234375 2.34375 -0.234375q1.765625 0 3.09375 0.453125q1.328125 0.4375 2.203125 1.265625q0.890625 0.8125 1.328125 1.953125q0.453125 1.140625 0.453125 2.53125q0 1.1875 -0.3125 2.21875q-0.3125 1.03125 -0.921875 1.828125q-0.609375 0.78125 -1.484375 1.34375q-0.875 0.546875 -2.03125 0.765625l0 0.03125q1.3125 0.140625 2.390625 0.65625q1.078125 0.515625 1.859375 1.296875q0.78125 0.78125 1.21875 1.828125q0.453125 1.046875 0.453125 2.234375z" fill-rule="nonzero"></path><defs><linearGradient id="gdd34d662f_0_0.4" gradientUnits="userSpaceOnUse" gradientTransform="matrix(21.31145760879976 0.0 0.0 5.765325667956162 489.4230086614173 407.3009950131234)" spreadMethod="pad" x1="21.31122313092855" y1="21.311457609880964" x2="21.311457609880964" y2="2.3711293843030903E-9"><stop offset="0.0" stop-color="#bedbff"></stop><stop offset="0.35" stop-color="#d1e5fe"></stop><stop offset="1.0" stop-color="#eef5ff"></stop></linearGradient></defs><path fill="url(#gdd34d662f_0_0.4)" d="m489.423 407.301l454.17325 0l0 122.86612l-454.17325 0z" fill-rule="nonzero"></path><path stroke="#4a7dbb" stroke-width="1.0" stroke-linejoin="round" stroke-linecap="butt" d="m489.423 407.301l454.17325 0l0 122.86612l-454.17325 0z" fill-rule="nonzero"></path><path fill="#000000" d="m559.77136 482.5872q0 0.15625 -0.078125 0.28125q-0.0625 0.125 -0.265625 0.203125q-0.1875 0.078125 -0.515625 0.125q-0.328125 0.0625 -0.859375 0.0625q-0.6875 0 -1.125 -0.0625q-0.421875 -0.0625 -0.640625 -0.21875q-0.203125 -0.15625 -0.34375 -0.359375l-9.296875 -12.625l0 12.625q0 0.140625 -0.078125 0.265625q-0.078125 0.125 -0.28125 0.203125q-0.1875 0.0625 -0.515625 0.109375q-0.3125 0.0625 -0.796875 0.0625q-0.46875 0 -0.8125 -0.0625q-0.328125 -0.046875 -0.53125 -0.109375q-0.1875 -0.078125 -0.265625 -0.203125q-0.078125 -0.125 -0.078125 -0.265625l0 -24.25q0 -0.15625 0.078125 -0.265625q0.078125 -0.125 0.265625 -0.1875q0.203125 -0.078125 0.53125 -0.125q0.34375 -0.046875 0.8125 -0.046875q0.484375 0 0.796875 0.046875q0.328125 0.046875 0.515625 0.125q0.203125 0.0625 0.28125 0.1875q0.078125 0.109375 0.078125 0.265625l0 11.234375l8.953125 -11.234375q0.109375 -0.171875 0.265625 -0.28125q0.15625 -0.125 0.375 -0.1875q0.234375 -0.078125 0.546875 -0.109375q0.328125 -0.046875 0.84375 -0.046875q0.5 0 0.8125 0.046875q0.3125 0.046875 0.5 0.125q0.1875 0.078125 0.25 0.203125q0.078125 0.109375 0.078125 0.25q0 0.25 -0.140625 0.515625q-0.125 0.25 -0.46875 0.6875l-8.375 10.03125l9.015625 11.984375q0.328125 0.515625 0.390625 0.703125q0.078125 0.171875 0.078125 0.296875zm7.15625 0.0625q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -17.578125q0 -0.140625 0.0625 -0.25q0.078125 -0.125 0.265625 -0.203125q0.1875 -0.078125 0.5 -0.109375q0.3125 -0.046875 0.78125 -0.046875q0.484375 0 0.796875 0.046875q0.3125 0.03125 0.484375 0.109375q0.1875 0.078125 0.265625 0.203125q0.078125 0.109375 0.078125 0.25l0 17.578125zm0.359375 -23.515625q0 1.125 -0.4375 1.546875q-0.421875 0.40625 -1.5625 0.40625q-1.140625 0 -1.5625 -0.40625q-0.421875 -0.40625 -0.421875 -1.515625q0 -1.125 0.421875 -1.53125q0.4375 -0.421875 1.59375 -0.421875q1.140625 0 1.546875 0.40625q0.421875 0.390625 0.421875 1.515625zm20.726562 23.515625q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.25 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.78125 0.046875q-0.5 0 -0.8125 -0.046875q-0.3125 -0.03125 -0.484375 -0.109375q-0.171875 -0.09375 -0.25 -0.1875q-0.078125 -0.109375 -0.078125 -0.265625l0 -10.296875q0 -1.5 -0.234375 -2.421875q-0.234375 -0.921875 -0.6875 -1.578125q-0.453125 -0.671875 -1.171875 -1.015625q-0.703125 -0.359375 -1.640625 -0.359375q-1.203125 0 -2.421875 0.859375q-1.203125 0.859375 -2.53125 2.515625l0 12.296875q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -17.578125q0 -0.15625 0.0625 -0.265625q0.0625 -0.109375 0.234375 -0.1875q0.171875 -0.09375 0.4375 -0.125q0.28125 -0.03125 0.734375 -0.03125q0.4375 0 0.71875 0.03125q0.28125 0.03125 0.4375 0.125q0.15625 0.078125 0.21875 0.1875q0.078125 0.109375 0.078125 0.265625l0 2.3125q1.484375 -1.65625 2.953125 -2.421875q1.46875 -0.78125 2.984375 -0.78125q1.75 0 2.953125 0.609375q1.203125 0.59375 1.9375 1.59375q0.75 0.984375 1.0625 2.328125q0.328125 1.328125 0.328125 3.203125l0 10.734375zm20.875 -9.5625q0 0.765625 -0.375 1.09375q-0.375 0.3125 -0.875 0.3125l-11.515625 0q0 1.46875 0.28125 2.640625q0.296875 1.171875 0.984375 2.015625q0.6875 0.84375 1.78125 1.296875q1.09375 0.4375 2.671875 0.4375q1.25 0 2.21875 -0.203125q0.984375 -0.203125 1.6875 -0.453125q0.71875 -0.265625 1.171875 -0.46875q0.46875 -0.203125 0.703125 -0.203125q0.140625 0 0.25 0.078125q0.109375 0.0625 0.15625 0.203125q0.0625 0.125 0.09375 0.375q0.03125 0.25 0.03125 0.59375q0 0.25 -0.03125 0.4375q-0.015625 0.1875 -0.046875 0.34375q-0.015625 0.140625 -0.09375 0.265625q-0.0625 0.109375 -0.171875 0.21875q-0.109375 0.109375 -0.640625 0.359375q-0.515625 0.234375 -1.359375 0.46875q-0.84375 0.234375 -1.953125 0.421875q-1.09375 0.1875 -2.34375 0.1875q-2.171875 0 -3.8125 -0.609375q-1.625 -0.609375 -2.734375 -1.796875q-1.109375 -1.1875 -1.6875 -2.984375q-0.5625 -1.796875 -0.5625 -4.1875q0 -2.265625 0.578125 -4.0625q0.59375 -1.8125 1.703125 -3.0625q1.109375 -1.265625 2.671875 -1.9375q1.5625 -0.6875 3.484375 -0.6875q2.078125 0 3.53125 0.671875q1.453125 0.65625 2.390625 1.78125q0.9375 1.125 1.375 2.640625q0.4375 1.515625 0.4375 3.234375l0 0.578125zm-3.234375 -0.953125q0.0625 -2.53125 -1.125 -3.96875q-1.1875 -1.453125 -3.5 -1.453125q-1.203125 0 -2.109375 0.453125q-0.890625 0.4375 -1.5 1.1875q-0.59375 0.734375 -0.9375 1.71875q-0.328125 0.984375 -0.359375 2.0625l9.53125 0zm34.214844 10.515625q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.25 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.78125 0.046875q-0.5 0 -0.8125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.171875 -0.09375 -0.25 -0.1875q-0.078125 -0.109375 -0.078125 -0.265625l0 -10.6875q0 -1.109375 -0.203125 -2.03125q-0.1875 -0.921875 -0.625 -1.578125q-0.421875 -0.671875 -1.09375 -1.015625q-0.65625 -0.359375 -1.5625 -0.359375q-1.109375 0 -2.234375 0.859375q-1.125 0.859375 -2.46875 2.515625l0 12.296875q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.1875 0.078125 -0.5 0.109375q-0.3125 0.046875 -0.78125 0.046875q-0.453125 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.25 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -10.6875q0 -1.109375 -0.21875 -2.03125q-0.21875 -0.921875 -0.65625 -1.578125q-0.421875 -0.671875 -1.078125 -1.015625q-0.65625 -0.359375 -1.546875 -0.359375q-1.109375 0 -2.25 0.859375q-1.125 0.859375 -2.453125 2.515625l0 12.296875q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -17.578125q0 -0.15625 0.0625 -0.265625q0.0625 -0.109375 0.234375 -0.1875q0.171875 -0.09375 0.4375 -0.125q0.28125 -0.03125 0.734375 -0.03125q0.4375 0 0.71875 0.03125q0.28125 0.03125 0.4375 0.125q0.15625 0.078125 0.21875 0.1875q0.078125 0.109375 0.078125 0.265625l0 2.3125q1.484375 -1.65625 2.875 -2.421875q1.390625 -0.78125 2.828125 -0.78125q1.09375 0 1.953125 0.265625q0.875 0.25 1.53125 0.71875q0.671875 0.453125 1.140625 1.09375q0.46875 0.625 0.78125 1.40625q0.875 -0.953125 1.65625 -1.609375q0.796875 -0.671875 1.53125 -1.078125q0.734375 -0.421875 1.421875 -0.609375q0.703125 -0.1875 1.40625 -0.1875q1.703125 0 2.84375 0.609375q1.15625 0.59375 1.859375 1.59375q0.71875 0.984375 1.015625 2.328125q0.3125 1.328125 0.3125 2.8125l0 11.125zm19.125 0.015625q0 0.234375 -0.15625 0.359375q-0.15625 0.109375 -0.4375 0.171875q-0.265625 0.0625 -0.796875 0.0625q-0.5 0 -0.8125 -0.0625q-0.296875 -0.0625 -0.4375 -0.171875q-0.140625 -0.125 -0.140625 -0.359375l0 -1.765625q-1.140625 1.234375 -2.5625 1.921875q-1.421875 0.6875 -3.0 0.6875q-1.390625 0 -2.515625 -0.375q-1.109375 -0.359375 -1.90625 -1.03125q-0.796875 -0.6875 -1.234375 -1.6875q-0.4375 -1.0 -0.4375 -2.265625q0 -1.484375 0.609375 -2.578125q0.609375 -1.09375 1.734375 -1.8125q1.140625 -0.71875 2.78125 -1.078125q1.640625 -0.375 3.6875 -0.375l2.421875 0l0 -1.359375q0 -1.015625 -0.21875 -1.796875q-0.21875 -0.78125 -0.703125 -1.296875q-0.46875 -0.515625 -1.234375 -0.78125q-0.75 -0.265625 -1.875 -0.265625q-1.1875 0 -2.140625 0.28125q-0.9375 0.28125 -1.65625 0.625q-0.703125 0.34375 -1.1875 0.625q-0.484375 0.28125 -0.71875 0.28125q-0.15625 0 -0.28125 -0.078125q-0.109375 -0.078125 -0.203125 -0.234375q-0.078125 -0.15625 -0.125 -0.390625q-0.03125 -0.25 -0.03125 -0.546875q0 -0.484375 0.0625 -0.765625q0.078125 -0.28125 0.34375 -0.53125q0.265625 -0.265625 0.90625 -0.609375q0.640625 -0.34375 1.484375 -0.625q0.84375 -0.28125 1.828125 -0.46875q1.0 -0.1875 2.015625 -0.1875q1.890625 0 3.21875 0.4375q1.328125 0.421875 2.140625 1.265625q0.828125 0.828125 1.203125 2.0625q0.375 1.21875 0.375 2.859375l0 11.859375zm-3.203125 -8.03125l-2.75 0q-1.328125 0 -2.3125 0.234375q-0.96875 0.21875 -1.625 0.65625q-0.640625 0.4375 -0.953125 1.0625q-0.296875 0.609375 -0.296875 1.40625q0 1.375 0.875 2.1875q0.875 0.796875 2.4375 0.796875q1.265625 0 2.34375 -0.640625q1.09375 -0.640625 2.28125 -1.96875l0 -3.734375zm18.253906 6.71875q0 0.5625 -0.078125 0.90625q-0.078125 0.328125 -0.234375 0.484375q-0.15625 0.15625 -0.46875 0.296875q-0.3125 0.140625 -0.71875 0.21875q-0.390625 0.09375 -0.84375 0.140625q-0.4375 0.0625 -0.890625 0.0625q-1.375 0 -2.359375 -0.359375q-0.96875 -0.359375 -1.59375 -1.09375q-0.625 -0.734375 -0.90625 -1.859375q-0.28125 -1.125 -0.28125 -2.640625l0 -10.28125l-2.453125 0q-0.296875 0 -0.484375 -0.3125q-0.171875 -0.3125 -0.171875 -1.015625q0 -0.359375 0.046875 -0.609375q0.0625 -0.265625 0.140625 -0.421875q0.078125 -0.171875 0.203125 -0.234375q0.125 -0.078125 0.28125 -0.078125l2.4375 0l0 -4.171875q0 -0.140625 0.0625 -0.25q0.078125 -0.125 0.265625 -0.203125q0.1875 -0.09375 0.5 -0.125q0.3125 -0.046875 0.78125 -0.046875q0.484375 0 0.796875 0.046875q0.3125 0.03125 0.484375 0.125q0.171875 0.078125 0.25 0.203125q0.078125 0.109375 0.078125 0.25l0 4.171875l4.515625 0q0.15625 0 0.265625 0.078125q0.125 0.0625 0.203125 0.234375q0.09375 0.15625 0.125 0.421875q0.046875 0.25 0.046875 0.609375q0 0.703125 -0.171875 1.015625q-0.171875 0.3125 -0.46875 0.3125l-4.515625 0l0 9.8125q0 1.8125 0.53125 2.75q0.546875 0.921875 1.9375 0.921875q0.453125 0 0.796875 -0.078125q0.359375 -0.09375 0.625 -0.1875q0.28125 -0.109375 0.46875 -0.1875q0.203125 -0.09375 0.359375 -0.09375q0.09375 0 0.171875 0.046875q0.09375 0.046875 0.140625 0.1875q0.046875 0.140625 0.078125 0.375q0.046875 0.234375 0.046875 0.578125zm7.4921875 1.296875q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -17.578125q0 -0.140625 0.0625 -0.25q0.078125 -0.125 0.265625 -0.203125q0.1875 -0.078125 0.5 -0.109375q0.3125 -0.046875 0.78125 -0.046875q0.484375 0 0.796875 0.046875q0.3125 0.03125 0.484375 0.109375q0.1875 0.078125 0.265625 0.203125q0.078125 0.109375 0.078125 0.25l0 17.578125zm0.359375 -23.515625q0 1.125 -0.4375 1.546875q-0.421875 0.40625 -1.5625 0.40625q-1.140625 0 -1.5625 -0.40625q-0.421875 -0.40625 -0.421875 -1.515625q0 -1.125 0.421875 -1.53125q0.4375 -0.421875 1.59375 -0.421875q1.140625 0 1.546875 0.40625q0.421875 0.390625 0.421875 1.515625zm18.226562 20.828125q0 0.34375 -0.015625 0.59375q-0.015625 0.234375 -0.078125 0.40625q-0.046875 0.15625 -0.109375 0.28125q-0.0625 0.125 -0.3125 0.375q-0.25 0.25 -0.84375 0.609375q-0.578125 0.359375 -1.3125 0.640625q-0.71875 0.28125 -1.578125 0.453125q-0.859375 0.1875 -1.78125 0.1875q-1.890625 0 -3.359375 -0.625q-1.46875 -0.625 -2.453125 -1.828125q-0.984375 -1.203125 -1.5 -2.953125q-0.515625 -1.75 -0.515625 -4.03125q0 -2.59375 0.625 -4.453125q0.640625 -1.875 1.734375 -3.0625q1.109375 -1.203125 2.59375 -1.765625q1.5 -0.578125 3.25 -0.578125q0.828125 0 1.625 0.15625q0.796875 0.15625 1.453125 0.40625q0.671875 0.25 1.1875 0.59375q0.515625 0.328125 0.75 0.5625q0.234375 0.234375 0.3125 0.375q0.09375 0.125 0.15625 0.3125q0.0625 0.1875 0.078125 0.421875q0.015625 0.234375 0.015625 0.578125q0 0.765625 -0.171875 1.078125q-0.171875 0.296875 -0.4375 0.296875q-0.28125 0 -0.671875 -0.3125q-0.375 -0.328125 -0.96875 -0.71875q-0.578125 -0.390625 -1.40625 -0.71875q-0.828125 -0.328125 -1.96875 -0.328125q-2.328125 0 -3.5625 1.796875q-1.234375 1.78125 -1.234375 5.1875q0 1.6875 0.3125 2.96875q0.328125 1.28125 0.953125 2.140625q0.625 0.859375 1.53125 1.28125q0.90625 0.421875 2.078125 0.421875q1.109375 0 1.953125 -0.34375q0.84375 -0.359375 1.453125 -0.78125q0.625 -0.421875 1.03125 -0.765625q0.421875 -0.34375 0.65625 -0.34375q0.140625 0 0.234375 0.078125q0.109375 0.078125 0.171875 0.265625q0.0625 0.1875 0.09375 0.46875q0.03125 0.28125 0.03125 0.671875zm23.648438 -6.171875q0 2.3125 -0.671875 4.125q-0.671875 1.796875 -1.921875 3.046875q-1.25 1.25 -3.046875 1.90625q-1.796875 0.640625 -4.078125 0.640625q-2.09375 0 -3.8125 -0.609375q-1.71875 -0.609375 -2.953125 -1.78125q-1.21875 -1.1875 -1.890625 -2.96875q-0.65625 -1.78125 -0.65625 -4.09375l0 -15.6875q0 -0.15625 0.078125 -0.265625q0.078125 -0.125 0.265625 -0.1875q0.203125 -0.078125 0.515625 -0.125q0.3125 -0.046875 0.8125 -0.046875q0.46875 0 0.796875 0.046875q0.34375 0.046875 0.515625 0.125q0.1875 0.0625 0.265625 0.1875q0.078125 0.109375 0.078125 0.265625l0 15.265625q0 1.765625 0.421875 3.078125q0.4375 1.296875 1.25 2.171875q0.8125 0.875 1.953125 1.3125q1.140625 0.4375 2.578125 0.4375q1.453125 0 2.59375 -0.421875q1.15625 -0.4375 1.9375 -1.296875q0.796875 -0.859375 1.21875 -2.125q0.421875 -1.28125 0.421875 -2.96875l0 -15.453125q0 -0.15625 0.078125 -0.265625q0.078125 -0.125 0.265625 -0.1875q0.203125 -0.078125 0.515625 -0.125q0.328125 -0.046875 0.8125 -0.046875q0.46875 0 0.78125 0.046875q0.328125 0.046875 0.515625 0.125q0.1875 0.0625 0.265625 0.1875q0.09375 0.109375 0.09375 0.265625l0 15.421875zm21.429688 8.859375q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.25 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.78125 0.046875q-0.5 0 -0.8125 -0.046875q-0.3125 -0.03125 -0.484375 -0.109375q-0.171875 -0.09375 -0.25 -0.1875q-0.078125 -0.109375 -0.078125 -0.265625l0 -10.296875q0 -1.5 -0.234375 -2.421875q-0.234375 -0.921875 -0.6875 -1.578125q-0.453125 -0.671875 -1.171875 -1.015625q-0.703125 -0.359375 -1.640625 -0.359375q-1.203125 0 -2.421875 0.859375q-1.203125 0.859375 -2.53125 2.515625l0 12.296875q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -17.578125q0 -0.15625 0.0625 -0.265625q0.0625 -0.109375 0.234375 -0.1875q0.171875 -0.09375 0.4375 -0.125q0.28125 -0.03125 0.734375 -0.03125q0.4375 0 0.71875 0.03125q0.28125 0.03125 0.4375 0.125q0.15625 0.078125 0.21875 0.1875q0.078125 0.109375 0.078125 0.265625l0 2.3125q1.484375 -1.65625 2.953125 -2.421875q1.46875 -0.78125 2.984375 -0.78125q1.75 0 2.953125 0.609375q1.203125 0.59375 1.9375 1.59375q0.75 0.984375 1.0625 2.328125q0.328125 1.328125 0.328125 3.203125l0 10.734375zm9.109375 0q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -17.578125q0 -0.140625 0.0625 -0.25q0.078125 -0.125 0.265625 -0.203125q0.1875 -0.078125 0.5 -0.109375q0.3125 -0.046875 0.78125 -0.046875q0.484375 0 0.796875 0.046875q0.3125 0.03125 0.484375 0.109375q0.1875 0.078125 0.265625 0.203125q0.078125 0.109375 0.078125 0.25l0 17.578125zm0.359375 -23.515625q0 1.125 -0.4375 1.546875q-0.421875 0.40625 -1.5625 0.40625q-1.140625 0 -1.5625 -0.40625q-0.421875 -0.40625 -0.421875 -1.515625q0 -1.125 0.421875 -1.53125q0.4375 -0.421875 1.59375 -0.421875q1.140625 0 1.546875 0.40625q0.421875 0.390625 0.421875 1.515625zm14.7265625 22.21875q0 0.5625 -0.078125 0.90625q-0.078125 0.328125 -0.234375 0.484375q-0.15625 0.15625 -0.46875 0.296875q-0.3125 0.140625 -0.71875 0.21875q-0.390625 0.09375 -0.84375 0.140625q-0.4375 0.0625 -0.890625 0.0625q-1.375 0 -2.359375 -0.359375q-0.96875 -0.359375 -1.59375 -1.09375q-0.625 -0.734375 -0.90625 -1.859375q-0.28125 -1.125 -0.28125 -2.640625l0 -10.28125l-2.453125 0q-0.296875 0 -0.484375 -0.3125q-0.171875 -0.3125 -0.171875 -1.015625q0 -0.359375 0.046875 -0.609375q0.0625 -0.265625 0.140625 -0.421875q0.078125 -0.171875 0.203125 -0.234375q0.125 -0.078125 0.28125 -0.078125l2.4375 0l0 -4.171875q0 -0.140625 0.0625 -0.25q0.078125 -0.125 0.265625 -0.203125q0.1875 -0.09375 0.5 -0.125q0.3125 -0.046875 0.78125 -0.046875q0.484375 0 0.796875 0.046875q0.3125 0.03125 0.484375 0.125q0.171875 0.078125 0.25 0.203125q0.078125 0.109375 0.078125 0.25l0 4.171875l4.515625 0q0.15625 0 0.265625 0.078125q0.125 0.0625 0.203125 0.234375q0.09375 0.15625 0.125 0.421875q0.046875 0.25 0.046875 0.609375q0 0.703125 -0.171875 1.015625q-0.171875 0.3125 -0.46875 0.3125l-4.515625 0l0 9.8125q0 1.8125 0.53125 2.75q0.546875 0.921875 1.9375 0.921875q0.453125 0 0.796875 -0.078125q0.359375 -0.09375 0.625 -0.1875q0.28125 -0.109375 0.46875 -0.1875q0.203125 -0.09375 0.359375 -0.09375q0.09375 0 0.171875 0.046875q0.09375 0.046875 0.140625 0.1875q0.046875 0.140625 0.078125 0.375q0.046875 0.234375 0.046875 0.578125zm23.554688 0.59375q0.15625 0.421875 0.171875 0.6875q0.015625 0.265625 -0.140625 0.40625q-0.15625 0.140625 -0.53125 0.171875q-0.359375 0.046875 -0.953125 0.046875q-0.609375 0 -0.96875 -0.03125q-0.359375 -0.03125 -0.546875 -0.09375q-0.1875 -0.078125 -0.28125 -0.1875q-0.078125 -0.125 -0.15625 -0.296875l-2.171875 -6.15625l-10.515625 0l-2.0625 6.078125q-0.0625 0.171875 -0.15625 0.296875q-0.09375 0.125 -0.28125 0.21875q-0.1875 0.09375 -0.53125 0.125q-0.34375 0.046875 -0.890625 0.046875q-0.5625 0 -0.921875 -0.0625q-0.359375 -0.046875 -0.515625 -0.171875q-0.140625 -0.140625 -0.140625 -0.40625q0.015625 -0.265625 0.171875 -0.703125l8.484375 -23.46875q0.078125 -0.21875 0.203125 -0.34375q0.125 -0.140625 0.359375 -0.21875q0.25 -0.078125 0.625 -0.109375q0.390625 -0.03125 0.96875 -0.03125q0.625 0 1.03125 0.03125q0.421875 0.03125 0.671875 0.109375q0.25 0.078125 0.390625 0.21875q0.140625 0.140625 0.21875 0.359375l8.46875 23.484375zm-10.875 -20.734375l-0.015625 0l-4.359375 12.609375l8.796875 0l-4.421875 -12.609375zm25.003906 5.0q0 0.4375 -0.03125 0.734375q-0.015625 0.28125 -0.078125 0.453125q-0.046875 0.171875 -0.140625 0.265625q-0.078125 0.078125 -0.234375 0.078125q-0.15625 0 -0.390625 -0.078125q-0.21875 -0.09375 -0.5 -0.1875q-0.28125 -0.09375 -0.640625 -0.171875q-0.34375 -0.078125 -0.765625 -0.078125q-0.484375 0 -0.953125 0.203125q-0.46875 0.1875 -0.984375 0.640625q-0.515625 0.453125 -1.09375 1.203125q-0.5625 0.734375 -1.234375 1.8125l0 11.5625q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -17.578125q0 -0.15625 0.0625 -0.265625q0.0625 -0.109375 0.234375 -0.1875q0.171875 -0.09375 0.4375 -0.125q0.28125 -0.03125 0.734375 -0.03125q0.4375 0 0.71875 0.03125q0.28125 0.03125 0.4375 0.125q0.15625 0.078125 0.21875 0.1875q0.078125 0.109375 0.078125 0.265625l0 2.546875q0.71875 -1.046875 1.34375 -1.703125q0.640625 -0.671875 1.203125 -1.046875q0.578125 -0.390625 1.125 -0.53125q0.5625 -0.15625 1.125 -0.15625q0.25 0 0.578125 0.03125q0.328125 0.03125 0.671875 0.109375q0.359375 0.078125 0.640625 0.1875q0.28125 0.09375 0.390625 0.1875q0.125 0.09375 0.15625 0.1875q0.046875 0.078125 0.078125 0.21875q0.03125 0.140625 0.03125 0.40625q0.015625 0.265625 0.015625 0.703125zm29.742188 16.4375q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.25 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.78125 0.046875q-0.5 0 -0.8125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.171875 -0.09375 -0.25 -0.1875q-0.078125 -0.109375 -0.078125 -0.265625l0 -10.6875q0 -1.109375 -0.203125 -2.03125q-0.1875 -0.921875 -0.625 -1.578125q-0.421875 -0.671875 -1.09375 -1.015625q-0.65625 -0.359375 -1.5625 -0.359375q-1.109375 0 -2.234375 0.859375q-1.125 0.859375 -2.46875 2.515625l0 12.296875q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.1875 0.078125 -0.5 0.109375q-0.3125 0.046875 -0.78125 0.046875q-0.453125 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.25 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -10.6875q0 -1.109375 -0.21875 -2.03125q-0.21875 -0.921875 -0.65625 -1.578125q-0.421875 -0.671875 -1.078125 -1.015625q-0.65625 -0.359375 -1.546875 -0.359375q-1.109375 0 -2.25 0.859375q-1.125 0.859375 -2.453125 2.515625l0 12.296875q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -17.578125q0 -0.15625 0.0625 -0.265625q0.0625 -0.109375 0.234375 -0.1875q0.171875 -0.09375 0.4375 -0.125q0.28125 -0.03125 0.734375 -0.03125q0.4375 0 0.71875 0.03125q0.28125 0.03125 0.4375 0.125q0.15625 0.078125 0.21875 0.1875q0.078125 0.109375 0.078125 0.265625l0 2.3125q1.484375 -1.65625 2.875 -2.421875q1.390625 -0.78125 2.828125 -0.78125q1.09375 0 1.953125 0.265625q0.875 0.25 1.53125 0.71875q0.671875 0.453125 1.140625 1.09375q0.46875 0.625 0.78125 1.40625q0.875 -0.953125 1.65625 -1.609375q0.796875 -0.671875 1.53125 -1.078125q0.734375 -0.421875 1.421875 -0.609375q0.703125 -0.1875 1.40625 -0.1875q1.703125 0 2.84375 0.609375q1.15625 0.59375 1.859375 1.59375q0.71875 0.984375 1.015625 2.328125q0.3125 1.328125 0.3125 2.8125l0 11.125zm19.125 0.015625q0 0.234375 -0.15625 0.359375q-0.15625 0.109375 -0.4375 0.171875q-0.265625 0.0625 -0.796875 0.0625q-0.5 0 -0.8125 -0.0625q-0.296875 -0.0625 -0.4375 -0.171875q-0.140625 -0.125 -0.140625 -0.359375l0 -1.765625q-1.140625 1.234375 -2.5625 1.921875q-1.421875 0.6875 -3.0 0.6875q-1.390625 0 -2.515625 -0.375q-1.109375 -0.359375 -1.90625 -1.03125q-0.796875 -0.6875 -1.234375 -1.6875q-0.4375 -1.0 -0.4375 -2.265625q0 -1.484375 0.609375 -2.578125q0.609375 -1.09375 1.734375 -1.8125q1.140625 -0.71875 2.78125 -1.078125q1.640625 -0.375 3.6875 -0.375l2.421875 0l0 -1.359375q0 -1.015625 -0.21875 -1.796875q-0.21875 -0.78125 -0.703125 -1.296875q-0.46875 -0.515625 -1.234375 -0.78125q-0.75 -0.265625 -1.875 -0.265625q-1.1875 0 -2.140625 0.28125q-0.9375 0.28125 -1.65625 0.625q-0.703125 0.34375 -1.1875 0.625q-0.484375 0.28125 -0.71875 0.28125q-0.15625 0 -0.28125 -0.078125q-0.109375 -0.078125 -0.203125 -0.234375q-0.078125 -0.15625 -0.125 -0.390625q-0.03125 -0.25 -0.03125 -0.546875q0 -0.484375 0.0625 -0.765625q0.078125 -0.28125 0.34375 -0.53125q0.265625 -0.265625 0.90625 -0.609375q0.640625 -0.34375 1.484375 -0.625q0.84375 -0.28125 1.828125 -0.46875q1.0 -0.1875 2.015625 -0.1875q1.890625 0 3.21875 0.4375q1.328125 0.421875 2.140625 1.265625q0.828125 0.828125 1.203125 2.0625q0.375 1.21875 0.375 2.859375l0 11.859375zm-3.203125 -8.03125l-2.75 0q-1.328125 0 -2.3125 0.234375q-0.96875 0.21875 -1.625 0.65625q-0.640625 0.4375 -0.953125 1.0625q-0.296875 0.609375 -0.296875 1.40625q0 1.375 0.875 2.1875q0.875 0.796875 2.4375 0.796875q1.265625 0 2.34375 -0.640625q1.09375 -0.640625 2.28125 -1.96875l0 -3.734375zm19.394531 -8.421875q0 0.4375 -0.03125 0.734375q-0.015625 0.28125 -0.078125 0.453125q-0.046875 0.171875 -0.140625 0.265625q-0.078125 0.078125 -0.234375 0.078125q-0.15625 0 -0.390625 -0.078125q-0.21875 -0.09375 -0.5 -0.1875q-0.28125 -0.09375 -0.640625 -0.171875q-0.34375 -0.078125 -0.765625 -0.078125q-0.484375 0 -0.953125 0.203125q-0.46875 0.1875 -0.984375 0.640625q-0.515625 0.453125 -1.09375 1.203125q-0.5625 0.734375 -1.234375 1.8125l0 11.5625q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.265625 0.1875q-0.171875 0.078125 -0.484375 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -17.578125q0 -0.15625 0.0625 -0.265625q0.0625 -0.109375 0.234375 -0.1875q0.171875 -0.09375 0.4375 -0.125q0.28125 -0.03125 0.734375 -0.03125q0.4375 0 0.71875 0.03125q0.28125 0.03125 0.4375 0.125q0.15625 0.078125 0.21875 0.1875q0.078125 0.109375 0.078125 0.265625l0 2.546875q0.71875 -1.046875 1.34375 -1.703125q0.640625 -0.671875 1.203125 -1.046875q0.578125 -0.390625 1.125 -0.53125q0.5625 -0.15625 1.125 -0.15625q0.25 0 0.578125 0.03125q0.328125 0.03125 0.671875 0.109375q0.359375 0.078125 0.640625 0.1875q0.28125 0.09375 0.390625 0.1875q0.125 0.09375 0.15625 0.1875q0.046875 0.078125 0.078125 0.21875q0.03125 0.140625 0.03125 0.40625q0.015625 0.265625 0.015625 0.703125zm19.804688 9.734375q0 0.640625 -0.203125 1.015625q-0.1875 0.375 -0.546875 0.375l-2.84375 0l0 5.3125q0 0.15625 -0.078125 0.265625q-0.078125 0.09375 -0.28125 0.1875q-0.1875 0.078125 -0.5 0.109375q-0.3125 0.046875 -0.796875 0.046875q-0.46875 0 -0.78125 -0.046875q-0.3125 -0.03125 -0.5 -0.109375q-0.1875 -0.09375 -0.265625 -0.1875q-0.0625 -0.109375 -0.0625 -0.265625l0 -5.3125l-10.421875 0q-0.234375 0 -0.390625 -0.0625q-0.15625 -0.0625 -0.296875 -0.21875q-0.125 -0.15625 -0.171875 -0.4375q-0.046875 -0.296875 -0.046875 -0.765625q0 -0.375 0.015625 -0.671875q0.03125 -0.296875 0.078125 -0.53125q0.0625 -0.25 0.15625 -0.46875q0.109375 -0.234375 0.234375 -0.484375l9.109375 -15.34375q0.09375 -0.15625 0.28125 -0.265625q0.1875 -0.125 0.46875 -0.203125q0.296875 -0.078125 0.71875 -0.109375q0.4375 -0.03125 1.03125 -0.03125q0.640625 0 1.109375 0.046875q0.484375 0.046875 0.78125 0.125q0.296875 0.078125 0.453125 0.203125q0.15625 0.125 0.15625 0.3125l0 16.125l2.84375 0q0.34375 0 0.546875 0.34375q0.203125 0.34375 0.203125 1.046875zm-6.859375 -15.25l-0.03125 0l-8.234375 13.859375l8.265625 0l0 -13.859375z" fill-rule="nonzero"></path><path fill="#000000" fill-opacity="0.0" d="m480.6403 211.34604l0 -73.10237" fill-rule="nonzero"></path><path stroke="#1f497d" stroke-width="3.0" stroke-linejoin="round" stroke-linecap="butt" d="m480.6403 211.34602l0 -55.102356" fill-rule="evenodd"></path><path fill="#1f497d" stroke="#1f497d" stroke-width="3.0" stroke-linecap="butt" d="m485.5955 156.24367l-4.9552 -13.614288l-4.9552 13.614288z" fill-rule="evenodd"></path><path fill="#000000" fill-opacity="0.0" d="m244.52756 407.301l236.12598 -73.102356" fill-rule="nonzero"></path><path stroke="#1f497d" stroke-width="3.0" stroke-linejoin="round" stroke-linecap="butt" d="m244.52756 407.30096l218.93115 -67.77899" fill-rule="evenodd"></path><path fill="#1f497d" stroke="#1f497d" stroke-width="3.0" stroke-linecap="butt" d="m464.9242 344.25552l11.539825 -8.759857l-14.470764 -0.70721436z" fill-rule="evenodd"></path><path fill="#000000" fill-opacity="0.0" d="m716.50964 407.301l-235.87402 -73.102356" fill-rule="nonzero"></path><path stroke="#1f497d" stroke-width="3.0" stroke-linejoin="round" stroke-linecap="butt" d="m716.5096 407.30096l-218.68076 -67.7738" fill-rule="evenodd"></path><path fill="#1f497d" stroke="#1f497d" stroke-width="3.0" stroke-linecap="butt" d="m499.29572 334.79407l-14.470947 0.70288086l11.53717 8.763336z" fill-rule="evenodd"></path></g></svg>
+
diff --git a/etc/doxygen/pages/Components.dox b/etc/doxygen/pages/Components.dox
index 023de80200bd3c6cbcadd9a163710562f4305b11..d5aa5901c10c8f836bee1dde0bd6f52d1aa323f1 100644
--- a/etc/doxygen/pages/Components.dox
+++ b/etc/doxygen/pages/Components.dox
@@ -1,5 +1,5 @@
 /**
-\addtogroup Components 5. Components
+\addtogroup Components Components
 
 \defgroup RobotAPI-Components RobotAPI Components
 \ingroup RobotAPI Components
diff --git a/etc/doxygen/pages/GuiPlugins.dox b/etc/doxygen/pages/GuiPlugins.dox
new file mode 100644
index 0000000000000000000000000000000000000000..5aea7e242f7e7a0711e4cbbf78c4bbdc32fa1dbe
--- /dev/null
+++ b/etc/doxygen/pages/GuiPlugins.dox
@@ -0,0 +1,19 @@
+/**
+\page RobotAPI-GuiPlugins RobotAPI Gui Plugins
+
+The following Gui Plugins are available:
+
+\subpage RobotAPI-GuiPlugins-ArmarXPlotter
+
+\subpage RobotAPI-GuiPlugins-TCPMover
+
+\subpage RobotAPI-GuiPlugins-HandUnitWidget
+
+\subpage RobotAPI-GuiPlugins-HapticUnitPlugin
+
+\subpage RobotAPI-GuiPlugins-KinematicUnitPlugin
+
+\subpage RobotAPI-GuiPlugins-PlatformUnitPlugin
+
+\subpage RobotAPI-GuiPlugins-RobotViewerPlugin
+*/
diff --git a/etc/doxygen/pages/Overview.dox b/etc/doxygen/pages/Overview.dox
index 2053028a162a753d7a73a81c229d9a95339ebcac..0674f2b8497ba3c52106cab461f8ab5323062de4 100644
--- a/etc/doxygen/pages/Overview.dox
+++ b/etc/doxygen/pages/Overview.dox
@@ -1,9 +1,29 @@
 /**
 \page RobotAPI-Overview RobotAPI Overview
+The RobotAPI package provides a robot-intependent API that other ArmarX packages can use for accessing central functionality of a robot.
+The central elements of RobotAPI are Sensor-Actor Units, i.e. components responsible for the propagation of sensor values and actor targets.
+Sensor-Actor Units work as a link between higher level ArmarX components and the actual robot hardware or a robot simulation environment, respectively.
+The RobotAPI package contains base classes for Sensor-Actor Units for different purposes, e.g. KinematicUnit for sensors and actors related to robotic joints.
+Concrete Sensor-Actor Units inherit from these base classes in order to provide a common interface.
+Each type of hardware and each type of simulation environment requires a distinct set of Sensor-Actor Units that handle the hardware/simulator access, e.g. KinematicUnitArmar3 and KinematicUnitArmar4 for accessing the kinematic elements of ARMAR-III and ARMAR-4, respectively:
 
-\brief The RobotAPI package provides a robot-intependent API that other ArmarX packages can use for accessing central functionality of a robot.
+\image html sensoractorunits2.svg "Inheritance diagram for Sensor-Actor Units"
 
-Central aspects of RobotAPI include:
+There are three ways to access Sensor-Actor Units:
+- Direct access via the unit's interface, e.g. KinematicUnitInterface. See the \link RobotAPI-SensorActorUnits list of Sensor-Actor Units\endlink.
+
+- Indirect access via a corresponding \link RobotAPI-SensorActorUnits-observers Observer\endlink.
+An Observer is a component that corresponds to a Sensor-Actor Unit.
+It monitors the continuous sensor value stream propagated by the unit and applies registered conditions to the sensor data.
+Each condition evauating to true causes the Observer to fire a dedicated event (\link Observers Read more\endlink).
+
+- Indirect access via the RobotStateComponent.
+The RobotStateComponent maintains a Simox representation of the robot synchronized with the available Sensor-Actor Units, particularly with the KinematicUnit (\link RobotAPI-Components Read more\endlink).
+
+\image html sensoractorunits.svg "Inheritance diagram for Sensor-Actor Units"
+
+
+Further documentation on the various contents of the RobotAPI package:
 
 \par Intelligent Coordinates
 RobotAPI provides datatypes for intelligent coordinates that refer to a robot coordinate frame and can be conveniently transformed between different frames.
@@ -32,12 +52,12 @@ Available GUI-plugins provide access to the kinematic robot state, end effectors
 RobotAPI also provides a GUI-plugin for robot visualization.
 
 \par
-\link RobotAPI-ArmarXGuiPlugins Read more \endlink
+\link RobotAPI-GuiPlugins Read more \endlink
 
-\par Statecharts
-RobotAPI contains a set of robot-independent statecharts that can be used in other ArmarX packages.
-This includes meta statecharts for handling robot state as well as statecharts concerning different sensor modalities.
 
-\par
-\link RobotAPI-Statecharts Read more \endlink
+\defgroup RobotAPI RobotAPI
+\copydoc RobotAPI-Overview
+
+\defgroup RobotAPI-Statecharts Statecharts
+\ingroup RobotAPI
 */
diff --git a/etc/doxygen/pages/RobotApi-Gui-plugins.dox b/etc/doxygen/pages/RobotApi-Gui-plugins.dox
deleted file mode 100644
index 7af77799e5d2f9e7abc2cd68d7bca9f7a6459607..0000000000000000000000000000000000000000
--- a/etc/doxygen/pages/RobotApi-Gui-plugins.dox
+++ /dev/null
@@ -1,5 +0,0 @@
-/**
- * \defgroup RobotAPI-ArmarXGuiPlugins RobotAPI GUI plugins
- * \ingroup ArmarXGuiPlugins RobotAPI
- * \brief &nbsp;
- */
diff --git a/etc/doxygen/pages/Tutorials.dox b/etc/doxygen/pages/Tutorials.dox
index 06d62b24b3971affc90d2fa318dfb43c2ccc9e99..2d701fa653905a41faf42bca6c1bc4bae776a2c7 100644
--- a/etc/doxygen/pages/Tutorials.dox
+++ b/etc/doxygen/pages/Tutorials.dox
@@ -1,9 +1,8 @@
 /**
-\cond DOXYGEN_EXCLUDE
-    TODO: Uncomment once tutorials are available
 
-    \page RobotAPI-Tutorials RobotAPI Tutorials
+\page RobotAPI-Tutorials RobotAPI Tutorials
+
+Tutorials related to RobotAPI
+\li \subpage RobotAPI-Tutorial-MoveRobotWithGui
 
-    Tutorials related to RobotAPI
-\endcond
 */
diff --git a/etc/doxygen/pages/armarpose.dox b/etc/doxygen/pages/armarpose.dox
index 983134d4fcbd15d731f208208a6905139f1e408c..f4cb6eb1eb1303cb0cdea4111e39c1f53acafce4 100644
--- a/etc/doxygen/pages/armarpose.dox
+++ b/etc/doxygen/pages/armarpose.dox
@@ -36,7 +36,7 @@ So an example code for creating a new FramedPosition looks like this:
     armarx::FramedPositionPtr position = new armarx::FramedPosition(pos, frame, agentName);
 \endcode
 
-\section FramedPose-ChangeFrame Change the frame of an FramedPosition
+\section FramedPose-ChangeFrame Change the frame of a FramedPosition
 In ArmarX the most common coordinate type is the FramedX, e.g. FramedPosition.
 To change the frame in this coordinate type, you can call \ref armarx::FramedPosition::changeFrame "changeFrame()" on the FramedPosition.
 You need to know the new frame, in which you want to have the
diff --git a/etc/doxygen/pages/mainpage.dox b/etc/doxygen/pages/mainpage.dox
new file mode 100644
index 0000000000000000000000000000000000000000..367b9a764ffa42ef8ef0307a713201b1d01ebb26
--- /dev/null
+++ b/etc/doxygen/pages/mainpage.dox
@@ -0,0 +1,15 @@
+/**
+\mainpage
+
+RobotAPI description
+
+\li \subpage RobotAPI-Overview "RobotAPI Overview"
+\li \subpage RobotAPI-Installation "RobotAPI Installation"
+\li \subpage RobotAPI-Tutorials "RobotAPI Tutorials"
+\li \subpage RobotAPI-HowTos "RobotAPI Howtos"
+\li \subpage RobotAPI-FAQ "RobotAPI FAQ"
+\li \subpage RobotAPI-Components "RobotAPI Components"
+\li \subpage RobotAPI-GuiPlugins "RobotAPI Gui Plugins"
+\li \subpage RobotAPI-About "RobotAPI About"
+\li \subpage RobotAPI-License "RobotAPI License"
+*/
diff --git a/etc/doxygen/pages/statecharts.dox b/etc/doxygen/pages/statecharts.dox
deleted file mode 100644
index 190c4ec423c47b70749116cbfb34e2344d536088..0000000000000000000000000000000000000000
--- a/etc/doxygen/pages/statecharts.dox
+++ /dev/null
@@ -1,5 +0,0 @@
-/**
-\defgroup RobotAPI-Statecharts RobotAPI Statecharts
-\ingroup RobotAPI Statecharts
-\brief &nbsp;
-*/
diff --git a/etc/doxygen/pages/tutorials/TutorialMoveRobotWithGui.dox b/etc/doxygen/pages/tutorials/TutorialMoveRobotWithGui.dox
new file mode 100644
index 0000000000000000000000000000000000000000..c30421bf523eac320224f6e6fa36da6a6094cbff
--- /dev/null
+++ b/etc/doxygen/pages/tutorials/TutorialMoveRobotWithGui.dox
@@ -0,0 +1,10 @@
+/**
+\page RobotAPI-Tutorial-MoveRobotWithGui Playing around with a kinematic simulation
+Prerequisites: None
+
+* explain components of scenario and link to their docu
+* startScenario
+* start gui
+* open widgets (KinematicUnitGui, RobotIK, RobotViewer, Plotting of some sensor values)
+* how to use the widgets
+*/
diff --git a/scenarios/CMakeLists.txt b/scenarios/CMakeLists.txt
index 29d0d1c9e76975231367f4220c0b872182ffec4c..2abeca70fde546d75fa6c8324ab9da975db54923 100644
--- a/scenarios/CMakeLists.txt
+++ b/scenarios/CMakeLists.txt
@@ -1,4 +1,5 @@
 
+add_subdirectory(KinematicSimulationArmar3)
+
 add_subdirectory(tests)
-add_subdirectory(MMMScenario)
 
diff --git a/scenarios/KinematicSimulationArmar3/CMakeLists.txt b/scenarios/KinematicSimulationArmar3/CMakeLists.txt
new file mode 100644
index 0000000000000000000000000000000000000000..6e5939b2cbdcad3aff5ca50e00b8403627ee72e0
--- /dev/null
+++ b/scenarios/KinematicSimulationArmar3/CMakeLists.txt
@@ -0,0 +1,32 @@
+# Add your components below as shown in the following example:
+
+set(SCENARIO_CONFIG_COMPONENTS
+
+	config/CommonStorage.cfg
+	config/PriorKnowledge.cfg
+	config/LongtermMemory.cfg
+	config/WorkingMemory.cfg
+	config/ObjectMemoryObserver.cfg
+
+	config/KinematicUnitSimulation.cfg
+	config/KinematicUnitObserver.cfg
+	config/HeadIKUnit.cfg
+	config/TCPControlUnit.cfg
+	config/HandUnitSimulation.LeftHand.cfg
+	config/HandUnitSimulation.RightHand.cfg
+	config/ForceTorqueUnitSimulation.cfg
+	config/ForceTorqueObserver.cfg
+
+	config/DebugObserver.cfg
+	config/ConditionHandler.cfg
+	config/SystemObserver.cfg
+	config/RobotStateComponent.cfg
+
+	config/ImageSequenceProvider.cfg
+)
+
+#    RobotControl
+
+# optional 3rd parameter: "path/to/global/config.cfg"
+armarx_scenario_from_configs("KinematicSimulationArmar3" "${SCENARIO_CONFIG_COMPONENTS}" "./config/Global.cfg")
+
diff --git a/scenarios/KinematicSimulationArmar3/config/CommonStorage.cfg b/scenarios/KinematicSimulationArmar3/config/CommonStorage.cfg
new file mode 100644
index 0000000000000000000000000000000000000000..99bcff276eb237bffc7d552c5cbc1b2dd0c205c4
--- /dev/null
+++ b/scenarios/KinematicSimulationArmar3/config/CommonStorage.cfg
@@ -0,0 +1,107 @@
+# ==================================================================
+# MemoryX properties
+# ==================================================================
+
+# MemoryX.CachePath:  Path for cache files
+#  Attributes:
+#  - Default:            ${HOME}/.armarx/mongo/.cache
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.CachePath = ${HOME}/.armarx/mongo/.cache
+
+
+# MemoryX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.DataPath = ""
+
+
+# MemoryX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Verbose
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# MemoryX.Verbosity = Verbose
+
+
+# MemoryX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# MemoryX.DisableLogging = 0
+
+
+# MemoryX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.ApplicationName = ""
+
+
+# MemoryX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.Config = ""
+
+
+# ==================================================================
+# MemoryX.CommonStorage properties
+# ==================================================================
+
+# MemoryX.CommonStorage.MongoUser:  MongoDB user name
+#  Attributes:
+#  - Case sensitivity:   no
+#  - Required:           yes
+MemoryX.CommonStorage.MongoUser = a
+
+
+# MemoryX.CommonStorage.MongoAuth:  Whether authentication should be used for MongoDB
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# MemoryX.CommonStorage.MongoAuth = 0
+
+
+# MemoryX.CommonStorage.MongoPassword:  MongoDB password
+#  Attributes:
+#  - Case sensitivity:   no
+#  - Required:           yes
+MemoryX.CommonStorage.MongoPassword = 1
+
+
+# MemoryX.CommonStorage.MongoHost:  MongoDB hostname and optionally port number
+#  Attributes:
+#  - Default:            localhost
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.CommonStorage.MongoHost = localhost
+
+
+# MemoryX.CommonStorage.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Error, Fatal, Info, Undefined, Verbose, Warning}
+# MemoryX.CommonStorage.MinimumLoggingLevel = Undefined
+
+
+# MemoryX.CommonStorage.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.CommonStorage.ObjectName = ""
+
+
+
diff --git a/scenarios/KinematicSimulationArmar3/config/ConditionHandler.cfg b/scenarios/KinematicSimulationArmar3/config/ConditionHandler.cfg
new file mode 100644
index 0000000000000000000000000000000000000000..a938a4186b94e0159b027fc30e3ccc3fc5c62d3a
--- /dev/null
+++ b/scenarios/KinematicSimulationArmar3/config/ConditionHandler.cfg
@@ -0,0 +1,92 @@
+# ==================================================================
+# ArmarX properties
+# ==================================================================
+
+# ArmarX.CachePath:  Path for cache files
+#  Attributes:
+#  - Default:            ${HOME}/.armarx/mongo/.cache
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.CachePath = ${HOME}/.armarx/mongo/.cache
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Verbose
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Verbose
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = 0
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ==================================================================
+# ArmarX.ConditionHandler properties
+# ==================================================================
+
+# ArmarX.ConditionHandler.HistoryLength:  Length of condition history kept by the conditionhandler
+#  Attributes:
+#  - Default:            1000
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.ConditionHandler.HistoryLength = 1000
+
+
+# ArmarX.ConditionHandler.Observers:  Comma seperated observer list
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+ ArmarX.ConditionHandler.Observers = Armar3KinematicUnitObserver,SystemObserver,ObjectMemoryObserver
+
+
+# ArmarX.ConditionHandler.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Error, Fatal, Info, Undefined, Verbose, Warning}
+# ArmarX.ConditionHandler.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.ConditionHandler.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.ConditionHandler.ObjectName = ""
+
+
+
diff --git a/scenarios/KinematicSimulationArmar3/config/DebugObserver.cfg b/scenarios/KinematicSimulationArmar3/config/DebugObserver.cfg
new file mode 100644
index 0000000000000000000000000000000000000000..1806791a06702d24ed5865914f404304f4244269
--- /dev/null
+++ b/scenarios/KinematicSimulationArmar3/config/DebugObserver.cfg
@@ -0,0 +1,84 @@
+# ==================================================================
+# ArmarX properties
+# ==================================================================
+
+# ArmarX.CachePath:  Path for cache files
+#  Attributes:
+#  - Default:            ${HOME}/.armarx/mongo/.cache
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.CachePath = ${HOME}/.armarx/mongo/.cache
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Verbose
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Verbose
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = 0
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.DatapathConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/datapath.cfg
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.DatapathConfig = ./config/datapath.cfg
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ==================================================================
+# ArmarX.DebugObserver properties
+# ==================================================================
+
+# ArmarX.DebugObserver.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Error, Fatal, Info, Undefined, Verbose, Warning}
+# ArmarX.DebugObserver.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.DebugObserver.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.DebugObserver.ObjectName = ""
+
+
+
diff --git a/scenarios/KinematicSimulationArmar3/config/ForceTorqueObserver.cfg b/scenarios/KinematicSimulationArmar3/config/ForceTorqueObserver.cfg
new file mode 100644
index 0000000000000000000000000000000000000000..af8cc946bcaac72b3fbd8f0d070a34e85f30c798
--- /dev/null
+++ b/scenarios/KinematicSimulationArmar3/config/ForceTorqueObserver.cfg
@@ -0,0 +1,91 @@
+# ==================================================================
+# ArmarX properties
+# ==================================================================
+
+# ArmarX.CachePath:  Path for cache files
+#  Attributes:
+#  - Default:            ${HOME}/.armarx/mongo/.cache
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.CachePath = ${HOME}/.armarx/mongo/.cache
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Verbose
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Verbose
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = 0
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.DatapathConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/datapath.cfg
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.DatapathConfig = ./config/datapath.cfg
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ==================================================================
+# ArmarX.ForceTorqueUnitObserver properties
+# ==================================================================
+
+# ArmarX.ForceTorqueUnitObserver.ForceTorqueTopicName:  Name of the ForceTorqueUnit Topic
+#  Attributes:
+#  - Case sensitivity:   no
+#  - Required:           yes
+ArmarX.ForceTorqueUnitObserver.ForceTorqueTopicName = "ForceTorqueValues"
+
+
+# ArmarX.ForceTorqueUnitObserver.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Error, Fatal, Info, Undefined, Verbose, Warning}
+# ArmarX.ForceTorqueUnitObserver.MinimumLoggingLevel = Verbose
+
+
+# ArmarX.ForceTorqueUnitObserver.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+ArmarX.ForceTorqueUnitObserver.ObjectName = "Armar3ForceTorqueObserver"
+
+
+
diff --git a/scenarios/KinematicSimulationArmar3/config/ForceTorqueUnitSimulation.cfg b/scenarios/KinematicSimulationArmar3/config/ForceTorqueUnitSimulation.cfg
new file mode 100644
index 0000000000000000000000000000000000000000..e6503a4c767125771c7668bc8ba08b87a2ce8d9a
--- /dev/null
+++ b/scenarios/KinematicSimulationArmar3/config/ForceTorqueUnitSimulation.cfg
@@ -0,0 +1,114 @@
+# ==================================================================
+# ArmarX properties
+# ==================================================================
+
+# ArmarX.CachePath:  Path for cache files
+#  Attributes:
+#  - Default:            ${HOME}/.armarx/mongo/.cache
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.CachePath = ${HOME}/.armarx/mongo/.cache
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Verbose
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Verbose
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = 0
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.DatapathConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/datapath.cfg
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.DatapathConfig = ./config/datapath.cfg
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ==================================================================
+# ArmarX.ForceTorqueUnitSimulation properties
+# ==================================================================
+
+# ArmarX.ForceTorqueUnitSimulation.IntervalMs:  The time in milliseconds between two calls to the simulation method.
+#  Attributes:
+#  - Default:            10
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.ForceTorqueUnitSimulation.IntervalMs = 10
+
+
+# ArmarX.ForceTorqueUnitSimulation.SensorName:  simulated sensor name
+#  Attributes:
+#  - Case sensitivity:   no
+#  - Required:           yes
+ArmarX.ForceTorqueUnitSimulation.SensorName = <set value!>
+
+
+# ArmarX.ForceTorqueUnitSimulation.ForceTorqueTopicName:  Name of the topic on which the sensor values are provided
+#  Attributes:
+#  - Default:            ForceTorqueValues
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.ForceTorqueUnitSimulation.ForceTorqueTopicName = ForceTorqueValues
+
+
+# ArmarX.ForceTorqueUnitSimulation.AgentName:  Name of the agent for which the sensor values are provided
+#  Attributes:
+#  - Case sensitivity:   no
+#  - Required:           yes
+ArmarX.ForceTorqueUnitSimulation.AgentName = Armar3
+
+
+# ArmarX.ForceTorqueUnitSimulation.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Error, Fatal, Info, Undefined, Verbose, Warning}
+# ArmarX.ForceTorqueUnitSimulation.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.ForceTorqueUnitSimulation.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.ForceTorqueUnitSimulation.ObjectName = ""
+
+
+
diff --git a/scenarios/KinematicSimulationArmar3/config/Global.cfg b/scenarios/KinematicSimulationArmar3/config/Global.cfg
new file mode 100644
index 0000000000000000000000000000000000000000..77927624693f052359958908ce6d8a1bb0e6bc4f
--- /dev/null
+++ b/scenarios/KinematicSimulationArmar3/config/Global.cfg
@@ -0,0 +1,5 @@
+ArmarX.DisableLogging = no
+VisionX.DisableLogging = no
+
+ArmarX.GlobalMinimumLoggingLevel = Verbose
+VisionX.GlobalMinimumLoggingLevel = Verbose
diff --git a/scenarios/KinematicSimulationArmar3/config/HandUnitSimulation.LeftHand.cfg b/scenarios/KinematicSimulationArmar3/config/HandUnitSimulation.LeftHand.cfg
new file mode 100644
index 0000000000000000000000000000000000000000..fc4b9bb96110823d5858d9e083b3e46cbd09bad6
--- /dev/null
+++ b/scenarios/KinematicSimulationArmar3/config/HandUnitSimulation.LeftHand.cfg
@@ -0,0 +1,98 @@
+# ==================================================================
+# ArmarX properties
+# ==================================================================
+
+# ArmarX.CachePath:  Path for cache files
+#  Attributes:
+#  - Default:            ${HOME}/.armarx/mongo/.cache
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.CachePath = ${HOME}/.armarx/mongo/.cache
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Verbose
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Verbose
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = 0
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.DatapathConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/datapath.cfg
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.DatapathConfig = ./config/datapath.cfg
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ==================================================================
+# ArmarX.HandUnitSimulation properties
+# ==================================================================
+
+# ArmarX.HandUnitSimulation.RobotFileName:  VirtualRobot XML file in which the endeffector is is stored.
+#  Attributes:
+#  - Case sensitivity:   no
+#  - Required:           yes
+ArmarX.HandUnitSimulation.RobotFileName = RobotAPI/robots/Armar3/ArmarIII.xml
+
+
+# ArmarX.HandUnitSimulation.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Error, Fatal, Info, Undefined, Verbose, Warning}
+# ArmarX.HandUnitSimulation.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.HandUnitSimulation.EndeffectorName:  Name of the endeffector as stored in the XML file (will publish values on EndeffectorName + 'State')
+#  Attributes:
+#  - Case sensitivity:   no
+#  - Required:           yes
+ArmarX.HandUnitSimulation.EndeffectorName = TCP L
+
+
+# ArmarX.HandUnitSimulation.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+ArmarX.HandUnitSimulation.ObjectName = "LeftHandUnit"
+
+
+
diff --git a/scenarios/KinematicSimulationArmar3/config/HandUnitSimulation.RightHand.cfg b/scenarios/KinematicSimulationArmar3/config/HandUnitSimulation.RightHand.cfg
new file mode 100644
index 0000000000000000000000000000000000000000..822c3975756a884597e1b14b6515d29804b8e79f
--- /dev/null
+++ b/scenarios/KinematicSimulationArmar3/config/HandUnitSimulation.RightHand.cfg
@@ -0,0 +1,98 @@
+# ==================================================================
+# ArmarX properties
+# ==================================================================
+
+# ArmarX.CachePath:  Path for cache files
+#  Attributes:
+#  - Default:            ${HOME}/.armarx/mongo/.cache
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.CachePath = ${HOME}/.armarx/mongo/.cache
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Verbose
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Verbose
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = 0
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.DatapathConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/datapath.cfg
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.DatapathConfig = ./config/datapath.cfg
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ==================================================================
+# ArmarX.HandUnitSimulation properties
+# ==================================================================
+
+# ArmarX.HandUnitSimulation.RobotFileName:  VirtualRobot XML file in which the endeffector is is stored.
+#  Attributes:
+#  - Case sensitivity:   no
+#  - Required:           yes
+ArmarX.HandUnitSimulation.RobotFileName = RobotAPI/robots/Armar3/ArmarIII.xml
+
+
+# ArmarX.HandUnitSimulation.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Error, Fatal, Info, Undefined, Verbose, Warning}
+# ArmarX.HandUnitSimulation.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.HandUnitSimulation.EndeffectorName:  Name of the endeffector as stored in the XML file (will publish values on EndeffectorName + 'State')
+#  Attributes:
+#  - Case sensitivity:   no
+#  - Required:           yes
+ArmarX.HandUnitSimulation.EndeffectorName = TCP R
+
+
+# ArmarX.HandUnitSimulation.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+ArmarX.HandUnitSimulation.ObjectName = "RightHandUnit"
+
+
+
diff --git a/scenarios/KinematicSimulationArmar3/config/HeadIKUnit.cfg b/scenarios/KinematicSimulationArmar3/config/HeadIKUnit.cfg
new file mode 100644
index 0000000000000000000000000000000000000000..8123d93084cae155a6f831c625e71a94031d50b2
--- /dev/null
+++ b/scenarios/KinematicSimulationArmar3/config/HeadIKUnit.cfg
@@ -0,0 +1,91 @@
+# ==================================================================
+# ArmarX properties
+# ==================================================================
+
+# ArmarX.CachePath:  Path for cache files
+#  Attributes:
+#  - Default:            ${HOME}/.armarx/mongo/.cache
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.CachePath = ${HOME}/.armarx/mongo/.cache
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Verbose
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Verbose
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = 0
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ==================================================================
+# ArmarX.HeadIKUnit properties
+# ==================================================================
+
+# ArmarX.HeadIKUnit.CycleTime:  Cycle time of the tcp control in ms
+#  Attributes:
+#  - Default:            30
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.HeadIKUnit.CycleTime = 30
+
+
+# ArmarX.HeadIKUnit.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Error, Fatal, Info, Undefined, Verbose, Warning}
+# ArmarX.HeadIKUnit.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.HeadIKUnit.KinematicUnitName:  Name of the KinematicUnit Proxy
+#  Attributes:
+#  - Case sensitivity:   no
+#  - Required:           yes
+ArmarX.HeadIKUnit.KinematicUnitName = "Armar3KinematicUnit"
+
+
+# ArmarX.HeadIKUnit.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.HeadIKUnit.ObjectName = ""
+
+
+
diff --git a/scenarios/KinematicSimulationArmar3/config/ImageSequenceProvider.cfg b/scenarios/KinematicSimulationArmar3/config/ImageSequenceProvider.cfg
new file mode 100644
index 0000000000000000000000000000000000000000..9090c34aa190698960476de5cdbfe3ccb414d296
--- /dev/null
+++ b/scenarios/KinematicSimulationArmar3/config/ImageSequenceProvider.cfg
@@ -0,0 +1,136 @@
+# ==================================================================
+# VisionX properties
+# ==================================================================
+
+# VisionX.CachePath:  Path for cache files
+#  Attributes:
+#  - Default:            ${HOME}/.armarx/mongo/.cache
+#  - Case sensitivity:   no
+#  - Required:           no
+# VisionX.CachePath = ${HOME}/.armarx/mongo/.cache
+
+
+# VisionX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# VisionX.DataPath = ""
+
+
+# VisionX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Verbose
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# VisionX.Verbosity = Verbose
+
+
+# VisionX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# VisionX.DisableLogging = 0
+
+
+# VisionX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# VisionX.ApplicationName = ""
+
+
+# VisionX.DatapathConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/datapath.cfg
+#  - Case sensitivity:   no
+#  - Required:           no
+# VisionX.DatapathConfig = ./config/datapath.cfg
+
+
+# VisionX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# VisionX.Config = ""
+
+
+# ==================================================================
+# VisionX.ImageSequenceProvider properties
+# ==================================================================
+
+# VisionX.ImageSequenceProvider.CalibrationFile:  Camera calibration file, will be made available in the SLICE interface
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+VisionX.ImageSequenceProvider.CalibrationFile = "/home/SMBAD/schieben/home/mca2.4/projects/armar3/robot_interface/files/camera_armar3a_640x480_wide.txt"
+
+
+# VisionX.ImageSequenceProvider.ImageSize:  Target resolution of the images. Loaded images will be converted to this size.
+#  Attributes:
+#  - Default:            640x480
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {1024x768, 1280x960, 1600x1200, 320x240, 640x480, 768x576, 800x600, none}
+# VisionX.ImageSequenceProvider.ImageSize = 640x480
+
+
+# VisionX.ImageSequenceProvider.FrameRate:  Frames per second
+#  Attributes:
+#  - Default:            30
+#  - Bounds:             [0; 60]
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Format:             \d+(.\d*)?
+VisionX.ImageSequenceProvider.FrameRate = 2
+
+
+# VisionX.ImageSequenceProvider.PathLeft:  Filename and path of the left camera images. Filenames need to follow the format: path/*%d.bmp (e.g. path/image_left0000.bmp).
+#  Attributes:
+#  - Case sensitivity:   no
+#  - Required:           yes
+#VisionX.ImageSequenceProvider.PathLeft = "/home/SMBAD/schieben/home/Bilder/OLP-Test/img2/scL0000.bmp"
+VisionX.ImageSequenceProvider.PathLeft = "/home/SMBAD/schieben/home/Bilder/BlaueTasse/scL0000.bmp"
+
+
+# VisionX.ImageSequenceProvider.ImagesAreUndistorted:  Sets whether images are provided undistorted.
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   no
+#  - Required:           no
+# VisionX.ImageSequenceProvider.ImagesAreUndistorted = 0
+
+
+# VisionX.ImageSequenceProvider.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Error, Fatal, Info, Undefined, Verbose, Warning}
+# VisionX.ImageSequenceProvider.MinimumLoggingLevel = Undefined
+
+
+# VisionX.ImageSequenceProvider.PathRight:  Filename and path of the right camera images. Filenames need to follow the format: path/*%d.bmp (e.g. path/image_right0000.bmp).
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+#VisionX.ImageSequenceProvider.PathRight = "/home/SMBAD/schieben/home/Bilder/OLP-Test/img2/scR0000.bmp"
+VisionX.ImageSequenceProvider.PathRight = "/home/SMBAD/schieben/home/Bilder/BlaueTasse/scR0000.bmp"
+
+
+# VisionX.ImageSequenceProvider.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+VisionX.ImageSequenceProvider.ObjectName = "Armar3ImageProvider"
+
+
+
diff --git a/scenarios/KinematicSimulationArmar3/config/KinematicUnitObserver.cfg b/scenarios/KinematicSimulationArmar3/config/KinematicUnitObserver.cfg
new file mode 100644
index 0000000000000000000000000000000000000000..965659b905355228ac0967a8f86632ece380a6f3
--- /dev/null
+++ b/scenarios/KinematicSimulationArmar3/config/KinematicUnitObserver.cfg
@@ -0,0 +1,90 @@
+# ==================================================================
+# ArmarX properties
+# ==================================================================
+
+# ArmarX.CachePath:  Path for cache files
+#  Attributes:
+#  - Default:            ${HOME}/.armarx/mongo/.cache
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.CachePath = ${HOME}/.armarx/mongo/.cache
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Verbose
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Verbose
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = 0
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ==================================================================
+# ArmarX.KinematicUnitObserver properties
+# ==================================================================
+
+# ArmarX.KinematicUnitObserver.RobotFileName:  Robot file name, e.g. robot_model.xml
+#  Attributes:
+#  - Case sensitivity:   no
+#  - Required:           yes
+ArmarX.KinematicUnitObserver.RobotFileName = RobotAPI/robots/Armar3/ArmarIII.xml
+
+
+# ArmarX.KinematicUnitObserver.RobotNodeSetName:  Robot node name
+#  Attributes:
+#  - Case sensitivity:   no
+#  - Required:           yes
+ArmarX.KinematicUnitObserver.RobotNodeSetName = Robot
+
+
+# ArmarX.KinematicUnitObserver.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Error, Fatal, Info, Undefined, Verbose, Warning}
+# ArmarX.KinematicUnitObserver.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.KinematicUnitObserver.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+ArmarX.KinematicUnitObserver.ObjectName = Armar3KinematicUnitObserver
+
+
+
diff --git a/scenarios/KinematicSimulationArmar3/config/KinematicUnitSimulation.cfg b/scenarios/KinematicSimulationArmar3/config/KinematicUnitSimulation.cfg
new file mode 100644
index 0000000000000000000000000000000000000000..6bef0c11bff2dfe917e56fb1445bf34a3f91b95c
--- /dev/null
+++ b/scenarios/KinematicSimulationArmar3/config/KinematicUnitSimulation.cfg
@@ -0,0 +1,98 @@
+# ==================================================================
+# ArmarX properties
+# ==================================================================
+
+# ArmarX.CachePath:  Path for cache files
+#  Attributes:
+#  - Default:            ${HOME}/.armarx/mongo/.cache
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.CachePath = ${HOME}/.armarx/mongo/.cache
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Verbose
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Verbose
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = 0
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ==================================================================
+# ArmarX.KinematicUnitSimulation properties
+# ==================================================================
+
+# ArmarX.KinematicUnitSimulation.IntervalMs:  The time in milliseconds between two calls to the simulation method.
+#  Attributes:
+#  - Default:            10
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.KinematicUnitSimulation.IntervalMs = 10
+
+
+# ArmarX.KinematicUnitSimulation.RobotFileName:  Robot file name, e.g. robot_model.xml
+#  Attributes:
+#  - Case sensitivity:   no
+#  - Required:           yes
+ArmarX.KinematicUnitSimulation.RobotFileName = RobotAPI/robots/Armar3/ArmarIII.xml
+
+
+# ArmarX.KinematicUnitSimulation.RobotNodeSetName:  Robot node name
+#  Attributes:
+#  - Case sensitivity:   no
+#  - Required:           yes
+ArmarX.KinematicUnitSimulation.RobotNodeSetName = Robot
+
+
+# ArmarX.KinematicUnitSimulation.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Error, Fatal, Info, Undefined, Verbose, Warning}
+# ArmarX.KinematicUnitSimulation.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.KinematicUnitSimulation.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+ArmarX.KinematicUnitSimulation.ObjectName = Armar3KinematicUnit
+
+
+
diff --git a/scenarios/KinematicSimulationArmar3/config/LongtermMemory.cfg b/scenarios/KinematicSimulationArmar3/config/LongtermMemory.cfg
new file mode 100644
index 0000000000000000000000000000000000000000..bdce00076f07bb6b7b0b48c254b81bceab9d619a
--- /dev/null
+++ b/scenarios/KinematicSimulationArmar3/config/LongtermMemory.cfg
@@ -0,0 +1,99 @@
+# ==================================================================
+# MemoryX properties
+# ==================================================================
+
+# MemoryX.CachePath:  Path for cache files
+#  Attributes:
+#  - Default:            ${HOME}/.armarx/mongo/.cache
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.CachePath = ${HOME}/.armarx/mongo/.cache
+
+
+# MemoryX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.DataPath = ""
+
+
+# MemoryX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Verbose
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# MemoryX.Verbosity = Verbose
+
+
+# MemoryX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# MemoryX.DisableLogging = 0
+
+
+# MemoryX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.ApplicationName = ""
+
+
+# MemoryX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.Config = ""
+
+
+# ==================================================================
+# MemoryX.LongtermMemory properties
+# ==================================================================
+
+# MemoryX.LongtermMemory.OacCollection:  Mongo collection holding all OACs
+#  Attributes:
+#  - Default:            oacs
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.LongtermMemory.OacCollection = oacs
+
+
+# MemoryX.LongtermMemory.SnapshotListCollection:  Mongo collection holding a list of snapshots with corresponding metadata
+#  Attributes:
+#  - Default:            snapshots
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.LongtermMemory.SnapshotListCollection = snapshots
+
+
+# MemoryX.LongtermMemory.DatabaseName:  Mongo database to store LTM data
+#  Attributes:
+#  - Case sensitivity:   no
+#  - Required:           yes
+MemoryX.LongtermMemory.DatabaseName = memdb
+
+
+# MemoryX.LongtermMemory.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Error, Fatal, Info, Undefined, Verbose, Warning}
+# MemoryX.LongtermMemory.MinimumLoggingLevel = Undefined
+
+
+# MemoryX.LongtermMemory.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.LongtermMemory.ObjectName = ""
+
+
+
diff --git a/scenarios/KinematicSimulationArmar3/config/ObjectMemoryObserver.cfg b/scenarios/KinematicSimulationArmar3/config/ObjectMemoryObserver.cfg
new file mode 100644
index 0000000000000000000000000000000000000000..1bba0f7bdc4d4e998788af7c0f48030ae90d8453
--- /dev/null
+++ b/scenarios/KinematicSimulationArmar3/config/ObjectMemoryObserver.cfg
@@ -0,0 +1,100 @@
+# ==================================================================
+# MemoryX properties
+# ==================================================================
+
+# MemoryX.CachePath:  Path for cache files
+#  Attributes:
+#  - Default:            ${HOME}/.armarx/mongo/.cache
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.CachePath = ${HOME}/.armarx/mongo/.cache
+
+
+# MemoryX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.DataPath = ""
+
+
+# MemoryX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Verbose
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# MemoryX.Verbosity = Verbose
+
+
+# MemoryX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# MemoryX.DisableLogging = 0
+
+
+# MemoryX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.ApplicationName = ""
+
+
+# MemoryX.DatapathConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/datapath.cfg
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.DatapathConfig = ./config/datapath.cfg
+
+
+# MemoryX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.Config = ""
+
+
+# ==================================================================
+# MemoryX.ObjectMemoryObserver properties
+# ==================================================================
+
+# MemoryX.ObjectMemoryObserver.WorkingMemoryProxy:  Proxy of working memory
+#  Attributes:
+#  - Default:            WorkingMemory
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.ObjectMemoryObserver.WorkingMemoryProxy = WorkingMemory
+
+
+# MemoryX.ObjectMemoryObserver.WorkingMemoryListenerTopic:  Topic for working memory updates
+#  Attributes:
+#  - Default:            WorkingMemoryUpdates
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.ObjectMemoryObserver.WorkingMemoryListenerTopic = WorkingMemoryUpdates
+
+
+# MemoryX.ObjectMemoryObserver.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Error, Fatal, Info, Undefined, Verbose, Warning}
+# MemoryX.ObjectMemoryObserver.MinimumLoggingLevel = Undefined
+
+
+# MemoryX.ObjectMemoryObserver.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.ObjectMemoryObserver.ObjectName = ""
+
+
+
diff --git a/scenarios/KinematicSimulationArmar3/config/PriorKnowledge.cfg b/scenarios/KinematicSimulationArmar3/config/PriorKnowledge.cfg
new file mode 100644
index 0000000000000000000000000000000000000000..459e98fa0c782473ef18cd35c65878d5af05931f
--- /dev/null
+++ b/scenarios/KinematicSimulationArmar3/config/PriorKnowledge.cfg
@@ -0,0 +1,95 @@
+# ==================================================================
+# MemoryX properties
+# ==================================================================
+
+# MemoryX.CachePath:  Path for cache files
+#  Attributes:
+#  - Default:            ${HOME}/.armarx/mongo/.cache
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.CachePath = ${HOME}/.armarx/mongo/.cache
+
+
+# MemoryX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.DataPath = ""
+
+
+# MemoryX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Verbose
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# MemoryX.Verbosity = Verbose
+
+
+# MemoryX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# MemoryX.DisableLogging = 0
+
+
+# MemoryX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.ApplicationName = ""
+
+
+# MemoryX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.Config = ""
+
+
+# ==================================================================
+# MemoryX.PriorKnowledge properties
+# ==================================================================
+
+# MemoryX.PriorKnowledge.RelationCollections:  Comma separated list of MongoDB collection (<db>.<collection>) which store known object classes relations. First collection will be used for writing.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.PriorKnowledge.RelationCollections = ""
+
+
+# MemoryX.PriorKnowledge.ClassCollections:  Comma separated list of MongoDB collection (<db>.<collection>) which store known object classes. First collection will be used for writing.
+#  Attributes:
+#  - Case sensitivity:   no
+#  - Required:           yes
+MemoryX.PriorKnowledge.ClassCollections = memdb.Prior_KitchenKK,memdb.Prior_KitchenKKObjects
+
+
+# MemoryX.PriorKnowledge.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Error, Fatal, Info, Undefined, Verbose, Warning}
+# MemoryX.PriorKnowledge.MinimumLoggingLevel = Undefined
+
+
+# MemoryX.PriorKnowledge.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.PriorKnowledge.ObjectName = ""
+
+# MemoryX.PriorKnowledge.GraphCollections: Comma separated list of MongoDB collection (<db>.<collection>) which store graphs. First collection will be used for writing.
+#  Attributes:
+#  - Case sensitivity:   no
+#  - Required:           no
+MemoryX.PriorKnowledge.GraphCollections = memdb.Prior_KitchenKKGraphs
+
diff --git a/scenarios/KinematicSimulationArmar3/config/RobotStateComponent.cfg b/scenarios/KinematicSimulationArmar3/config/RobotStateComponent.cfg
new file mode 100644
index 0000000000000000000000000000000000000000..74dae5bf009f993f0afb14a861e093fd4f135935
--- /dev/null
+++ b/scenarios/KinematicSimulationArmar3/config/RobotStateComponent.cfg
@@ -0,0 +1,4 @@
+ArmarX.RobotStateComponent.RobotFileName=RobotAPI/robots/Armar3/ArmarIII.xml       	# model XML file path containing a VirtualRobot RobotNodeSet that defines the joints
+ArmarX.RobotStateComponent.RobotNodeSetName=Robot					# node set name
+ArmarX.RobotStateComponent.ObjectName=RobotStateComponent      			# name of the ICE adapter
+ArmarX.RobotStateComponent.AgentName=Armar3
diff --git a/scenarios/KinematicSimulationArmar3/config/SystemObserver.cfg b/scenarios/KinematicSimulationArmar3/config/SystemObserver.cfg
new file mode 100644
index 0000000000000000000000000000000000000000..7102973bdf909d22014a0c940bfa2b128fffeabd
--- /dev/null
+++ b/scenarios/KinematicSimulationArmar3/config/SystemObserver.cfg
@@ -0,0 +1,76 @@
+# ==================================================================
+# ArmarX properties
+# ==================================================================
+
+# ArmarX.CachePath:  Path for cache files
+#  Attributes:
+#  - Default:            ${HOME}/.armarx/mongo/.cache
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.CachePath = ${HOME}/.armarx/mongo/.cache
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Verbose
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Verbose
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = 0
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ==================================================================
+# ArmarX.SystemObserver properties
+# ==================================================================
+
+# ArmarX.SystemObserver.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Error, Fatal, Info, Undefined, Verbose, Warning}
+# ArmarX.SystemObserver.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.SystemObserver.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.SystemObserver.ObjectName = ""
+
+
+
diff --git a/scenarios/KinematicSimulationArmar3/config/TCPControlUnit.cfg b/scenarios/KinematicSimulationArmar3/config/TCPControlUnit.cfg
new file mode 100644
index 0000000000000000000000000000000000000000..5a9d95709b50b5b2974814a9183e19e58b61a903
--- /dev/null
+++ b/scenarios/KinematicSimulationArmar3/config/TCPControlUnit.cfg
@@ -0,0 +1,158 @@
+# ==================================================================
+# ArmarX properties
+# ==================================================================
+
+# ArmarX.CachePath:  Path for cache files
+#  Attributes:
+#  - Default:            ${HOME}/.armarx/mongo/.cache
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.CachePath = ${HOME}/.armarx/mongo/.cache
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Verbose
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Verbose
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = 0
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.DatapathConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/datapath.cfg
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.DatapathConfig = ./config/datapath.cfg
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ==================================================================
+# ArmarX.TCPControlUnit properties
+# ==================================================================
+
+# ArmarX.TCPControlUnit.CycleTime:  Cycle time of the tcp control in ms
+#  Attributes:
+#  - Default:            30
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.TCPControlUnit.CycleTime = 30
+
+
+# ArmarX.TCPControlUnit.RobotFileName:  Robot file name, e.g. robot_model.xml
+#  Attributes:
+#  - Case sensitivity:   no
+#  - Required:           yes
+ArmarX.TCPControlUnit.inheritFrom=RobotConfig
+
+
+# ArmarX.TCPControlUnit.MaxJointVelocity:  Maximal joint velocity in rad/sec
+#  Attributes:
+#  - Default:            0.523500025
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.TCPControlUnit.MaxJointVelocity = 0.523500025
+
+
+# ArmarX.TCPControlUnit.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Error, Fatal, Info, Undefined, Verbose, Warning}
+# ArmarX.TCPControlUnit.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.TCPControlUnit.TCPsToReport:  comma seperated list of nodesets' endeffectors, which poses and velocities that should be reported. * for all, empty for none
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+ArmarX.TCPControlUnit.TCPsToReport = TCP R,TCP L
+
+
+# ArmarX.TCPControlUnit.MaximumCommandDelay:  Delay after which the TCP Control unit releases itself if no new velocity have been set.
+#  Attributes:
+#  - Default:            200
+#  - Case sensitivity:   no
+#  - Required:           no
+ArmarX.TCPControlUnit.MaximumCommandDelay = 500
+
+
+# ArmarX.TCPControlUnit.KinematicUnitName:  Name of the KinematicUnit Proxy
+#  Attributes:
+#  - Case sensitivity:   no
+#  - Required:           yes
+ArmarX.TCPControlUnit.KinematicUnitName = Armar3KinematicUnit
+
+
+# ArmarX.TCPControlUnit.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.TCPControlUnit.ObjectName = ""
+
+
+# ==================================================================
+# ArmarX.TCPControlUnitObserver properties
+# ==================================================================
+
+# ArmarX.TCPControlUnitObserver.TCPControlUnitName:  Name of the TCPControlUnit
+#  Attributes:
+#  - Case sensitivity:   no
+#  - Required:           yes
+ArmarX.TCPControlUnitObserver.TCPControlUnitName = TCPControlUnit
+
+
+# ArmarX.TCPControlUnitObserver.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Error, Fatal, Info, Undefined, Verbose, Warning}
+# ArmarX.TCPControlUnitObserver.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.TCPControlUnitObserver.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# ArmarX.TCPControlUnitObserver.ObjectName = ""
+
+
+
diff --git a/scenarios/KinematicSimulationArmar3/config/WorkingMemory.cfg b/scenarios/KinematicSimulationArmar3/config/WorkingMemory.cfg
new file mode 100644
index 0000000000000000000000000000000000000000..6b9351e1ddd297c346e559a232ff100fa4e38bbb
--- /dev/null
+++ b/scenarios/KinematicSimulationArmar3/config/WorkingMemory.cfg
@@ -0,0 +1,156 @@
+# ==================================================================
+# MemoryX properties
+# ==================================================================
+
+# MemoryX.CachePath:  Path for cache files
+#  Attributes:
+#  - Default:            ${HOME}/.armarx/mongo/.cache
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.CachePath = ${HOME}/.armarx/mongo/.cache
+
+
+# MemoryX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.DataPath = ""
+
+
+# MemoryX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Verbose
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# MemoryX.Verbosity = Verbose
+
+
+# MemoryX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# MemoryX.DisableLogging = 0
+
+
+# MemoryX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.ApplicationName = ""
+
+
+# MemoryX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.Config = ""
+
+
+# ==================================================================
+# MemoryX.WorkingMemory properties
+# ==================================================================
+
+# MemoryX.WorkingMemory.MatchByClassName:  Check for class equality when searching for corresponding instance
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# MemoryX.WorkingMemory.MatchByClassName = 1
+
+
+# MemoryX.WorkingMemory.MatchThreshold:  Threshold value of spatial proximity between observations to consider them belonging to the same instance (0..1)
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.WorkingMemory.MatchThreshold = 0
+
+
+# MemoryX.WorkingMemory.UpdatesTopicName:  Name of IceStrom topic to publish scene updates on
+#  Attributes:
+#  - Default:            WorkingMemoryUpdates
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.WorkingMemory.UpdatesTopicName = WorkingMemoryUpdates
+
+
+# MemoryX.WorkingMemory.UseKalmanFilter:  Switch fusion with Kalman Filter on/off.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+MemoryX.WorkingMemory.UseKalmanFilter = 1
+
+
+# MemoryX.WorkingMemory.PublishUpdates:  Publish scene updates (ObjectCreated/Updated/Removed) on IceStrom topic
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+MemoryX.WorkingMemory.PublishUpdates = 1
+
+
+# MemoryX.WorkingMemory.UseLongtermMemory:  Switch longterm memory on/off.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+MemoryX.WorkingMemory.UseLongtermMemory = 1
+
+
+# MemoryX.WorkingMemory.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {Error, Fatal, Info, Undefined, Verbose, Warning}
+# MemoryX.WorkingMemory.MinimumLoggingLevel = Undefined
+
+
+# MemoryX.WorkingMemory.UsePriorMemory:  Switch prior knowledge on/off.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   no
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# MemoryX.WorkingMemory.UsePriorMemory = 1
+
+
+# MemoryX.WorkingMemory.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.WorkingMemory.ObjectName = ""
+
+
+# MemoryX.WorkingMemory.PriorMemoryName:  Name of PriorKnowledge Ice component
+#  Attributes:
+#  - Default:            PriorKnowledge
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.WorkingMemory.PriorMemoryName = PriorKnowledge
+
+
+# MemoryX.WorkingMemory.LongtermMemoryName:  Name of LongtermMemory Ice component
+#  Attributes:
+#  - Default:            LongtermMemory
+#  - Case sensitivity:   no
+#  - Required:           no
+# MemoryX.WorkingMemory.LongtermMemoryName = LongtermMemory
+
+MemoryX.ObjectLocalizationMemoryUpdater.CheckFieldOfView = 0
+MemoryX.ObjectLocalizationMemoryUpdater.HandNodeNameLeft = "TCP L"
+MemoryX.ObjectLocalizationMemoryUpdater.HandNodeNameRight = "TCP R"
+
+
diff --git a/scenarios/MMMScenario/CMakeLists.txt b/scenarios/MMMScenario/CMakeLists.txt
deleted file mode 100644
index 14a51ca63854220bb4e611fbced631dcf5661e5b..0000000000000000000000000000000000000000
--- a/scenarios/MMMScenario/CMakeLists.txt
+++ /dev/null
@@ -1,6 +0,0 @@
-set(SCENARIO_CONFIG_COMPONENTS
-    config/MMMPlayerApp.cfg
-    )
-
-# optional 3rd parameter: "path/to/global/config.cfg"
-armarx_scenario_from_configs("MMMScenario" "${SCENARIO_CONFIG_COMPONENTS}" "config/global.cfg")
diff --git a/scenarios/MMMScenario/config/MMMPlayerApp.cfg b/scenarios/MMMScenario/config/MMMPlayerApp.cfg
deleted file mode 100644
index 49a06df94b78546bb804deb9ece1637b02308b8d..0000000000000000000000000000000000000000
--- a/scenarios/MMMScenario/config/MMMPlayerApp.cfg
+++ /dev/null
@@ -1,175 +0,0 @@
-# ==================================================================
-# ArmarX properties
-# ==================================================================
-
-# ArmarX.CachePath:  Path for cache files
-#  Attributes:
-#  - Default:            ${HOME}/.armarx/mongo/.cache
-#  - Case sensitivity:   no
-#  - Required:           no
-# ArmarX.CachePath = ${HOME}/.armarx/mongo/.cache
-
-
-# ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
-#  Attributes:
-#  - Default:            0
-#  - Case sensitivity:   no
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.EnableProfiling = 0
-
-
-# ArmarX.DataPath:  Semicolon-separated search list for data files
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   no
-#  - Required:           no
-# ArmarX.DataPath = ""
-
-
-# ArmarX.Verbosity:  Global logging level for whole application
-#  Attributes:
-#  - Default:            Verbose
-#  - Case sensitivity:   no
-#  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-# ArmarX.Verbosity = Verbose
-
-
-# ArmarX.DisableLogging:  Turn logging off in whole application
-#  Attributes:
-#  - Default:            0
-#  - Case sensitivity:   no
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.DisableLogging = 0
-
-
-# ArmarX.ApplicationName:  Application name
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   no
-#  - Required:           no
-# ArmarX.ApplicationName = ""
-
-
-# ArmarX.DependenciesConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
-#  Attributes:
-#  - Default:            ./config/dependencies.cfg
-#  - Case sensitivity:   no
-#  - Required:           no
-# ArmarX.DependenciesConfig = ./config/dependencies.cfg
-
-
-# ArmarX.Config:  Comma-separated list of configuration files 
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   no
-#  - Required:           no
-# ArmarX.Config = ""
-
-
-# ==================================================================
-# ArmarX.MMMPlayer properties
-# ==================================================================
-
-# ArmarX.MMMPlayer.Kp:  Proportional gain value of PID Controller
-#  Attributes:
-#  - Default:            1
-#  - Case sensitivity:   no
-#  - Required:           no
-ArmarX.MMMPlayer.Kp = 1
-
-
-# ArmarX.MMMPlayer.Kd:  Differential gain value of PID Controller
-#  Attributes:
-#  - Default:            1
-#  - Case sensitivity:   no
-#  - Required:           no
-ArmarX.MMMPlayer.Kd = 0
-
-
-# ArmarX.MMMPlayer.UsePIDController:  Specify whether the PID Controller should be used
-#  Attributes:
-#  - Default:            1
-#  - Case sensitivity:   no
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-ArmarX.MMMPlayer.UsePIDController = 1
-
-
-# ArmarX.MMMPlayer.LoopPlayback:  Specify whether should be repeated after execution
-#  Attributes:
-#  - Default:            1
-#  - Case sensitivity:   no
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.MMMPlayer.LoopPlayback = 1
-
-
-# ArmarX.MMMPlayer.KinematicTopicName:  Name of the KinematicUnit reporting topic
-#  Attributes:
-#  - Case sensitivity:   no
-#  - Required:           yes
-ArmarX.MMMPlayer.KinematicTopicName = AllState
-
-
-# ArmarX.MMMPlayer.KinematicUnitName:  Name of the KinematicUnit to which the joint values should be sent
-#  Attributes:
-#  - Case sensitivity:   no
-#  - Required:           yes
-ArmarX.MMMPlayer.KinematicUnitName = KinematicUnitArmar4
-
-
-# ArmarX.MMMPlayer.FPS:  FPS with which the recording should be executed. Velocities will be adapted.
-#  Attributes:
-#  - Default:            100
-#  - Case sensitivity:   no
-#  - Required:           no
-ArmarX.MMMPlayer.FPS = 100
-
-
-# ArmarX.MMMPlayer.MMMFile:  Path to MMM XML File
-#  Attributes:
-#  - Case sensitivity:   no
-#  - Required:           yes
-ArmarX.MMMPlayer.MMMFile = /home/SMBAD/marek/Dokumente/Daten/point_at_left03_armar4.xml
-
-
-# ArmarX.MMMPlayer.EnableProfiling:  enable profiler which is used for logging performance events
-#  Attributes:
-#  - Default:            0
-#  - Case sensitivity:   no
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.MMMPlayer.EnableProfiling = 0
-
-
-# ArmarX.MMMPlayer.Ki:  Integral gain value of PID Controller
-#  Attributes:
-#  - Default:            9.99999975e-06
-#  - Case sensitivity:   no
-#  - Required:           no
-ArmarX.MMMPlayer.Ki = 9.99999975e-06
-ArmarX.MMMPlayer.absMaximumVelocity = 1000000
-ArmarX.MMMPlayer.RobotNodeSetName = AllState
-
-
-# ArmarX.MMMPlayer.MinimumLoggingLevel:  Local logging level only for this component
-#  Attributes:
-#  - Default:            Undefined
-#  - Case sensitivity:   no
-#  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Info, Undefined, Verbose, Warning}
-# ArmarX.MMMPlayer.MinimumLoggingLevel = Undefined
-
-
-# ArmarX.MMMPlayer.ObjectName:  Name of IceGrid well-known object
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   no
-#  - Required:           no
-# ArmarX.MMMPlayer.ObjectName = ""
-
-
-
diff --git a/scenarios/MMMScenario/config/global.cfg b/scenarios/MMMScenario/config/global.cfg
deleted file mode 100644
index ac68157eaa025deca2b5c7063b7e5690f759b8cf..0000000000000000000000000000000000000000
--- a/scenarios/MMMScenario/config/global.cfg
+++ /dev/null
@@ -1,12 +0,0 @@
-ArmarX.DisableLogging = no
-VisionX.DisableLogging = no
-
-ArmarX.GlobalMinimumLoggingLevel = Verbose
-#MemoryX.Verbosity = Debug
-VisionX.Verbosity = Verbose
-
-RobotConfig.RobotFileName=Armar4/robotmodel/Armar4.xml
-#RobotConfig.RobotName=Armar4
-RobotConfig.AgentName=Armar4
-RobotConfig.RobotNodeSetName=All
-#RobotConfig.PlatformName=Platform
diff --git a/scenarios/tests/DebugDrawerTest/DebugDrawerTestApp/CMakeLists.txt b/scenarios/tests/DebugDrawerTest/DebugDrawerTestApp/CMakeLists.txt
index 4cdab2f848eba6ba8ea1939c27b76c770f3f1c54..8ba9a6e56bab9040426e2e6993ba1804e5cf9482 100644
--- a/scenarios/tests/DebugDrawerTest/DebugDrawerTestApp/CMakeLists.txt
+++ b/scenarios/tests/DebugDrawerTest/DebugDrawerTestApp/CMakeLists.txt
@@ -7,7 +7,7 @@ if(Eigen3_FOUND)
 endif()
 
 set(COMPONENT_LIBS
-ArmarXInterfaces
+ArmarXCoreInterfaces
 ArmarXCore
 RobotAPIInterfaces
 DebugDrawer
diff --git a/scenarios/tests/DebugDrawerTest/DebugDrawerTestApp/DebugDrawerTest.cpp b/scenarios/tests/DebugDrawerTest/DebugDrawerTestApp/DebugDrawerTest.cpp
index c3380bff11dd73768e9de647d33fe9b139067c86..ae00f7755b5f71eaeaaf7907617d065542f8c612 100644
--- a/scenarios/tests/DebugDrawerTest/DebugDrawerTestApp/DebugDrawerTest.cpp
+++ b/scenarios/tests/DebugDrawerTest/DebugDrawerTestApp/DebugDrawerTest.cpp
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    RobotAPI::DebugDrawerTestApp
 * @author     vahrenkamp
 * @date       2015
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
diff --git a/scenarios/tests/DebugDrawerTest/DebugDrawerTestApp/DebugDrawerTest.h b/scenarios/tests/DebugDrawerTest/DebugDrawerTestApp/DebugDrawerTest.h
index c57c9963feae86a10204d7dd928d5c059d297c6a..3f8c50bfb1af875c41ce5e236929121a31021b3d 100644
--- a/scenarios/tests/DebugDrawerTest/DebugDrawerTestApp/DebugDrawerTest.h
+++ b/scenarios/tests/DebugDrawerTest/DebugDrawerTestApp/DebugDrawerTest.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,14 +16,14 @@
 * @package    RobotAPI::DebugDrawerTestApp
 * @author     vahrenkamp
 * @date       2015
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
 #ifndef ARMARX_COMPONENT_DebugDrawerTest_H
 #define ARMARX_COMPONENT_DebugDrawerTest_H
 
-#include <Core/core/Component.h>
+#include <ArmarXCore/core/Component.h>
 #include <RobotAPI/interface/visualization/DebugDrawerInterface.h>
 
 namespace armarx
diff --git a/scenarios/tests/DebugDrawerTest/DebugDrawerTestApp/DebugDrawerTestApp.h b/scenarios/tests/DebugDrawerTest/DebugDrawerTestApp/DebugDrawerTestApp.h
index 962deed6ff20be3e134c5bcf40c6048e0dedab1d..47686c9267c33184bacc2e70e1ee19c3b66e48cb 100644
--- a/scenarios/tests/DebugDrawerTest/DebugDrawerTestApp/DebugDrawerTestApp.h
+++ b/scenarios/tests/DebugDrawerTest/DebugDrawerTestApp/DebugDrawerTestApp.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,14 +16,14 @@
 * @package    RobotAPI::DebugDrawerTestApp
 * @author     vahrenkamp
 * @date       2015
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
 
 #include "DebugDrawerTest.h"
 
-#include <Core/core/application/Application.h>
+#include <ArmarXCore/core/application/Application.h>
 
 namespace armarx
 {
diff --git a/scenarios/tests/DebugDrawerTest/DebugDrawerTestApp/main.cpp b/scenarios/tests/DebugDrawerTest/DebugDrawerTestApp/main.cpp
index 9923bbcb3c8b852f568d25d2b627622b3594e2de..f837e8036f30884b4cffaa3143d51a289366eb10 100644
--- a/scenarios/tests/DebugDrawerTest/DebugDrawerTestApp/main.cpp
+++ b/scenarios/tests/DebugDrawerTest/DebugDrawerTestApp/main.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    RobotAPI::DebugDrawerTestApp
  * @author     vahrenkamp
  * @date       2015
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 #include "DebugDrawerTestApp.h"
-#include <Core/core/logging/Logging.h>
+#include <ArmarXCore/core/logging/Logging.h>
 
 int main(int argc, char* argv[])
 {
diff --git a/scenarios/tests/RemoteRobotTest/RemoteRobotTestProject/RemoteRobotTestProject.cpp b/scenarios/tests/RemoteRobotTest/RemoteRobotTestProject/RemoteRobotTestProject.cpp
index e70ec49339c10c70f60ed3ba311a9987a03f87a4..103f195414416fdedf8c9b1894f13563c1948217 100644
--- a/scenarios/tests/RemoteRobotTest/RemoteRobotTestProject/RemoteRobotTestProject.cpp
+++ b/scenarios/tests/RemoteRobotTest/RemoteRobotTestProject/RemoteRobotTestProject.cpp
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    RemoteRobotTestProject::
 * @author     ( at kit dot edu)
 * @date       
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
diff --git a/scenarios/tests/RemoteRobotTest/RemoteRobotTestProject/RemoteRobotTestProject.h b/scenarios/tests/RemoteRobotTest/RemoteRobotTestProject/RemoteRobotTestProject.h
index bcdafe56aeb774dcc92204465455b6f2b241a00e..94bf8c14aa4609b4138e9619d51039c858516a6f 100644
--- a/scenarios/tests/RemoteRobotTest/RemoteRobotTestProject/RemoteRobotTestProject.h
+++ b/scenarios/tests/RemoteRobotTest/RemoteRobotTestProject/RemoteRobotTestProject.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    RemoteRobotTestProject::
 * @author     ( at kit dot edu)
 * @date       
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
diff --git a/scenarios/tests/RemoteRobotTest/RemoteRobotTestProject/RemoteRobotTestProjectApp.h b/scenarios/tests/RemoteRobotTest/RemoteRobotTestProject/RemoteRobotTestProjectApp.h
index a468c295916cf511089b4b0e6f42126c4c902fad..b0b64a6b0117a737ac35dba6756f949c28940a8d 100644
--- a/scenarios/tests/RemoteRobotTest/RemoteRobotTestProject/RemoteRobotTestProjectApp.h
+++ b/scenarios/tests/RemoteRobotTest/RemoteRobotTestProject/RemoteRobotTestProjectApp.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    RemoteRobotTestProject::
 * @author     ( at kit dot edu)
 * @date
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
diff --git a/scenarios/tests/RemoteRobotTest/RemoteRobotTestProject/test/RemoteRobotTestProjectTest.cpp b/scenarios/tests/RemoteRobotTest/RemoteRobotTestProject/test/RemoteRobotTestProjectTest.cpp
index ab3310ce34dd85cafcdc7720a23e97c58a2e0439..aa3e2250ab0b086aad64a442585a347430951fc2 100644
--- a/scenarios/tests/RemoteRobotTest/RemoteRobotTestProject/test/RemoteRobotTestProjectTest.cpp
+++ b/scenarios/tests/RemoteRobotTest/RemoteRobotTestProject/test/RemoteRobotTestProjectTest.cpp
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    RemoteRobotTestProject::
 * @author     (at kit dot edu)
 * @date       
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
diff --git a/source/RobotAPI/applications/CMakeLists.txt b/source/RobotAPI/applications/CMakeLists.txt
index 0ebfe454de9a3bee8dc9016a3f81d6ef5b2a2360..821ef9dc2da3cda5f8f61f7a03809c1fc0775195 100644
--- a/source/RobotAPI/applications/CMakeLists.txt
+++ b/source/RobotAPI/applications/CMakeLists.txt
@@ -14,12 +14,9 @@ add_subdirectory(KinematicUnitSimulation)
 add_subdirectory(PlatformUnitSimulation)
 add_subdirectory(PlatformUnitObserver)
 add_subdirectory(RobotStateComponent)
-add_subdirectory(RobotIK)
 add_subdirectory(HandUnitSimulation)
 add_subdirectory(ForceTorqueUnitSimulation)
 
 
-add_subdirectory(MMMPlayer)
-
 add_subdirectory(XsensIMU)
 add_subdirectory(InertialMeasurementUnitObserver)
diff --git a/source/RobotAPI/applications/ForceTorqueObserver/ForceTorqueObserverApp.h b/source/RobotAPI/applications/ForceTorqueObserver/ForceTorqueObserverApp.h
index b5ca6815de9f02ec8426b1f795f3658a9437e963..c415f85c18c650dc3b277d802cb72f8524f8bd58 100644
--- a/source/RobotAPI/applications/ForceTorqueObserver/ForceTorqueObserverApp.h
+++ b/source/RobotAPI/applications/ForceTorqueObserver/ForceTorqueObserverApp.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,22 +16,22 @@
  * @package    ArmarXCore::applications
  * @author     Kai Welke (weöle dot at kit dot edu)
  * @date       2012
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 
-#include <Core/core/application/Application.h>
+#include <ArmarXCore/core/application/Application.h>
 #include <RobotAPI/components/units/ForceTorqueObserver.h>
 
 namespace armarx
 {
     class ForceTorqueObserverApp :
-		virtual public armarx::Application
-	{
+        virtual public armarx::Application
+    {
         void setup(const ManagedIceObjectRegistryInterfacePtr& registry, Ice::PropertiesPtr properties)
         {
-            registry->addObject( Component::create<ForceTorqueObserver>(properties) );
+            registry->addObject(Component::create<ForceTorqueObserver>(properties));
         }
     };
 }
diff --git a/source/RobotAPI/applications/ForceTorqueObserver/main.cpp b/source/RobotAPI/applications/ForceTorqueObserver/main.cpp
index 52e9334438a84dd529a3930b5fdcfb9f64bbaf27..f75a56a95de5d3dc42543797a4c5ab4aedd30a2b 100644
--- a/source/RobotAPI/applications/ForceTorqueObserver/main.cpp
+++ b/source/RobotAPI/applications/ForceTorqueObserver/main.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    RobotAPI::application::ForceTorqueObserver
  * @author     Manfred Kroehnert
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 #include "ForceTorqueObserverApp.h"
-#include <Core/core/logging/Logging.h>
+#include <ArmarXCore/core/logging/Logging.h>
 
 int main(int argc, char* argv[])
 {
diff --git a/source/RobotAPI/applications/ForceTorqueUnitSimulation/ForceTorqueUnitSimulationApp.h b/source/RobotAPI/applications/ForceTorqueUnitSimulation/ForceTorqueUnitSimulationApp.h
index be328546e3fcb0446f26ae29d915c7d614655c65..83c5468821c29a916335db9e2f94094d159f9fcb 100644
--- a/source/RobotAPI/applications/ForceTorqueUnitSimulation/ForceTorqueUnitSimulationApp.h
+++ b/source/RobotAPI/applications/ForceTorqueUnitSimulation/ForceTorqueUnitSimulationApp.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    RobotAPI::applications
  * @author     Peter Kaiser
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 
-#include <Core/core/application/Application.h>
+#include <ArmarXCore/core/application/Application.h>
 #include <RobotAPI/components/units/ForceTorqueUnitSimulation.h>
 
 namespace armarx
@@ -36,8 +35,8 @@ namespace armarx
         /**
          * @see armarx::Application::setup()
          */
-        void setup(const ManagedIceObjectRegistryInterfacePtr &registry, Ice::PropertiesPtr properties) 
-        { 
+        void setup(const ManagedIceObjectRegistryInterfacePtr& registry, Ice::PropertiesPtr properties)
+        {
             registry->addObject(Component::create<ForceTorqueUnitSimulation>(properties));
         }
     };
diff --git a/source/RobotAPI/applications/ForceTorqueUnitSimulation/main.cpp b/source/RobotAPI/applications/ForceTorqueUnitSimulation/main.cpp
index 398862ed8b6d5b6159043ea6bad6cc5e539ef054..080b5c2c50f0a4571180fecd57aefb5070217e9d 100644
--- a/source/RobotAPI/applications/ForceTorqueUnitSimulation/main.cpp
+++ b/source/RobotAPI/applications/ForceTorqueUnitSimulation/main.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    RobotAPI::application::ForceTorqueUnitSimulation
  * @author     Peter Kaiser
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
diff --git a/source/RobotAPI/applications/HandUnitSimulation/CMakeLists.txt b/source/RobotAPI/applications/HandUnitSimulation/CMakeLists.txt
index 529b2f94308fd1a0d9305cf1cbf5d2bd2669daa2..5ab07e08cab7afea440dfd8a58890e9573b27967 100644
--- a/source/RobotAPI/applications/HandUnitSimulation/CMakeLists.txt
+++ b/source/RobotAPI/applications/HandUnitSimulation/CMakeLists.txt
@@ -9,7 +9,7 @@ if (Eigen3_FOUND)
 endif()
 
 
-set(COMPONENT_LIBS RobotAPIUnits ArmarXInterfaces ArmarXCore)
+set(COMPONENT_LIBS RobotAPIUnits ArmarXCoreInterfaces ArmarXCore)
 
 set(EXE_SOURCE main.cpp)
 
diff --git a/source/RobotAPI/applications/HandUnitSimulation/HandUnitSimulationApp.h b/source/RobotAPI/applications/HandUnitSimulation/HandUnitSimulationApp.h
index bb995504b1d3325b443457b46a07faf00bfde838..ba67452edd496005d9e3d0b5d8778de2d79f3101 100644
--- a/source/RobotAPI/applications/HandUnitSimulation/HandUnitSimulationApp.h
+++ b/source/RobotAPI/applications/HandUnitSimulation/HandUnitSimulationApp.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    RobotAPI::application::HandUnitSimulation
  * @author     David Schiebener ( schiebener at kit dot edu )
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -27,7 +26,7 @@
 
 #include <RobotAPI/components/units/HandUnitSimulation.h>
 
-#include <Core/core/application/Application.h>
+#include <ArmarXCore/core/application/Application.h>
 
 namespace armarx
 {
@@ -46,7 +45,7 @@ namespace armarx
         void setup(const ManagedIceObjectRegistryInterfacePtr& registry,
                    Ice::PropertiesPtr properties)
         {
-            registry->addObject( Component::create<HandUnitSimulation>(properties) );
+            registry->addObject(Component::create<HandUnitSimulation>(properties));
         }
     };
 }
diff --git a/source/RobotAPI/applications/HandUnitSimulation/main.cpp b/source/RobotAPI/applications/HandUnitSimulation/main.cpp
index 8cdb60028b4e43738a4fc9c94dc0b4de52b3dce7..27de1ec1c24063aac04682f82e99f555ad9f839d 100644
--- a/source/RobotAPI/applications/HandUnitSimulation/main.cpp
+++ b/source/RobotAPI/applications/HandUnitSimulation/main.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    RobotAPI::application::HandUnitSimulation
  * @author     David Schiebener ( schiebener at kit dot edu )
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 #include "HandUnitSimulationApp.h"
-#include <Core/core/logging/Logging.h>
+#include <ArmarXCore/core/logging/Logging.h>
 
 int main(int argc, char* argv[])
 {
diff --git a/source/RobotAPI/applications/HapticObserver/HapticObserverApp.h b/source/RobotAPI/applications/HapticObserver/HapticObserverApp.h
index ff769075646fc41ac24c53674d5c672da55f3bb4..8bae1433630337201d8bb4d3324d069332cb1fbe 100644
--- a/source/RobotAPI/applications/HapticObserver/HapticObserverApp.h
+++ b/source/RobotAPI/applications/HapticObserver/HapticObserverApp.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,14 +16,14 @@
  * @package    RobotAPI::application::HapticObserver
  * @author     Simon Ottenhaus ( simon dot ottenhaus at kit dot edu )
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 #ifndef _ARMARX_APPLICATION_RobotAPI_HapticObserver_H
 #define _ARMARX_APPLICATION_RobotAPI_HapticObserver_H
 
-#include <Core/core/application/Application.h>
+#include <ArmarXCore/core/application/Application.h>
 #include <RobotAPI/components/units/HapticObserver.h>
 
 namespace armarx
@@ -44,7 +43,7 @@ namespace armarx
         void setup(const ManagedIceObjectRegistryInterfacePtr& registry,
                    Ice::PropertiesPtr properties)
         {
-            registry->addObject( Component::create<HapticObserver>(properties) );
+            registry->addObject(Component::create<HapticObserver>(properties));
         }
     };
 }
diff --git a/source/RobotAPI/applications/HapticObserver/main.cpp b/source/RobotAPI/applications/HapticObserver/main.cpp
index e0b4270b484237e71355600dde6e595589435535..ca0fdaf45cb5a1e1abc0c923470f1e989b4a6ca8 100644
--- a/source/RobotAPI/applications/HapticObserver/main.cpp
+++ b/source/RobotAPI/applications/HapticObserver/main.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    RobotAPI::application::HapticObserver
  * @author     Simon Ottenhaus ( simon dot ottenhaus at kit dot edu )
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 #include "HapticObserverApp.h"
-#include <Core/core/logging/Logging.h>
+#include <ArmarXCore/core/logging/Logging.h>
 
 int main(int argc, char* argv[])
 {
diff --git a/source/RobotAPI/applications/HeadIKUnit/HeadIKUnitApp.h b/source/RobotAPI/applications/HeadIKUnit/HeadIKUnitApp.h
index 01246f6bde9b23e73c256eee6aee684960405938..1e4d804b41948b6f339bbb210c4684ee25e15a7b 100644
--- a/source/RobotAPI/applications/HeadIKUnit/HeadIKUnitApp.h
+++ b/source/RobotAPI/applications/HeadIKUnit/HeadIKUnitApp.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    ArmarXCore::applications
  * @author     David Schiebener (schiebener at kit dot edu)
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 
-#include <Core/core/application/Application.h>
+#include <ArmarXCore/core/application/Application.h>
 #include <RobotAPI/components/units/HeadIKUnit.h>
 
 namespace armarx
@@ -32,7 +31,7 @@ namespace armarx
     {
         void setup(const ManagedIceObjectRegistryInterfacePtr& registry, Ice::PropertiesPtr properties)
         {
-            registry->addObject( Component::create<HeadIKUnit>(properties) );
+            registry->addObject(Component::create<HeadIKUnit>(properties));
         }
     };
 }
diff --git a/source/RobotAPI/applications/HeadIKUnit/main.cpp b/source/RobotAPI/applications/HeadIKUnit/main.cpp
index 411a5eef168cdd16c4a3f58e69d221139511a585..e919c4a2428af4eda531c5ec684b813044451081 100644
--- a/source/RobotAPI/applications/HeadIKUnit/main.cpp
+++ b/source/RobotAPI/applications/HeadIKUnit/main.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    RobotAPI::application::HeadIKUnit
  * @author     David Schiebener
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
diff --git a/source/RobotAPI/applications/InertialMeasurementUnitObserver/CMakeLists.txt b/source/RobotAPI/applications/InertialMeasurementUnitObserver/CMakeLists.txt
index 9fd6cf01ff46b757947cacb71591b6edba6b9d7b..e280918bcf6713df170b90e5a40273c4b5da86c2 100644
--- a/source/RobotAPI/applications/InertialMeasurementUnitObserver/CMakeLists.txt
+++ b/source/RobotAPI/applications/InertialMeasurementUnitObserver/CMakeLists.txt
@@ -9,7 +9,7 @@ armarx_component_set_name("InertialMeasurementUnitObserverApp")
 #    include_directories(${MyLib_INCLUDE_DIRS})
 #endif()
 
-set(COMPONENT_LIBS ArmarXInterfaces ArmarXCore ArmarXCoreObservers  RobotAPIUnits)
+set(COMPONENT_LIBS ArmarXCoreInterfaces ArmarXCore ArmarXCoreObservers  RobotAPIUnits)
 
 set(EXE_SOURCE InertialMeasurementUnitObserverApp.h main.cpp)
 
diff --git a/source/RobotAPI/applications/InertialMeasurementUnitObserver/InertialMeasurementUnitObserverApp.h b/source/RobotAPI/applications/InertialMeasurementUnitObserver/InertialMeasurementUnitObserverApp.h
index eb1acbd082b3e17a9ba4a8fea2694c4b25ab0b1c..39898375eef5a33542b0d692b4fbd5be7bbc038f 100644
--- a/source/RobotAPI/applications/InertialMeasurementUnitObserver/InertialMeasurementUnitObserverApp.h
+++ b/source/RobotAPI/applications/InertialMeasurementUnitObserver/InertialMeasurementUnitObserverApp.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    RobotAPI::application::InertialMeasurementUnitObserver
  * @author     Markus Grotz ( markus-grotz at web dot de )
  * @date       2015
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -27,8 +26,8 @@
 
 #include <RobotAPI/components/units/InertialMeasurementUnitObserver.h>
 
-#include <Core/core/application/Application.h>
-#include <Core/core/Component.h>
+#include <ArmarXCore/core/application/Application.h>
+#include <ArmarXCore/core/Component.h>
 
 
 namespace armarx
@@ -48,7 +47,7 @@ namespace armarx
         void setup(const ManagedIceObjectRegistryInterfacePtr& registry,
                    Ice::PropertiesPtr properties)
         {
-            registry->addObject( Component::create<InertialMeasurementUnitObserver>(properties) );
+            registry->addObject(Component::create<InertialMeasurementUnitObserver>(properties));
         }
     };
 }
diff --git a/source/RobotAPI/applications/InertialMeasurementUnitObserver/main.cpp b/source/RobotAPI/applications/InertialMeasurementUnitObserver/main.cpp
index 661d5706f88f4630aad7da1be2749629c69f9cd6..1a293f2ace157ceed9e65912a1197028b4c7ffb2 100644
--- a/source/RobotAPI/applications/InertialMeasurementUnitObserver/main.cpp
+++ b/source/RobotAPI/applications/InertialMeasurementUnitObserver/main.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    RobotAPI::application::InertialMeasurementUnitObserver
  * @author     Markus Grotz ( markus-grotz at web dot de )
  * @date       2015
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 #include "InertialMeasurementUnitObserverApp.h"
-#include <Core/core/logging/Logging.h>
+#include <ArmarXCore/core/logging/Logging.h>
 
 int main(int argc, char* argv[])
 {
diff --git a/source/RobotAPI/applications/KinematicUnitObserver/KinematicUnitObserverApp.h b/source/RobotAPI/applications/KinematicUnitObserver/KinematicUnitObserverApp.h
index 84dcb2406dc3f2da30874d12db1a9bebb2a11127..5dbc9624a5e8481582d1e3a67fd87fcf72d943b3 100644
--- a/source/RobotAPI/applications/KinematicUnitObserver/KinematicUnitObserverApp.h
+++ b/source/RobotAPI/applications/KinematicUnitObserver/KinematicUnitObserverApp.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    ArmarXCore::applications
  * @author     Christian Boege (boege dot at kit dot edu)
  * @date       2011
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 
-#include <Core/core/application/Application.h>
+#include <ArmarXCore/core/application/Application.h>
 #include <RobotAPI/components/units/KinematicUnitObserver.h>
 
 namespace armarx
@@ -30,15 +29,15 @@ namespace armarx
     /**
      * Application for testing the armarx::KinematicUnitObserver
      */
-	class KinematicUnitObserverApp :
-		virtual public armarx::Application
-	{
+    class KinematicUnitObserverApp :
+        virtual public armarx::Application
+    {
         /**
          * @see armarx::Application::setup()
          */
-        void setup(const ManagedIceObjectRegistryInterfacePtr& registry, Ice::PropertiesPtr properties) 
-        { 
-            registry->addObject( Component::create<KinematicUnitObserver>(properties) ); 
+        void setup(const ManagedIceObjectRegistryInterfacePtr& registry, Ice::PropertiesPtr properties)
+        {
+            registry->addObject(Component::create<KinematicUnitObserver>(properties));
         }
-	};
+    };
 }
diff --git a/source/RobotAPI/applications/KinematicUnitObserver/main.cpp b/source/RobotAPI/applications/KinematicUnitObserver/main.cpp
index 6caa89a542892ca94ff669dc94fc9034bb8c0dbf..accfeceb8d206d5851c5aa080314443bb8b708a7 100644
--- a/source/RobotAPI/applications/KinematicUnitObserver/main.cpp
+++ b/source/RobotAPI/applications/KinematicUnitObserver/main.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    Core::application::KinematicUnitObserver
  * @author     Manfred Kroehnert
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 #include "KinematicUnitObserverApp.h"
-#include <Core/core/logging/Logging.h>
+#include <ArmarXCore/core/logging/Logging.h>
 
 int main(int argc, char* argv[])
 {
diff --git a/source/RobotAPI/applications/KinematicUnitSimulation/KinematicUnitSimulationApp.h b/source/RobotAPI/applications/KinematicUnitSimulation/KinematicUnitSimulationApp.h
index 6d4add7170f9799914444b62e68f76d49a4fcc72..46e2fa71bb276fd00f971ca8892bb87438cc700e 100644
--- a/source/RobotAPI/applications/KinematicUnitSimulation/KinematicUnitSimulationApp.h
+++ b/source/RobotAPI/applications/KinematicUnitSimulation/KinematicUnitSimulationApp.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    ArmarXCore::applications
  * @author     Christian Boege (boege at kit dot edu)
  * @date       2011
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 
-#include <Core/core/application/Application.h>
+#include <ArmarXCore/core/application/Application.h>
 #include <RobotAPI/components/units/KinematicUnitSimulation.h>
 
 namespace armarx
@@ -36,9 +35,9 @@ namespace armarx
         /**
          * @see armarx::Application::setup()
          */
-        void setup(const ManagedIceObjectRegistryInterfacePtr& registry, Ice::PropertiesPtr properties) 
-        { 
-            registry->addObject( Component::create<KinematicUnitSimulation>(properties) ); 
+        void setup(const ManagedIceObjectRegistryInterfacePtr& registry, Ice::PropertiesPtr properties)
+        {
+            registry->addObject(Component::create<KinematicUnitSimulation>(properties));
         }
     };
 }
diff --git a/source/RobotAPI/applications/KinematicUnitSimulation/main.cpp b/source/RobotAPI/applications/KinematicUnitSimulation/main.cpp
index 14648392913909c1fe51dc553e4e05938278251c..243525eb84e1b320bb7a28a8317ab4e4c849f270 100644
--- a/source/RobotAPI/applications/KinematicUnitSimulation/main.cpp
+++ b/source/RobotAPI/applications/KinematicUnitSimulation/main.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    Core::application::KinematicUnitSimulation
  * @author     Manfred Kroehnert
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 #include "KinematicUnitSimulationApp.h"
-#include <Core/core/logging/Logging.h>
+#include <ArmarXCore/core/logging/Logging.h>
 
 int main(int argc, char* argv[])
 {
diff --git a/source/RobotAPI/applications/MMMPlayer/CMakeLists.txt b/source/RobotAPI/applications/MMMPlayer/CMakeLists.txt
index 1aa2b39a4c3f68a824af971907286c0716c0eef0..84a48de2986de1098d0fc14f95815cb5b140da6c 100644
--- a/source/RobotAPI/applications/MMMPlayer/CMakeLists.txt
+++ b/source/RobotAPI/applications/MMMPlayer/CMakeLists.txt
@@ -16,7 +16,7 @@ if (Eigen3_FOUND)
     include_directories(${Eigen3_INCLUDE_DIR})
 endif()
 
-set(COMPONENT_LIBS MMMPlayer ArmarXInterfaces ArmarXCore ${MMMCORE_LIBRARIES})
+set(COMPONENT_LIBS MMMPlayer ArmarXCoreInterfaces ArmarXCore ${MMMCORE_LIBRARIES})
 
 set(EXE_SOURCE MMMPlayerApp.h main.cpp)
 
diff --git a/source/RobotAPI/applications/MMMPlayer/MMMPlayerApp.h b/source/RobotAPI/applications/MMMPlayer/MMMPlayerApp.h
index 809e37f4b7e6a2082fc2c7ed2225ba580fe8053b..e1026ef8377fa2ab00d2424676c584fdec17794e 100644
--- a/source/RobotAPI/applications/MMMPlayer/MMMPlayerApp.h
+++ b/source/RobotAPI/applications/MMMPlayer/MMMPlayerApp.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    RobotAPI::application::MMMPlayer
  * @author     Mirko Waechter ( mirko dot waechter at kit dot edu )
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -27,8 +26,8 @@
 
 #include <RobotAPI/components/MMMPlayer/MMMPlayer.h>
 
-#include <Core/core/application/Application.h>
-#include <Core/core/Component.h>
+#include <ArmarXCore/core/application/Application.h>
+#include <ArmarXCore/core/Component.h>
 
 
 namespace armarx
@@ -48,7 +47,7 @@ namespace armarx
         void setup(const ManagedIceObjectRegistryInterfacePtr& registry,
                    Ice::PropertiesPtr properties)
         {
-            registry->addObject( Component::create<MMMPlayer>(properties) );
+            registry->addObject(Component::create<MMMPlayer>(properties));
         }
     };
 }
diff --git a/source/RobotAPI/applications/MMMPlayer/main.cpp b/source/RobotAPI/applications/MMMPlayer/main.cpp
index 32f1a335c2cb18dc3d88afb9730c784cbb7fe4f2..da1c3893b3192d218bca51df0f5c333cc1dc9f4a 100644
--- a/source/RobotAPI/applications/MMMPlayer/main.cpp
+++ b/source/RobotAPI/applications/MMMPlayer/main.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    RobotAPI::application::MMMPlayer
  * @author     Mirko Waechter ( mirko dot waechter at kit dot edu )
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 #include "MMMPlayerApp.h"
-#include <Core/core/logging/Logging.h>
+#include <ArmarXCore/core/logging/Logging.h>
 
 int main(int argc, char* argv[])
 {
diff --git a/source/RobotAPI/applications/PlatformUnitObserver/PlatformUnitObserverApp.h b/source/RobotAPI/applications/PlatformUnitObserver/PlatformUnitObserverApp.h
index 9196492b1df3e826284c7512692c641e079dc5b3..15eb07fc527af47aef13782b4718483ddae2fb35 100644
--- a/source/RobotAPI/applications/PlatformUnitObserver/PlatformUnitObserverApp.h
+++ b/source/RobotAPI/applications/PlatformUnitObserver/PlatformUnitObserverApp.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    ArmarXCore::applications
  * @author     Manfred Kroehnert (manfred dot kroehnert at kit dot edu)
  * @date       2013
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 
-#include <Core/core/application/Application.h>
+#include <ArmarXCore/core/application/Application.h>
 #include <RobotAPI/components/units/PlatformUnitObserver.h>
 
 namespace armarx
@@ -38,7 +37,7 @@ namespace armarx
          */
         void setup(const ManagedIceObjectRegistryInterfacePtr& registry, Ice::PropertiesPtr properties)
         {
-            registry->addObject( Component::create<PlatformUnitObserver>(properties) );
+            registry->addObject(Component::create<PlatformUnitObserver>(properties));
         }
-	};
+    };
 }
diff --git a/source/RobotAPI/applications/PlatformUnitObserver/main.cpp b/source/RobotAPI/applications/PlatformUnitObserver/main.cpp
index d8c784b40dc36d5d5efc51150230d70d807170ba..a3e52e8ed2ab320c498d3ea43b913f8a1cff66cd 100644
--- a/source/RobotAPI/applications/PlatformUnitObserver/main.cpp
+++ b/source/RobotAPI/applications/PlatformUnitObserver/main.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    Core::application::PlatformUnitObserver
  * @author     Manfred Kroehnert
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 #include "PlatformUnitObserverApp.h"
-#include <Core/core/logging/Logging.h>
+#include <ArmarXCore/core/logging/Logging.h>
 
 int main(int argc, char* argv[])
 {
diff --git a/source/RobotAPI/applications/PlatformUnitSimulation/PlatformUnitSimulationApp.h b/source/RobotAPI/applications/PlatformUnitSimulation/PlatformUnitSimulationApp.h
index cdf0896c3d5e8e71f72e887c23dd327b811d7773..172ca667045152e9005c73198adef48535e7f208 100644
--- a/source/RobotAPI/applications/PlatformUnitSimulation/PlatformUnitSimulationApp.h
+++ b/source/RobotAPI/applications/PlatformUnitSimulation/PlatformUnitSimulationApp.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    ArmarXCore::applications
  * @author     tobias haass
  * @date       2013
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 
-#include <Core/core/application/Application.h>
+#include <ArmarXCore/core/application/Application.h>
 #include <RobotAPI/components/units/PlatformUnitSimulation.h>
 
 namespace armarx
@@ -36,9 +35,9 @@ namespace armarx
         /**
          * @see armarx::Application::setup()
          */
-        void setup(const ManagedIceObjectRegistryInterfacePtr& registry, Ice::PropertiesPtr properties) 
-        { 
-            registry->addObject( Component::create<PlatformUnitSimulation>(properties) );
+        void setup(const ManagedIceObjectRegistryInterfacePtr& registry, Ice::PropertiesPtr properties)
+        {
+            registry->addObject(Component::create<PlatformUnitSimulation>(properties));
         }
     };
 }
diff --git a/source/RobotAPI/applications/PlatformUnitSimulation/main.cpp b/source/RobotAPI/applications/PlatformUnitSimulation/main.cpp
index d0f0d8d799942effde9f5208bcd0d1ca89cbd1ee..3a2ff9ecf98e3565b84926cc8dcf41d5a2d7e7bc 100644
--- a/source/RobotAPI/applications/PlatformUnitSimulation/main.cpp
+++ b/source/RobotAPI/applications/PlatformUnitSimulation/main.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    Core::application::PlatformUnitSimulation
  * @author     Manfred Kroehnert
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 #include "PlatformUnitSimulationApp.h"
-#include <Core/core/logging/Logging.h>
+#include <ArmarXCore/core/logging/Logging.h>
 
 int main(int argc, char* argv[])
 {
diff --git a/source/RobotAPI/applications/RobotControl/RobotControlApp.h b/source/RobotAPI/applications/RobotControl/RobotControlApp.h
index 3d6a7969d538dae9bbdb648a27dbe2e20caf7f78..c290545210136c8014c21e29b50f53f859ffd788 100644
--- a/source/RobotAPI/applications/RobotControl/RobotControlApp.h
+++ b/source/RobotAPI/applications/RobotControl/RobotControlApp.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    ArmarXCore::applications
  * @author     Kai Welke (weöle dot at kit dot edu)
  * @date       2012
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 
-#include <Core/core/application/Application.h>
+#include <ArmarXCore/core/application/Application.h>
 #include <RobotAPI/statecharts/operations/RobotControl.h>
 
 namespace armarx
@@ -31,14 +30,14 @@ namespace armarx
      * Application for testing armarx::RobotControl
      */
     class RobotControlApp :
-		virtual public armarx::Application
-	{
+        virtual public armarx::Application
+    {
         /**
          * @see armarx::Application::setup()
          */
-        void setup(const ManagedIceObjectRegistryInterfacePtr& registry, Ice::PropertiesPtr properties) 
-        { 
-            registry->addObject( Component::create<RobotControl>(properties) ); 
+        void setup(const ManagedIceObjectRegistryInterfacePtr& registry, Ice::PropertiesPtr properties)
+        {
+            registry->addObject(Component::create<RobotControl>(properties));
         }
-	};
+    };
 }
diff --git a/source/RobotAPI/applications/RobotControl/main.cpp b/source/RobotAPI/applications/RobotControl/main.cpp
index b42109ee66362d378a75014a5d4da3802577101c..8ff8a5db87d5049bc35667f2b376a4844e8819e7 100644
--- a/source/RobotAPI/applications/RobotControl/main.cpp
+++ b/source/RobotAPI/applications/RobotControl/main.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    Core::application::RobotControl
  * @author     Manfred Kroehnert
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 #include "RobotControlApp.h"
-#include <Core/core/logging/Logging.h>
+#include <ArmarXCore/core/logging/Logging.h>
 
 int main(int argc, char* argv[])
 {
diff --git a/source/RobotAPI/applications/RobotControlUI/RobotControlUI.cpp b/source/RobotAPI/applications/RobotControlUI/RobotControlUI.cpp
index 7862de8c1e1f915800f9c81443e5e6ae1aa66f5a..1200654b333ff92b2767293d04be750a81770c71 100644
--- a/source/RobotAPI/applications/RobotControlUI/RobotControlUI.cpp
+++ b/source/RobotAPI/applications/RobotControlUI/RobotControlUI.cpp
@@ -2,30 +2,29 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU General Public LIcense as
- * published by the Free Software Foundation; either version 2 of
- * the LIcense, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public LIcense for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
- * You should have received a copy of the GNU General Public LIcense
- * along with this program. If not, see <http://www.gnu.org/lIcenses/>.
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
  *
  * @package    ArmarX::Applications
  * @author     Jan Issac (jan dot issac at gmx dot net)
  * @date       2011
- * @copyright  http://www.gnu.org/lIcenses/gpl-2.0.txt
- *             GNU General Public LIcense
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
  */
 
 #include "RobotControlUI.h"
-#include <Core/core/application/Application.h>
+#include <ArmarXCore/core/application/Application.h>
 
 #include <iostream>
-#include <Core/observers/ObserverObjectFactories.h>
+#include <ArmarXCore/observers/ObserverObjectFactories.h>
 
 using namespace armarx;
 using namespace std;
@@ -52,22 +51,25 @@ void RobotControlUI::run()
 {
     string eventstring;
     cout << "Please insert the event string: " <<  std::flush;
-//    cin >> eventstring;
+    //    cin >> eventstring;
     eventstring = "EvLoadScenario";
-    if(eventstring == "q")
+
+    if (eventstring == "q")
     {
-//        shutdown();
+        //        shutdown();
     }
-    else{
+    else
+    {
         cout << "Please insert the state id of the state that should process the event: " <<  std::flush;
         int id;
-//        cin >> id;
+        //        cin >> id;
         id = 11;
         cout << "sending to id:" << id << endl;
-        EventPtr evt = new Event("EVENTTOALL",eventstring);
+        EventPtr evt = new Event("EVENTTOALL", eventstring);
         StateUtilFunctions::addToDictionary(evt, "proxyName", "RemoteStateOfferer");
         StateUtilFunctions::addToDictionary(evt, "stateName", "MoveArm");
         //robotProxy->issueEvent(id, evt);
     }
-//    cin >> eventstring;
+
+    //    cin >> eventstring;
 }
diff --git a/source/RobotAPI/applications/RobotControlUI/RobotControlUI.h b/source/RobotAPI/applications/RobotControlUI/RobotControlUI.h
index b9d76d5a99575b648bb43edad810a420bf29c236..0fa2a7b12cd6929cedaf3aa886f4e7ab2d4929e8 100644
--- a/source/RobotAPI/applications/RobotControlUI/RobotControlUI.h
+++ b/source/RobotAPI/applications/RobotControlUI/RobotControlUI.h
@@ -2,32 +2,31 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU General Public LIcense as
- * published by the Free Software Foundation; either version 2 of
- * the LIcense, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public LIcense for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
- * You should have received a copy of the GNU General Public LIcense
- * along with this program. If not, see <http://www.gnu.org/lIcenses/>.
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
  *
  * @package    ArmarX::Applications
  * @author     Jan Issac (jan dot issac at gmx dot net)
  * @date       2011
- * @copyright  http://www.gnu.org/lIcenses/gpl-2.0.txt
- *             GNU General Public LIcense
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
  */
 
 #ifndef _ARMARX_SIMPLECOMPONENTTEST_H
 #define _ARMARX_SIMPLECOMPONENTTEST_H
 
 // ArmarXCore
-#include <Core/core/Component.h>
-#include <Core/core/services/tasks/RunningTask.h>
-#include <Core/core/IceManager.h>
+#include <ArmarXCore/core/Component.h>
+#include <ArmarXCore/core/services/tasks/RunningTask.h>
+#include <ArmarXCore/core/IceManager.h>
 #include <RobotAPI/statecharts/operations/RobotControl.h>
 #include <string>
 
@@ -39,7 +38,10 @@ namespace armarx
     public:
         int stateId;
         RobotControlInterfacePrx robotProxy;
-        virtual std::string getDefaultName() const { return "RobotControlUI"; }
+        virtual std::string getDefaultName() const
+        {
+            return "RobotControlUI";
+        }
         virtual void onInitComponent();
         virtual void onConnectComponent();
         virtual void onExitComponent();
diff --git a/source/RobotAPI/applications/RobotControlUI/RobotControlUIApp.h b/source/RobotAPI/applications/RobotControlUI/RobotControlUIApp.h
index 923620f9e4ab35948a4d0ebc5f064cfda444c7cf..0764e757abf269af90a40ec661bbbd0e958256a2 100644
--- a/source/RobotAPI/applications/RobotControlUI/RobotControlUIApp.h
+++ b/source/RobotAPI/applications/RobotControlUI/RobotControlUIApp.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    ArmarXCore::applications
  * @author     Kai Welke (weöle dot at kit dot edu)
  * @date       2012
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 
-#include <Core/core/application/Application.h>
+#include <ArmarXCore/core/application/Application.h>
 #include "RobotControlUI.h"
 
 namespace armarx
@@ -38,7 +37,7 @@ namespace armarx
          */
         void setup(const ManagedIceObjectRegistryInterfacePtr& registry, Ice::PropertiesPtr properties)
         {
-            registry->addObject( Component::create<RobotControlUI>(properties) );
+            registry->addObject(Component::create<RobotControlUI>(properties));
         }
     };
 }
diff --git a/source/RobotAPI/applications/RobotControlUI/main.cpp b/source/RobotAPI/applications/RobotControlUI/main.cpp
index 69a727b32d7c36e304ed6ed72e9ba04b5cb07671..dca188e23dd8c529da34f498356ee8098a09cc3c 100644
--- a/source/RobotAPI/applications/RobotControlUI/main.cpp
+++ b/source/RobotAPI/applications/RobotControlUI/main.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    Core::application::RobotControlUI
  * @author     Manfred Kroehnert
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 #include "RobotControlUIApp.h"
-#include <Core/core/logging/Logging.h>
+#include <ArmarXCore/core/logging/Logging.h>
 
 int main(int argc, char* argv[])
 {
diff --git a/source/RobotAPI/applications/RobotStateComponent/RobotStateComponentApp.h b/source/RobotAPI/applications/RobotStateComponent/RobotStateComponentApp.h
index 38fc1f7ee884be47ce111f437c93c99f9110a34d..065d5f07715699b1c499b567338f80271207dede 100644
--- a/source/RobotAPI/applications/RobotStateComponent/RobotStateComponentApp.h
+++ b/source/RobotAPI/applications/RobotStateComponent/RobotStateComponentApp.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,13 +16,13 @@
 * @package    RobotStateComponent::
 * @author     ( at kit dot edu)
 * @date
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
 
 
-#include <Core/core/application/Application.h>
+#include <ArmarXCore/core/application/Application.h>
 #include <RobotAPI/components/RobotState/RobotStateComponent.h>
 
 namespace armarx
@@ -37,13 +36,13 @@ namespace armarx
         /**
          * @see armarx::Application::setup()
          */
-        void setup(const ManagedIceObjectRegistryInterfacePtr& registry, Ice::PropertiesPtr properties) 
-        { 
+        void setup(const ManagedIceObjectRegistryInterfacePtr& registry, Ice::PropertiesPtr properties)
+        {
             auto state = Component::create<RobotStateComponent>(properties);
             auto observer = Component::create<RobotStateObserver>(properties);
             state->setRobotStateObserver(observer);
-            registry->addObject( state );
-            registry->addObject( observer );
+            registry->addObject(state);
+            registry->addObject(observer);
         }
     };
 }
diff --git a/source/RobotAPI/applications/RobotStateComponent/main.cpp b/source/RobotAPI/applications/RobotStateComponent/main.cpp
index 0b602b6260fc3ddd8116c45c2e168bc13b5151a3..2966ad88097e52a83f9b0b48d78371857e9963b0 100644
--- a/source/RobotAPI/applications/RobotStateComponent/main.cpp
+++ b/source/RobotAPI/applications/RobotStateComponent/main.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    Core::application::RobotStateComponent
  * @author     Manfred Kroehnert
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 #include "RobotStateComponentApp.h"
-#include <Core/core/logging/Logging.h>
+#include <ArmarXCore/core/logging/Logging.h>
 
 int main(int argc, char* argv[])
 {
diff --git a/source/RobotAPI/applications/RobotStateObserver/RobotStateObserverApp.h b/source/RobotAPI/applications/RobotStateObserver/RobotStateObserverApp.h
index 8242165300590cf49e412e3781e3da1ce801f119..f0b6ca4cba6e32a7c03903827e5b3bbafd24cdcc 100644
--- a/source/RobotAPI/applications/RobotStateObserver/RobotStateObserverApp.h
+++ b/source/RobotAPI/applications/RobotStateObserver/RobotStateObserverApp.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    ArmarXCore::applications
  * @author     Kai Welke (welke dot at kit dot edu)
  * @date       2012
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 
-#include <Core/core/application/Application.h>
+#include <ArmarXCore/core/application/Application.h>
 #include <RobotAPI/libraries/core/remoterobot/RobotStateObserver.h>
 
 namespace armarx
@@ -30,15 +29,15 @@ namespace armarx
     /**
      * Application for testing armarx::RobotStateObserver
      */
-	class RobotStateObserverApp :
-		virtual public armarx::Application
-	{
+    class RobotStateObserverApp :
+        virtual public armarx::Application
+    {
         /**
          * @see armarx::Application::setup()
          */
-        void setup(const ManagedIceObjectRegistryInterfacePtr& registry, Ice::PropertiesPtr properties) 
-        { 
-            registry->addObject( Component::create<RobotStateObserver>(properties) ); 
+        void setup(const ManagedIceObjectRegistryInterfacePtr& registry, Ice::PropertiesPtr properties)
+        {
+            registry->addObject(Component::create<RobotStateObserver>(properties));
         }
-	};
+    };
 }
diff --git a/source/RobotAPI/applications/RobotStateObserver/main.cpp b/source/RobotAPI/applications/RobotStateObserver/main.cpp
index 30ecac9a8f70d004c44097c49ab5e7c5d640658d..c57020dfa7cd60c3132118a1bf67052beb278d3f 100644
--- a/source/RobotAPI/applications/RobotStateObserver/main.cpp
+++ b/source/RobotAPI/applications/RobotStateObserver/main.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    Core::application::RobotStateObserver
  * @author     Manfred Kroehnert
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 #include "RobotStateObserverApp.h"
-#include <Core/core/logging/Logging.h>
+#include <ArmarXCore/core/logging/Logging.h>
 
 int main(int argc, char* argv[])
 {
diff --git a/source/RobotAPI/applications/TCPControlUnit/TCPControlUnitApp.h b/source/RobotAPI/applications/TCPControlUnit/TCPControlUnitApp.h
index 805a724b757da2de0c0ca47a3b84bf5bc1cd2e61..5a395d6fd4aae92dd4ec535d91e2539f4d119571 100644
--- a/source/RobotAPI/applications/TCPControlUnit/TCPControlUnitApp.h
+++ b/source/RobotAPI/applications/TCPControlUnit/TCPControlUnitApp.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,24 +16,24 @@
  * @package    ArmarXCore::applications
  * @author     Kai Welke (weöle dot at kit dot edu)
  * @date       2012
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 
-#include <Core/core/application/Application.h>
+#include <ArmarXCore/core/application/Application.h>
 #include <RobotAPI/components/units/TCPControlUnit.h>
 #include <RobotAPI/components/units/TCPControlUnitObserver.h>
 
 namespace armarx
 {
     class TCPControlUnitApp :
-		virtual public armarx::Application
-	{
+        virtual public armarx::Application
+    {
         void setup(const ManagedIceObjectRegistryInterfacePtr& registry, Ice::PropertiesPtr properties)
         {
-            registry->addObject( Component::create<TCPControlUnit>(properties) );
-            registry->addObject( Component::create<TCPControlUnitObserver>(properties) );
+            registry->addObject(Component::create<TCPControlUnit>(properties));
+            registry->addObject(Component::create<TCPControlUnitObserver>(properties));
         }
     };
 }
diff --git a/source/RobotAPI/applications/TCPControlUnit/main.cpp b/source/RobotAPI/applications/TCPControlUnit/main.cpp
index ca23f217c9b253ded6218ca10954c78e8f2c0edb..941b7017ba23ae1ed5a7dfe963ded261ccffd019 100644
--- a/source/RobotAPI/applications/TCPControlUnit/main.cpp
+++ b/source/RobotAPI/applications/TCPControlUnit/main.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    RobotAPI::application::TCPControlUnit
  * @author     Manfred Kroehnert
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 #include "TCPControlUnitApp.h"
-#include <Core/core/logging/Logging.h>
+#include <ArmarXCore/core/logging/Logging.h>
 
 int main(int argc, char* argv[])
 {
diff --git a/source/RobotAPI/applications/WeissHapticUnit/WeissHapticUnitApp.h b/source/RobotAPI/applications/WeissHapticUnit/WeissHapticUnitApp.h
index 4466a3b0e17882e97de29656ef6618e29e713425..9b2cb9e06b8029b90c2277e2bed3ff09d97eb63b 100644
--- a/source/RobotAPI/applications/WeissHapticUnit/WeissHapticUnitApp.h
+++ b/source/RobotAPI/applications/WeissHapticUnit/WeissHapticUnitApp.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,14 +16,14 @@
  * @package    RobotAPI::application::WeissHapticUnit
  * @author     Simon Ottenhaus ( simon dot ottenhaus at kit dot edu )
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 #ifndef _ARMARX_APPLICATION_RobotAPI_WeissHapticUnit_H
 #define _ARMARX_APPLICATION_RobotAPI_WeissHapticUnit_H
 
-#include <Core/core/application/Application.h>
+#include <ArmarXCore/core/application/Application.h>
 #include <RobotAPI/components/units/HapticObserver.h>
 #include <RobotAPI/libraries/drivers/WeissHapticSensor/WeissHapticUnit.h>
 
@@ -45,8 +44,8 @@ namespace armarx
         void setup(const ManagedIceObjectRegistryInterfacePtr& registry,
                    Ice::PropertiesPtr properties)
         {
-            registry->addObject( Component::create<WeissHapticUnit>(properties) );
-            registry->addObject( Component::create<HapticObserver>(properties) );
+            registry->addObject(Component::create<WeissHapticUnit>(properties));
+            registry->addObject(Component::create<HapticObserver>(properties));
         }
     };
 }
diff --git a/source/RobotAPI/applications/WeissHapticUnit/main.cpp b/source/RobotAPI/applications/WeissHapticUnit/main.cpp
index 488f764ec81279f8a74391c1f34f3ccf02ac0f7b..e627759fca862ba748105456b459d6e8da9e7d69 100644
--- a/source/RobotAPI/applications/WeissHapticUnit/main.cpp
+++ b/source/RobotAPI/applications/WeissHapticUnit/main.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    RobotAPI::application::WeissHapticUnit
  * @author     Simon Ottenhaus ( simon dot ottenhaus at kit dot edu )
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 #include "WeissHapticUnitApp.h"
-#include <Core/core/logging/Logging.h>
+#include <ArmarXCore/core/logging/Logging.h>
 
 int main(int argc, char* argv[])
 {
diff --git a/source/RobotAPI/applications/XsensIMU/CMakeLists.txt b/source/RobotAPI/applications/XsensIMU/CMakeLists.txt
index 73778cdf5323c15503526ab8e9461e503dd2e3e4..68a3af2b1c42625496dba90e2fc18eea9acd1f6d 100644
--- a/source/RobotAPI/applications/XsensIMU/CMakeLists.txt
+++ b/source/RobotAPI/applications/XsensIMU/CMakeLists.txt
@@ -9,7 +9,7 @@ armarx_component_set_name("XsensIMUApp")
 #    include_directories(${MyLib_INCLUDE_DIRS})
 #endif()
 
-set(COMPONENT_LIBS ArmarXInterfaces ArmarXCore XsensIMU)
+set(COMPONENT_LIBS ArmarXCoreInterfaces ArmarXCore XsensIMU)
 
 set(EXE_SOURCE XsensIMUApp.h main.cpp)
 
diff --git a/source/RobotAPI/applications/XsensIMU/XsensIMUApp.h b/source/RobotAPI/applications/XsensIMU/XsensIMUApp.h
index 92c9f0be0193fb1d8a30794a43443b229c332547..6fcd5818e014d6d66b0eeb373f30f577bced7e32 100644
--- a/source/RobotAPI/applications/XsensIMU/XsensIMUApp.h
+++ b/source/RobotAPI/applications/XsensIMU/XsensIMUApp.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    RobotAPI::application::XsensIMU
  * @author     Markus Grotz ( markus-grotz at web dot de )
  * @date       2015
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -27,8 +26,8 @@
 
 #include <RobotAPI/libraries/drivers/XsensIMU/XsensIMU.h>
 
-#include <Core/core/application/Application.h>
-#include <Core/core/Component.h>
+#include <ArmarXCore/core/application/Application.h>
+#include <ArmarXCore/core/Component.h>
 
 
 namespace armarx
@@ -48,7 +47,7 @@ namespace armarx
         void setup(const ManagedIceObjectRegistryInterfacePtr& registry,
                    Ice::PropertiesPtr properties)
         {
-            registry->addObject( Component::create<XsensIMU>(properties) );
+            registry->addObject(Component::create<XsensIMU>(properties));
         }
     };
 }
diff --git a/source/RobotAPI/applications/XsensIMU/main.cpp b/source/RobotAPI/applications/XsensIMU/main.cpp
index e58d9dd795abaf00f1e9eb2d7af93c47c413f6cf..d1a482c9f534cb79d5ecc7022b7cb6502c3794ff 100644
--- a/source/RobotAPI/applications/XsensIMU/main.cpp
+++ b/source/RobotAPI/applications/XsensIMU/main.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    RobotAPI::application::XsensIMU
  * @author     Markus Grotz ( markus-grotz at web dot de )
  * @date       2015
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 #include "XsensIMUApp.h"
-#include <Core/core/logging/Logging.h>
+#include <ArmarXCore/core/logging/Logging.h>
 
 int main(int argc, char* argv[])
 {
diff --git a/source/RobotAPI/applications/deprecated/MotionControl/CMakeLists.txt b/source/RobotAPI/applications/deprecated/MotionControl/CMakeLists.txt
index c8099e969b735a7dc2cfa1571e8b0dc139dc1e9c..711bc726927394a249a20ac8ecb4583b01433c64 100644
--- a/source/RobotAPI/applications/deprecated/MotionControl/CMakeLists.txt
+++ b/source/RobotAPI/applications/deprecated/MotionControl/CMakeLists.txt
@@ -8,7 +8,7 @@ find_package(Simox QUIET)
 armarx_build_if(Simox_FOUND "Simox-VirtualRobot not available")
 
 
-set(COMPONENT_LIBS MotionControl RobotAPICore ArmarXInterfaces ArmarXCore ArmarXCoreObservers RobotAPIRobotStateComponent ArmarXCoreStatechart RobotAPIOperations)
+set(COMPONENT_LIBS MotionControl RobotAPICore ArmarXCoreInterfaces ArmarXCore ArmarXCoreObservers RobotAPIRobotStateComponent ArmarXCoreStatechart RobotAPIOperations)
 
 set(SOURCES main.cpp MotionControlApp.h)
 
diff --git a/source/RobotAPI/applications/deprecated/MotionControl/MotionControlApp.h b/source/RobotAPI/applications/deprecated/MotionControl/MotionControlApp.h
index 5a1250ca065155c1e788b0a61207acf32d549628..54c2d4765c771bac03741ed4e388da9c52c7ac3a 100644
--- a/source/RobotAPI/applications/deprecated/MotionControl/MotionControlApp.h
+++ b/source/RobotAPI/applications/deprecated/MotionControl/MotionControlApp.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,22 +16,22 @@
  * @package    ArmarXCore::applications
  * @author     Kai Welke (weöle dot at kit dot edu)
  * @date       2012
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 
-#include <Core/core/application/Application.h>
+#include <ArmarXCore/core/application/Application.h>
 #include <RobotAPI/statecharts/motioncontrol/MotionControl.h>
 
 namespace armarx
 {
     class MotionControlApp :
-		virtual public armarx::Application
-	{
+        virtual public armarx::Application
+    {
         void setup(const ManagedIceObjectRegistryInterfacePtr& registry, Ice::PropertiesPtr properties)
         {
-            registry->addObject( Component::create<MotionControl::MotionControlOfferer>(properties) );
+            registry->addObject(Component::create<MotionControl::MotionControlOfferer>(properties));
         }
     };
 }
diff --git a/source/RobotAPI/applications/deprecated/MotionControl/main.cpp b/source/RobotAPI/applications/deprecated/MotionControl/main.cpp
index b12d363adb53ba4b5c4e4eb835e7e93f49d35e13..221c3c39cae5ebd4ba14fdca409ea3a4a31282e9 100644
--- a/source/RobotAPI/applications/deprecated/MotionControl/main.cpp
+++ b/source/RobotAPI/applications/deprecated/MotionControl/main.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    RobotAPI::application::MotionControl
  * @author     Manfred Kroehnert
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 #include "MotionControlApp.h"
-#include <Core/core/logging/Logging.h>
+#include <ArmarXCore/core/logging/Logging.h>
 
 int main(int argc, char* argv[])
 {
diff --git a/source/RobotAPI/applications/deprecated/MotionControlTest/MotionControlTestApp.h b/source/RobotAPI/applications/deprecated/MotionControlTest/MotionControlTestApp.h
index af86e3541435a37fc39ca3d5d192cc0784eb7ae8..cf04af28420ce90829a0fbfba227cb73d6dca2d8 100644
--- a/source/RobotAPI/applications/deprecated/MotionControlTest/MotionControlTestApp.h
+++ b/source/RobotAPI/applications/deprecated/MotionControlTest/MotionControlTestApp.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    ArmarXCore::applications
  * @author     Kai Welke (weöle dot at kit dot edu)
  * @date       2012
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 
-#include <Core/core/application/Application.h>
+#include <ArmarXCore/core/application/Application.h>
 #include <RobotAPI/statecharts/motioncontrol/MotionControl.h>
 
 namespace armarx
@@ -32,7 +31,7 @@ namespace armarx
     {
         void setup(const ManagedIceObjectRegistryInterfacePtr& registry, Ice::PropertiesPtr properties)
         {
-            registry->addObject( Component::create<MotionControl::MotionControlOfferer>(properties) );
+            registry->addObject(Component::create<MotionControl::MotionControlOfferer>(properties));
         }
     };
 }
diff --git a/source/RobotAPI/applications/deprecated/MotionControlTest/main.cpp b/source/RobotAPI/applications/deprecated/MotionControlTest/main.cpp
index dd6c501553c97e8f7c8e41d6655dc79fcaed61cf..d6c5b5587217d77cf4d09da44e924780a5b7dddf 100644
--- a/source/RobotAPI/applications/deprecated/MotionControlTest/main.cpp
+++ b/source/RobotAPI/applications/deprecated/MotionControlTest/main.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    RobotAPI::application::MotionControlTest
  * @author     Manfred Kroehnert
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 #include "MotionControlTestApp.h"
-#include <Core/core/logging/Logging.h>
+#include <ArmarXCore/core/logging/Logging.h>
 
 int main(int argc, char* argv[])
 {
diff --git a/source/RobotAPI/applications/RobotIK/CMakeLists.txt b/source/RobotAPI/applications/moved_to_robotcomponents_RobotIK/CMakeLists.txt
similarity index 100%
rename from source/RobotAPI/applications/RobotIK/CMakeLists.txt
rename to source/RobotAPI/applications/moved_to_robotcomponents_RobotIK/CMakeLists.txt
diff --git a/source/RobotAPI/applications/RobotIK/RobotIKApp.h b/source/RobotAPI/applications/moved_to_robotcomponents_RobotIK/RobotIKApp.h
similarity index 65%
rename from source/RobotAPI/applications/RobotIK/RobotIKApp.h
rename to source/RobotAPI/applications/moved_to_robotcomponents_RobotIK/RobotIKApp.h
index 2bfb0051e3a97bba0507cfb6fb2ae501d9caa600..958331f3ee99014fb9ce027a1895fe0e248959b4 100644
--- a/source/RobotAPI/applications/RobotIK/RobotIKApp.h
+++ b/source/RobotAPI/applications/moved_to_robotcomponents_RobotIK/RobotIKApp.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,13 +16,13 @@
 * @package    RobotAPI::RobotIK
 * @author     ( joshua dot haustein at gmail dot com)
 * @date       2015
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
 
 
-#include <Core/core/application/Application.h>
+#include <ArmarXCore/core/application/Application.h>
 #include <RobotAPI/components/RobotIK/RobotIK.h>
 
 namespace armarx
@@ -37,10 +36,10 @@ namespace armarx
         /**
          * @see armarx::Application::setup()
          */
-        void setup(const ManagedIceObjectRegistryInterfacePtr& registry, Ice::PropertiesPtr properties) 
-        { 
+        void setup(const ManagedIceObjectRegistryInterfacePtr& registry, Ice::PropertiesPtr properties)
+        {
             auto iksolver = Component::create<RobotIK>(properties);
-            registry->addObject( iksolver );
+            registry->addObject(iksolver);
         }
     };
 }
diff --git a/source/RobotAPI/applications/RobotIK/main.cpp b/source/RobotAPI/applications/moved_to_robotcomponents_RobotIK/main.cpp
similarity index 65%
rename from source/RobotAPI/applications/RobotIK/main.cpp
rename to source/RobotAPI/applications/moved_to_robotcomponents_RobotIK/main.cpp
index 2ba1087bf6c34afcd3be2ec186988d79535e8e61..18b3ad25f9a17f19a237e9479266a65aaceaa846 100644
--- a/source/RobotAPI/applications/RobotIK/main.cpp
+++ b/source/RobotAPI/applications/moved_to_robotcomponents_RobotIK/main.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,12 +16,12 @@
  * @package    RobotAPI::applications::RobotIK
  * @author     Joshua Haustein
  * @date       2015
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 #include "RobotIKApp.h"
-#include <Core/core/logging/Logging.h>
+#include <ArmarXCore/core/logging/Logging.h>
 
 int main(int argc, char* argv[])
 {
diff --git a/source/RobotAPI/components/CMakeLists.txt b/source/RobotAPI/components/CMakeLists.txt
index 06399d58c2f161451dce1dd0afd99eec0af31a71..fb09cfb0a45c54b1fd2f503b76a857ccd73a87e4 100644
--- a/source/RobotAPI/components/CMakeLists.txt
+++ b/source/RobotAPI/components/CMakeLists.txt
@@ -1,7 +1,5 @@
 
 add_subdirectory(units)
 add_subdirectory(DebugDrawer)
-add_subdirectory(MMMPlayer)
 add_subdirectory(RobotState)
-add_subdirectory(RobotIK)
 
diff --git a/source/RobotAPI/components/MMMPlayer/CMakeLists.txt b/source/RobotAPI/components/MMMPlayer/CMakeLists.txt
deleted file mode 100644
index 84a9104738bd6d1ba2fc58ff3d82f7f290fb722c..0000000000000000000000000000000000000000
--- a/source/RobotAPI/components/MMMPlayer/CMakeLists.txt
+++ /dev/null
@@ -1,35 +0,0 @@
-armarx_component_set_name("MMMPlayer")
-
-find_package(MMMCore QUIET)
-armarx_build_if(MMMCore_FOUND "MMMCORE not available")
-if(MMMCore_FOUND)
-    include_directories(${MMMCORE_INCLUDE_DIRS})
-endif()
-
-find_package(Eigen3 QUIET)
-find_package(Simox ${ArmarX_Simox_VERSION} QUIET)
-
-armarx_build_if(Eigen3_FOUND "Eigen3 not available")
-armarx_build_if(Simox_FOUND "Simox-VirtualRobot not available")
-
-if (Eigen3_FOUND AND Simox_FOUND)
-    include_directories(
-        ${Eigen3_INCLUDE_DIR}
-        ${Simox_INCLUDE_DIRS})
-endif()
-
-set(COMPONENT_LIBS RobotAPIInterfaces RobotAPICore ArmarXInterfaces ArmarXCore ArmarXCoreObservers ${MMMCORE_LIBRARIES})
-
-set(SOURCES
-./MMMPlayer.cpp
-#@TEMPLATE_LINE@@COMPONENT_PATH@/@COMPONENT_NAME@.cpp
-)
-set(HEADERS
-./MMMPlayer.h
-#@TEMPLATE_LINE@@COMPONENT_PATH@/@COMPONENT_NAME@.h
-)
-
-armarx_add_component("${SOURCES}" "${HEADERS}")
-
-# add unit tests
-add_subdirectory(test)
diff --git a/source/RobotAPI/components/MMMPlayer/MMMPlayer.cpp b/source/RobotAPI/components/MMMPlayer/MMMPlayer.cpp
deleted file mode 100644
index 96170872e1b0eed8f09fd2db1f9891e93ea7bf88..0000000000000000000000000000000000000000
--- a/source/RobotAPI/components/MMMPlayer/MMMPlayer.cpp
+++ /dev/null
@@ -1,259 +0,0 @@
-/*
- * This file is part of ArmarX.
- *
- * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
- *
- * ArmarX is distributed in the hope that it will be useful, but
- * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with this program. If not, see <http://www.gnu.org/licenses/>.
- *
- * @package    RobotAPI::ArmarXObjects::MMMPlayer
- * @author     Mirko Waechter ( mirko dot waechter at kit dot edu )
- * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
- *             GNU General Public License
- */
-
-#include "MMMPlayer.h"
-#include <MMM/Motion/MotionReaderXML.h>
-
-#include <Core/core/exceptions/local/ExpressionException.h>
-
-#include <Core/core/system/ArmarXDataPath.h>
-
-#include <Core/observers/variant/Variant.h>
-#include <Core/interface/observers/VariantBase.h>
-
-
-using namespace armarx;
-using namespace MMM;
-
-
-void MMMPlayer::onInitComponent()
-{
-    usingProxy(getProperty<std::string>("KinematicUnitName").getValue());
-    usingProxy("DebugObserver");
-
-    motionFPS = 1;
-    desiredFPS = 1;
-    usePIDController = getProperty<bool>("UsePIDController").getValue();
-    if(usePIDController)
-        usingTopic(getProperty<std::string>("RobotNodeSetName").getValue());
-}
-
-
-void MMMPlayer::onConnectComponent()
-{
-    {
-        ScopedLock lock(playerMutex);
-        currentFrame = 0;
-        MotionReaderXML reader;
-        auto motionPath = getProperty<std::string>("MMMFile").getValue();
-        ArmarXDataPath::getAbsolutePath(motionPath, motionPath);
-        motion = reader.loadMotion(motionPath);
-        if(!motion)
-        {
-            terminate();
-            return;
-        }
-        jointNames = motion->getJointNames();
-        if(motion->getNumFrames() > 1)
-        {
-            float frameDuration = motion->getMotionFrame(1)->timestep - motion->getMotionFrame(0)->timestep;
-            ARMARX_CHECK_EXPRESSION(frameDuration != 0);
-            ARMARX_CHECK_EXPRESSION(frameDuration > 0)
-                    motionFPS = 1.0f/frameDuration;
-            ARMARX_VERBOSE << VAROUT(motionFPS);
-        }
-
-        kin = getProxy<KinematicUnitInterfacePrx>(getProperty<std::string>("KinematicUnitName").getValue());
-        debugObserver = getProxy<DebugObserverInterfacePrx>("DebugObserver");
-        desiredFPS = getProperty<float>("FPS").getValue();
-
-        start = 0.3;
-        end = 1.26;
-        direction = 1;
-
-        jointOffets["Right Arm Shoulder2"] = 20.0/180.0*M_PI;
-        jointOffets["Left Arm Shoulder2"] = 20.0/180.0*M_PI;
-
-        NameControlModeMap modes;
-        for (size_t i = 0; i < jointNames.size(); ++i) {
-            const auto& jointName = jointNames.at(i);
-            if(usePIDController)
-            {
-                modes[jointName] = eVelocityControl;
-            }
-            else
-            {
-                modes[jointName] = ePositionControl;
-            }
-        }
-        kin->switchControlMode(modes);
-    }
-
-    maxVel = getProperty<float>("absMaximumVelocity").getValue();
-    task = new PeriodicTask<MMMPlayer>(this, &MMMPlayer::run, 10, false, "MMMPlayerTask");
-    motionStartTime = IceUtil::Time::now();
-    task->start();
-}
-
-
-void MMMPlayer::run()
-{
-    ScopedLock lock(playerMutex);
-    NameValueMap targetVelocities;
-
-
-
-    currentMotionTime = (IceUtil::Time::now() - motionStartTime).toSecondsDouble() * 100 * desiredFPS / motionFPS;
-    if(direction>0)
-        currentFrame = currentMotionTime;
-    else
-        currentFrame = motion->getNumFrames() - (int)currentMotionTime;
-    if(currentFrame >= (int)motion->getNumFrames() || currentFrame < 0)
-    {
-        if(getProperty<bool>("LoopPlayback").getValue())
-        {
-            direction *= -1;
-            motionStartTime = IceUtil::Time::now();
-            return;
-        }
-        else if(task)
-        {
-            return;
-        }
-    }
-    double interpolationValue = currentMotionTime - (int)currentMotionTime;
-    auto frame = motion->getMotionFrame(currentFrame);
-    MMM::MotionFramePtr nextFrame;
-    if(currentFrame +1 < (int)motion->getNumFrames())
-        nextFrame = motion->getMotionFrame(currentFrame+1);
-    targetPositionValues.clear();
-    ARMARX_INFO << deactivateSpam(1) << "frame: " << currentFrame << " " << VAROUT(interpolationValue);
-    StringVariantBaseMap debugTargetValues;
-    ARMARX_CHECK_EXPRESSION((int)jointNames.size() == frame->joint.rows());
-    for (size_t i = 0; i < jointNames.size(); ++i) {
-        const auto& jointName = jointNames.at(i);
-        auto& targetPosValue = targetPositionValues[jointName] = frame->joint[i];
-        if(nextFrame)
-            targetPosValue += interpolationValue * (nextFrame->joint[i] - frame->joint[i]);
-        auto it = jointOffets.find(jointName);
-        if(it != jointOffets.end())
-            targetPosValue += it->second;
-        assert(targetPosValue == targetPositionValues[jointName]);
-        debugTargetValues[jointName] = new Variant(targetPosValue);
-        float& targetVel = targetVelocities[jointName] =  0.0;
-        auto vel = frame->joint_vel[i];
-        if(vel != 0.0f)
-        {
-            targetVel = vel;
-        }
-        else if(nextFrame)
-        {
-            if(nextFrame->timestep - frame->timestep == 0)
-                ARMARX_INFO << deactivateSpam() << "timestep delta is zero at frame " << currentFrame << " - cannot calculate velocity";
-            targetVel = targetVelocities[jointName] = (nextFrame->joint[i] - frame->joint[i]) / (nextFrame->timestep - frame->timestep);
-
-
-        }
-
-
-        MMM::MotionFramePtr nextNextFrame;
-        if(currentFrame + 2 < (int)motion->getNumFrames())
-            nextNextFrame = motion->getMotionFrame(currentFrame+2);
-        if(nextNextFrame)
-        {
-            float nextTargetVel = (nextNextFrame->joint[i] - nextFrame->joint[i]) / (nextNextFrame->timestep - nextFrame->timestep);
-            targetVel += interpolationValue * (nextTargetVel - targetVel);
-        }
-        targetVel *= desiredFPS/motionFPS*direction;
-
-
-//        targetVelocities[jointName] =  0.0;
-        auto pid = PIDs.find(jointName);
-        if(usePIDController && pid != PIDs.end())
-        {
-            auto cv = pid->second->getControlValue();
-            targetVel += cv;
-            if(cv > 20)
-                ARMARX_INFO << "" << (jointName) << ": v:" << (targetVel) << " pos: " << targetPosValue;
-
-//            debugObserver->setDebugDatafield(jointName, "p", new Variant(pid->second->previousError * pid->second->Kp));
-//            debugObserver->setDebugDatafield(jointName, "i", new Variant(pid->second->integral* pid->second->Ki));
-//            debugObserver->setDebugDatafield(jointName, "d", new Variant(pid->second->derivative * pid->second->Kd));
-//            debugObserver->setDebugDatafield(jointName, "velocity", new Variant(targetVelocities[jointName]));
-        }
-        targetVel  = std::min<double>(maxVel/180.0*M_PI,targetVel);
-        targetVel  = std::max<double>(-1 * maxVel/180.0*M_PI,targetVel);
-    }
-//    ARMARX_INFO << "target: " << targetPositionValues ;
-    std::stringstream out;
-    for(auto v : debugTargetValues)
-        out << v.first << ": " << v.second->getFloat() << " " << targetPositionValues[v.first] << "\n" ;
-//    ARMARX_INFO << "debugtarget: " << out.str() ;
-    debugObserver->setDebugChannel("targetJointAngles", debugTargetValues);
-    kin->setJointVelocities(targetVelocities);
-    if(!usePIDController)
-        kin->setJointAngles(targetPositionValues);
-    ARMARX_VERBOSE << deactivateSpam(3) << "Playing frame " << currentFrame;
-//    currentFrame+=direction;
-}
-
-void MMMPlayer::reportJointAngles(const NameValueMap &angles, bool, const Ice::Current &)
-{
-    ScopedLock lock(playerMutex);
-    std::stringstream out;
-    for(auto v : angles)
-        out << v.first << ": " << v.second << " " << targetPositionValues[v.first] << "\n" ;
-//    ARMARX_INFO  << deactivateSpam(0.5) << "jointangles reported: " << out.str();
-    if(!usePIDController)
-    {
-        ARMARX_INFO << deactivateSpam() << "jointangles reporting DISABLED";
-        return;
-
-    }
-
-    for(const auto &joint: angles)
-    {
-
-        const std::string& name = joint.first;
-        auto it = PIDs.find(name);
-        if(it == PIDs.end())
-        {
-            PIDs[name] = PIDControllerPtr(new PIDController(getProperty<float>("Kp").getValue(),
-                                                                   getProperty<float>("Ki").getValue(),
-                                                                   getProperty<float>("Kd").getValue()));
-            it = PIDs.find(name);
-        }
-        ARMARX_INFO  << deactivateSpam() << name;
-        PIDControllerPtr pid = it->second;
-        pid->update(joint.second, targetPositionValues[name]);
-    }
-}
-
-void MMMPlayer::onDisconnectComponent()
-{
-    if(task)
-        task->stop();
-    kin->stop();
-}
-
-
-void MMMPlayer::onExitComponent()
-{
-
-}
-
-PropertyDefinitionsPtr MMMPlayer::createPropertyDefinitions()
-{
-    return PropertyDefinitionsPtr(new MMMPlayerPropertyDefinitions(
-                                      getConfigIdentifier()));
-}
diff --git a/source/RobotAPI/components/MMMPlayer/MMMPlayer.h b/source/RobotAPI/components/MMMPlayer/MMMPlayer.h
deleted file mode 100644
index 6a31c2d37601497d70547105ffee48827d167be4..0000000000000000000000000000000000000000
--- a/source/RobotAPI/components/MMMPlayer/MMMPlayer.h
+++ /dev/null
@@ -1,164 +0,0 @@
-/*
- * This file is part of ArmarX.
- *
- * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
- *
- * ArmarX is distributed in the hope that it will be useful, but
- * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with this program. If not, see <http://www.gnu.org/licenses/>.
- *
- * @package    RobotAPI::ArmarXObjects::MMMPlayer
- * @author     Mirko Waechter ( mirko dot waechter at kit dot edu )
- * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
- *             GNU General Public License
- */
-
-#ifndef _ARMARX_COMPONENT_RobotAPI_MMMPlayer_H
-#define _ARMARX_COMPONENT_RobotAPI_MMMPlayer_H
-
-#include <MMM/Motion/Motion.h>
-
-
-
-#include <Core/core/Component.h>
-
-#include <RobotAPI/interface/units/KinematicUnitInterface.h>
-
-#include <Core/core/services/tasks/PeriodicTask.h>
-#include <RobotAPI/libraries/core/PIDController.h>
-
-#include <Core/interface/observers/ObserverInterface.h>
-
-namespace armarx
-{
-    /**
-     * \class MMMPlayerPropertyDefinitions
-     * \brief
-     */
-    class MMMPlayerPropertyDefinitions:
-        public ComponentPropertyDefinitions
-    {
-    public:
-        MMMPlayerPropertyDefinitions(std::string prefix):
-            ComponentPropertyDefinitions(prefix)
-        {
-            defineRequiredProperty<std::string>("MMMFile", "Path to MMM XML File");
-            defineRequiredProperty<std::string>("KinematicUnitName", "Name of the KinematicUnit to which the joint values should be sent");
-            defineRequiredProperty<std::string>("KinematicTopicName", "Name of the KinematicUnit reporting topic");
-            defineOptionalProperty<float>("FPS", 100.0f, "FPS with which the recording should be executed. Velocities will be adapted.");
-            defineOptionalProperty<bool>("LoopPlayback", true, "Specify whether should be repeated after execution")
-                    .setCaseInsensitive(true)
-                    .map("true",    true)
-                    .map("yes",     true)
-                    .map("1",       true)
-                    .map("false",   false)
-                    .map("no",      false)
-                    .map("0",       false);
-            defineOptionalProperty<bool>("UsePIDController", true, "Specify whether the PID Controller should be used")
-                    .setCaseInsensitive(true)
-                    .map("true",    true)
-                    .map("yes",     true)
-                    .map("1",       true)
-                    .map("false",   false)
-                    .map("no",      false)
-                    .map("0",       false);
-            defineOptionalProperty<float>("Kp", 1.f, "Proportional gain value of PID Controller");
-            defineOptionalProperty<float>("Ki", 0.00001f, "Integral gain value of PID Controller");
-            defineOptionalProperty<float>("Kd", 1.0f, "Differential gain value of PID Controller");
-            defineOptionalProperty<float>("absMaximumVelocity", 120.0f, "The PID will never set a velocity above this threshold in degree");
-            defineOptionalProperty<std::string>("RobotNodeSetName", "RobotState", "The name of the robot node set to be used (only need for PIDController mode)");
-
-        }
-    };
-
-    /**
-     * \class MMMPlayer
-     * \ingroup RobotAPI-Components
-     * \brief Replays an MMM trajectory from a file.
-     *
-     * MMMPlayer reads an MMM trajectory from an MMM XML file (component property) and replays the motion using the KinematicUnit and its currently loaded robot.
-     * The trajectory can be replayed using position control or velocity control.
-     * In the latter case, the control parameters (P, I, D) can be configured via component properties.
-     */
-    class MMMPlayer :
-        virtual public armarx::Component,
-            public KinematicUnitListener
-    {
-    public:
-        /**
-         * @see armarx::ManagedIceObject::getDefaultName()
-         */
-        virtual std::string getDefaultName() const
-        {
-            return "MMMPlayer";
-        }
-
-    protected:
-        /**
-         * @see armarx::ManagedIceObject::onInitComponent()
-         */
-        virtual void onInitComponent();
-
-        /**
-         * @see armarx::ManagedIceObject::onConnectComponent()
-         */
-        virtual void onConnectComponent();
-
-        /**
-         * @see armarx::ManagedIceObject::onDisconnectComponent()
-         */
-        virtual void onDisconnectComponent();
-
-        /**
-         * @see armarx::ManagedIceObject::onExitComponent()
-         */
-        virtual void onExitComponent();
-
-        /**
-         * @see PropertyUser::createPropertyDefinitions()
-         */
-        virtual PropertyDefinitionsPtr createPropertyDefinitions();
-
-        void run();
-        bool usePIDController;
-        Mutex playerMutex;
-        MMM::MotionPtr motion;
-        KinematicUnitInterfacePrx kin;
-        DebugObserverInterfacePrx debugObserver;
-        PeriodicTask<MMMPlayer>::pointer_type task;
-        StringList jointNames;
-        int currentFrame;
-        double currentMotionTime;
-        float motionFPS;
-        float desiredFPS;
-        std::map<std::string, PIDControllerPtr> PIDs;
-        NameValueMap targetPositionValues;
-        IceUtil::Time motionStartTime;
-        float start, end;
-        int direction;
-        NameValueMap jointOffets;
-        float maxVel;
-
-
-        // KinematicUnitListener interface
-    public:
-        void reportControlModeChanged(const NameControlModeMap &, bool, const Ice::Current &){}
-        void reportJointAngles(const NameValueMap &angles, bool, const Ice::Current &);
-        void reportJointVelocities(const NameValueMap &, bool, const Ice::Current &){}
-        void reportJointTorques(const NameValueMap &, bool, const Ice::Current &){}
-        void reportJointAccelerations(const NameValueMap &, bool, const Ice::Current &){}
-        void reportJointCurrents(const NameValueMap &, bool, const Ice::Current &){}
-        void reportJointMotorTemperatures(const NameValueMap &, bool, const Ice::Current &){}
-        void reportJointStatuses(const NameStatusMap &, bool, const Ice::Current &){}
-    };
-}
-
-#endif
diff --git a/source/RobotAPI/components/MMMPlayer/test/CMakeLists.txt b/source/RobotAPI/components/MMMPlayer/test/CMakeLists.txt
deleted file mode 100644
index 16a4cf72988867edbe64273efc0970b571548e5f..0000000000000000000000000000000000000000
--- a/source/RobotAPI/components/MMMPlayer/test/CMakeLists.txt
+++ /dev/null
@@ -1,5 +0,0 @@
-
-# Libs required for the tests
-SET(LIBS ${LIBS} ArmarXCore MMMPlayer)
- 
-armarx_add_test(MMMPlayerTest MMMPlayerTest.cpp "${LIBS}")
\ No newline at end of file
diff --git a/source/RobotAPI/components/MMMPlayer/test/MMMPlayerTest.cpp b/source/RobotAPI/components/MMMPlayer/test/MMMPlayerTest.cpp
deleted file mode 100644
index 326edd5156a723b5b205d7a29ec561e2d2f18e6d..0000000000000000000000000000000000000000
--- a/source/RobotAPI/components/MMMPlayer/test/MMMPlayerTest.cpp
+++ /dev/null
@@ -1,38 +0,0 @@
-/*
- * This file is part of ArmarX.
- *
- * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
- *
- * ArmarX is distributed in the hope that it will be useful, but
- * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with this program. If not, see <http://www.gnu.org/licenses/>.
- *
- * @package    RobotAPI::ArmarXObjects::MMMPlayer
- * @author     Mirko Waechter ( mirko dot waechter at kit dot edu )
- * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
- *             GNU General Public License
- */
-
-#define BOOST_TEST_MODULE RobotAPI::ArmarXObjects::MMMPlayer
-
-#define ARMARX_BOOST_TEST
-
-#include <RobotAPI/Test.h>
-#include <RobotAPI/components/MMMPlayer/MMMPlayer.h>
-
-#include <iostream>
-
-BOOST_AUTO_TEST_CASE(testExample)
-{
-    armarx::MMMPlayer instance;
-
-    BOOST_CHECK_EQUAL(true, true);
-}
diff --git a/source/RobotAPI/components/RobotIK/CMakeLists.txt b/source/RobotAPI/components/RobotIK/CMakeLists.txt
deleted file mode 100644
index e463e42ece1e089176619aecec92c53a46b0da18..0000000000000000000000000000000000000000
--- a/source/RobotAPI/components/RobotIK/CMakeLists.txt
+++ /dev/null
@@ -1,28 +0,0 @@
-armarx_set_target("Core Library: ArmarXCoreRobotIK")
-
-find_package(Eigen3 QUIET)
-find_package(Simox ${ArmarX_Simox_VERSION} QUIET)
-
-armarx_build_if(Eigen3_FOUND "Eigen3 not available")
-armarx_build_if(Simox_FOUND "Simox-VirtualRobot not available")
-
-include_directories(${Eigen3_INCLUDE_DIR})
-include_directories(${Simox_INCLUDE_DIRS})
-
-set(LIB_NAME       RobotAPIRobotIK)
-set(LIB_VERSION    0.1.0)
-set(LIB_SOVERSION  0)
-
-set(LIBS ArmarXCore RobotAPICore)
-
-set(LIB_FILES
-        RobotIK.cpp
-    )
-
-set(LIB_HEADERS
-        RobotIK.h
-)
-
-armarx_add_library("${LIB_NAME}" "${LIB_VERSION}" "${LIB_SOVERSION}" "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
-
-add_subdirectory(test)
\ No newline at end of file
diff --git a/source/RobotAPI/components/RobotIK/RobotIK.cpp b/source/RobotAPI/components/RobotIK/RobotIK.cpp
deleted file mode 100644
index 61446149c698d0bbf52f6fee259c61c1a1a1eb00..0000000000000000000000000000000000000000
--- a/source/RobotAPI/components/RobotIK/RobotIK.cpp
+++ /dev/null
@@ -1,633 +0,0 @@
-/*
- * This file is part of ArmarX.
- *
- * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
- *
- * ArmarX is distributed in the hope that it will be useful, but
- * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with this program. If not, see <http://www.gnu.org/licenses/>.
- *
- * @package    RobotAPI::ArmarXObjects::RobotIK
- * @author     Joshua Haustein ( joshua dot haustein at gmail dot com )
- * @date       2015
- * @copyright  http://www.gnu.org/licenses/gpl.txt
- *             GNU General Public License
- */
-
-#include "RobotIK.h"
-
-#include <VirtualRobot/XML/RobotIO.h>
-#include <VirtualRobot/Nodes/RobotNode.h>
-#include <VirtualRobot/RobotNodeSet.h>
-#include <VirtualRobot/Workspace/Reachability.h>
-#include <VirtualRobot/Workspace/Manipulability.h>
-#include <VirtualRobot/IK/CoMIK.h>
-#include <VirtualRobot/IK/JointLimitAvoidanceJacobi.h>
-#include <VirtualRobot/IK/HierarchicalIK.h>
-
-#include <boost/foreach.hpp>
-#include <boost/format.hpp>
-#include <boost/filesystem.hpp>
- 
-#include <Core/core/system/ArmarXDataPath.h>
-#include <Core/core/ArmarXManager.h>
-#include <Core/core/ArmarXObjectScheduler.h>
-#include <RobotAPI/libraries/core/remoterobot/RemoteRobot.h>
-
-#include <algorithm>
-#include <set>
-
-// using namespace std;
-using namespace VirtualRobot;
-using namespace Eigen;
-using namespace Ice;
-using namespace boost;
-
-namespace armarx
-{
-
-    void RobotIK::onInitComponent()
-    {
-        _robotFile = getProperty<std::string>("RobotFileName").getValue();
-        if (!ArmarXDataPath::getAbsolutePath(_robotFile, _robotFile))
-        {
-            throw UserException("Could not find robot file " + _robotFile);
-        }
-
-        this->_robotModel = VirtualRobot::RobotIO::loadRobot(_robotFile, VirtualRobot::RobotIO::eStructure);
-        
-        if (this->_robotModel)
-        {
-            ARMARX_VERBOSE << "Loaded robot from file " << _robotFile;
-        }
-        else
-        {
-            ARMARX_VERBOSE << "Failed loading robot from file " << _robotFile;
-        }
-        
-        // Get number of ik trials    
-        _numIKTrials = getProperty<int>("NumIKTrials").getValue();
-
-        // Load initial reachability maps (if configured)
-        std::vector<std::string> spaces;
-        std::string spacesStr = getProperty<std::string>("InitialReachabilitySpaces").getValue();
-        boost::split(spaces, spacesStr, boost::is_any_of(";"));
-
-        if(spacesStr != "")
-        {
-            std::string spacesFolder = getProperty<std::string>("ReachabilitySpacesFolder").getValue();
-
-            for(auto &space : spaces)
-            {
-                ARMARX_INFO << "Initially loading reachability space '" << (spacesFolder + "/" + space) << "'";
-
-                std::string absolutePath;
-                if(!ArmarXDataPath::getAbsolutePath(spacesFolder + "/" + space, absolutePath))
-                {
-                    ARMARX_ERROR << "Could not load reachability map '" << (spacesFolder + "/" + space) << "'";
-                    continue;
-                }
-
-                loadReachabilitySpace(absolutePath);
-            }
-        }       
-
-        usingProxy(getProperty<std::string>("RobotStateComponentName").getValue());
-        offeringTopic("DebugDrawerUpdates");
-    }
-
-
-    void RobotIK::onConnectComponent()
-    {
-        _robotStateComponentPrx = getProxy<RobotStateComponentInterfacePrx>(getProperty<std::string>("RobotStateComponentName").getValue());
-        if (_robotStateComponentPrx->getRobotFilename().compare(_robotFile) != 0) {
-            ARMARX_WARNING << "The robot state component uses the robot model " << _robotStateComponentPrx->getRobotFilename()
-                << " This component, however, uses " << _robotFile << " Both models must be identical!";
-        }
-        _synchronizedRobot = _robotStateComponentPrx->getSynchronizedRobot();
-        debugDrawer = getTopic<armarx::DebugDrawerInterfacePrx>("DebugDrawerUpdates");
-
-    }
-
-    void RobotIK::onDisconnectComponent()
-    {
-    }
-
-    PropertyDefinitionsPtr RobotIK::createPropertyDefinitions()
-    {
-        return PropertyDefinitionsPtr(new RobotIKPropertyDefinitions(
-                                          getConfigIdentifier()));
-    }
-
-    NameValueMap RobotIK::computeIKFramedPose(const std::string& robotNodeSetName, 
-            const FramedPoseBasePtr& tcpPose, armarx::CartesianSelection cs, const Ice::Current&) const
-    {
-        NameValueMap ikSolution;
-        computeIK(robotNodeSetName, toGlobalPose(tcpPose), cs, ikSolution);
-        return ikSolution;
-    }
-
-    NameValueMap RobotIK::computeIKGlobalPose(const std::string& robotNodeSetName, 
-            const PoseBasePtr& tcpPose, armarx::CartesianSelection cs, const Ice::Current&) const
-    {
-        NameValueMap ikSolution;
-        Pose globalTcpPose(tcpPose->position, tcpPose->orientation);
-        computeIK(robotNodeSetName, globalTcpPose.toEigen(), cs, ikSolution);
-        return ikSolution;
-    }
-
-    ExtendedIKResult RobotIK::computeExtendedIKGlobalPose(const std::string& robotNodeSetName,
-            const PoseBasePtr& tcpPose, armarx::CartesianSelection cs, const Ice::Current&) const
-    {
-        ExtendedIKResult ikSolution;
-        Pose globalTcpPose(tcpPose->position, tcpPose->orientation);
-        computeIK(robotNodeSetName, globalTcpPose.toEigen(), cs, ikSolution);
-        return ikSolution;
-    }
-
-    NameValueMap RobotIK::computeCoMIK(const std::string& robotNodeSetJoints, const CoMIKDescriptor& desc, const Ice::Current&) const
-    {
-        // Make sure we have valid input parameters
-        if (!_robotModel->hasRobotNodeSet(robotNodeSetJoints)) 
-        {
-            return NameValueMap();
-        }
-
-        if (!_robotModel->hasRobotNodeSet(desc.robotNodeSetBodies)) 
-        {
-            return NameValueMap();
-        }
-
-        RobotNodePtr coordSystem = RobotNodePtr();
-        if (desc.coordSysName.size() > 0 && _robotModel->hasRobotNode(desc.coordSysName)) 
-        {
-            coordSystem = _robotModel->getRobotNode(desc.coordSysName);
-        }
-        
-        // Create and initialize ik solver
-        RobotNodeSetPtr joints = _robotModel->getRobotNodeSet(robotNodeSetJoints);
-        CoMIK comIkSolver(joints, _robotModel->getRobotNodeSet(desc.robotNodeSetBodies), coordSystem);
-        Eigen::VectorXf goal(2);
-        goal(0) = desc.gx;
-        goal(1) = desc.gy;
-        comIkSolver.setGoal(goal, desc.tolerance);
-        
-        // Solve
-        std::lock_guard<std::recursive_mutex> lock(_modifyRobotModelMutex);
-        bool success = comIkSolver.solveIK();
-        NameValueMap result;
-        if (success) 
-        {
-            BOOST_FOREACH(auto joint, joints->getAllRobotNodes())
-            {
-                NameValueMap::value_type jointPair(joint->getName(), joint->getJointValue());
-                result.insert(jointPair);
-            }
-        } 
-        return result;
-    }
-
-    NameValueMap RobotIK::computeHierarchicalDeltaIK(const std::string& robotNodeSetName, 
-        const IKTasks& iktasks, const CoMIKDescriptor& comIK, float stepSize,
-        bool avoidJointLimits, bool enableCenterOfMass, const Ice::Current&) const
-    {
-        typedef std::pair<int, JacobiProviderPtr> PriorityJacobiProviderPair;
-        auto lowerPriorityCompare = [] (const PriorityJacobiProviderPair& a, const PriorityJacobiProviderPair& b) { return a.first < b.first; };
-        std::multiset<PriorityJacobiProviderPair, decltype(lowerPriorityCompare)> jacobiProviders(lowerPriorityCompare);
-
-        if (!_robotModel->hasRobotNodeSet(robotNodeSetName)) 
-        {
-            throw UserException("Unknown robot node set " + robotNodeSetName);
-        }
-
-        synchRobot();
-
-        RobotNodeSetPtr rns = _robotModel->getRobotNodeSet(robotNodeSetName);
-        // First add all ik tasks
-        BOOST_FOREACH(DifferentialIKDescriptor ikTask, iktasks)
-        {
-            if (!_robotModel->hasRobotNode(ikTask.tcpName)) 
-            {
-                throw UserException("Unknown TCP: " + ikTask.tcpName);
-            }
-
-            RobotNodePtr coordSystem = RobotNodePtr();
-            if(ikTask.coordSysName.size() > 0 && _robotModel->hasRobotNode(ikTask.coordSysName))
-            {
-                coordSystem = _robotModel->getRobotNode(ikTask.coordSysName);
-            }
-
-            DifferentialIKPtr diffIK(new DifferentialIK(rns, coordSystem, convertInverseJacobiMethod(ikTask.ijm)));
-            Pose globalTcpPose(ikTask.tcpGoal->position, ikTask.tcpGoal->orientation);
-            RobotNodePtr tcp = _robotModel->getRobotNode(ikTask.tcpName);
-            diffIK->setGoal(globalTcpPose.toEigen(), tcp, convertCartesianSelection(ikTask.csel));
-            JacobiProviderPtr jacoProv = diffIK;
-            jacobiProviders.insert(PriorityJacobiProviderPair(ikTask.priority, jacoProv));
-        }
-
-        // Now add the center of mass task
-        if (enableCenterOfMass)
-        {
-            if (!_robotModel->hasRobotNodeSet(comIK.robotNodeSetBodies)) 
-            {
-                throw UserException("Unknown robot node set for bodies: " + comIK.robotNodeSetBodies);
-            }
-
-            RobotNodePtr coordSystem = RobotNodePtr();
-            if (comIK.coordSysName.size() > 0 && _robotModel->hasRobotNode(comIK.coordSysName)) 
-            {
-                coordSystem = _robotModel->getRobotNode(comIK.coordSysName);
-            }   
-        
-            CoMIKPtr comIkSolver(new CoMIK(rns, _robotModel->getRobotNodeSet(comIK.robotNodeSetBodies)));
-            Eigen::VectorXf goal(2);
-            goal(0) = comIK.gx;
-            goal(1) = comIK.gy;
-            comIkSolver->setGoal(goal, comIK.tolerance);
-            JacobiProviderPtr jacoProv = comIkSolver;
-            jacobiProviders.insert(PriorityJacobiProviderPair(comIK.priority, jacoProv));   
-        }
-
-        std::vector<JacobiProviderPtr> jacobies;
-        BOOST_FOREACH(PriorityJacobiProviderPair pair, jacobiProviders)
-        {
-            jacobies.push_back(pair.second);
-        }
-
-        if (avoidJointLimits)
-        {
-            JointLimitAvoidanceJacobiPtr avoidanceJacobi(new JointLimitAvoidanceJacobi(rns));
-            jacobies.push_back(avoidanceJacobi);
-        }
-
-        std::lock_guard<std::recursive_mutex> lock(_modifyRobotModelMutex);
-        HierarchicalIK hik(rns);
-        Eigen::VectorXf delta = hik.computeStep(jacobies, stepSize);
-        NameValueMap result;
-
-        int index = 0;
-        BOOST_FOREACH(RobotNodePtr node, rns->getAllRobotNodes())
-        {
-            NameValueMap::value_type jointPair(node->getName(), delta(index));
-            result.insert(jointPair);
-            ++index;
-        }
-        return result;
-    }
-
-    bool RobotIK::createReachabilitySpace(const std::string& chainName, const std::string& coordinateSystem, float stepTranslation,
-        float stepRotation, const WorkspaceBounds& minBounds, const WorkspaceBounds& maxBounds, int numSamples, const Ice::Current&) 
-    {
-        std::lock_guard<std::recursive_mutex> cacheLock(_accessReachabilityCacheMutex);
-        if (_reachabilities.count(chainName) == 0)
-        {
-            if (!_robotModel->hasRobotNodeSet(chainName))
-            {
-                return false;
-            }
-            WorkspaceRepresentationPtr reachability(new Reachability(_robotModel));
-            float minBoundsArray[] = {minBounds.x, minBounds.y, minBounds.z, minBounds.ro, minBounds.pi, minBounds.ya};
-            float maxBoundsArray[] = {maxBounds.x, maxBounds.y, maxBounds.z, maxBounds.ro, maxBounds.pi, maxBounds.ya};
-            
-            std::lock_guard<std::recursive_mutex> robotLock(_modifyRobotModelMutex);
-            // TODO add collision checks 
-            if (coordinateSystem.size() > 0)
-            {
-                if (!_robotModel->hasRobotNode(coordinateSystem))
-                {
-                    ARMARX_ERROR << "Unknown coordinate system " << coordinateSystem;
-                    return false;
-                }
-                reachability->initialize(_robotModel->getRobotNodeSet(chainName), stepTranslation, stepRotation, minBoundsArray, maxBoundsArray,
-                                         VirtualRobot::SceneObjectSetPtr(), VirtualRobot::SceneObjectSetPtr(), _robotModel->getRobotNode(coordinateSystem));
-            } 
-            else
-            {
-                reachability->initialize(_robotModel->getRobotNodeSet(chainName), stepTranslation, stepRotation, minBoundsArray, maxBoundsArray);
-                ARMARX_WARNING << "Using global coordinate system to create reachability space.";
-            }
-            reachability->addRandomTCPPoses(numSamples);
-            _reachabilities.insert(ReachabilityCacheType::value_type(chainName, reachability));
-        }
-        return true;
-    }
-
-    bool RobotIK::defineRobotNodeSet(const std::string& name, const NodeNameList& nodes, 
-        const std::string& tcpName, const std::string& rootNodeName, const Ice::Current&)
-    {
-        auto stringsCompareEqual = [] (const std::string& a, const std::string& b) { return a.compare(b) == 0; };
-        auto stringsCompareSmaller = [] (const std::string& a, const std::string& b) { return a.compare(b) <= 0; };
-        // First check if there is already a set with the given name
-        // We need to lock here, to make sure we are not adding similar named sets at the same time.
-        std::lock_guard<std::recursive_mutex> lock(_editRobotNodeSetsMutex);
-        if (_robotModel->hasRobotNodeSet(name))
-        {
-            // If so, check if the set is identical to the one we plan to add
-            bool setsIdentical = true;
-            RobotNodeSetPtr rns = _robotModel->getRobotNodeSet(name);
-            // Check TCP node
-            RobotNodePtr tcpNode = rns->getTCP();
-            setsIdentical &= stringsCompareEqual(tcpNode->getName(), tcpName);
-            // Check Root node
-            RobotNodePtr rootNode = rns->getKinematicRoot();
-            setsIdentical &= stringsCompareEqual(rootNode->getName(), rootNodeName);
-            // Check remaining nodes
-            std::vector<std::string> nodeNames;
-            BOOST_FOREACH(RobotNodePtr robotNode, rns->getAllRobotNodes())
-            {
-                nodeNames.push_back(robotNode->getName());
-            }
-            // TODO check if sorting actually makes sense here
-            std::sort(nodeNames.begin(), nodeNames.end(), stringsCompareSmaller);
-            std::vector<std::string> inputNodeNames(nodes);
-            std::sort(inputNodeNames.begin(), inputNodeNames.end(), stringsCompareSmaller);
-            std::pair< std::vector<std::string>::iterator, std::vector<std::string>::iterator > mismatch;
-            mismatch = std::mismatch(nodeNames.begin(), nodeNames.end(), inputNodeNames.begin(), stringsCompareEqual);
-            setsIdentical &= mismatch.first == nodeNames.end() && mismatch.second == inputNodeNames.end();
-            
-            return setsIdentical;
-        }
-        // Else we can add the new robot node set
-        RobotNodeSetPtr rns = RobotNodeSet::createRobotNodeSet(_robotModel, name, nodes, rootNodeName, tcpName, true);
-        return _robotModel->hasRobotNodeSet(name);
-    }
-
-    std::string RobotIK::getRobotFilename(const Ice::Current&) const
-    {       
-        return _robotFile;
-    }
-
-    bool RobotIK::hasReachabilitySpace(const std::string& chainName, const Ice::Current&) const 
-    {
-        std::lock_guard<std::recursive_mutex> lock(_accessReachabilityCacheMutex);
-        return _reachabilities.count(chainName) > 0;
-    }
-
-    bool RobotIK::isFramedPoseReachable(const std::string& chainName, const FramedPoseBasePtr& tcpPose, const Ice::Current&) const 
-    {
-        return isReachable(chainName, toReachabilityMapFrame(tcpPose, chainName));
-    }
-
-    bool RobotIK::isPoseReachable(const std::string& chainName, const PoseBasePtr& tcpPose, const Ice::Current&) const 
-    {
-        Pose globalTcpPose(tcpPose->position, tcpPose->orientation);
-        return isReachable(chainName, globalTcpPose.toEigen());
-    }
-
-    bool RobotIK::loadReachabilitySpace(const std::string& filename, const Ice::Current&) 
-    {
-        WorkspaceRepresentationPtr newSpace;
-        bool success = false;
-
-        // 1st try to load as manipulability file
-        try
-        {
-            newSpace.reset(new Manipulability(_robotModel));
-            newSpace->load(filename);
-            success = true;
-
-            ARMARX_INFO << "Map '" << filename << "' loaded as Manipulability map";
-        }
-        catch(...)
-        {
-        }
-
-        // 2nd try to load as reachability file
-        if(!success)
-        {
-            try
-            {
-                newSpace.reset(new Reachability(_robotModel));
-                newSpace->load(filename);
-                success = true;
-
-                ARMARX_INFO << "Map '" << filename << "' loaded as Reachability map";
-            }
-            catch(...)
-            {
-            }
-        }
-
-        if(!success)
-        {
-            ARMARX_ERROR << "Failed to load map '" << filename << "'";
-            return false;
-        }
-
-        try
-        {
-            std::lock_guard<std::recursive_mutex> lock(_accessReachabilityCacheMutex);
-            std::string chainName = newSpace->getNodeSet()->getName();
-
-            if (_reachabilities.count(chainName) == 0)
-            {
-                _reachabilities.insert(ReachabilityCacheType::value_type(chainName, newSpace));
-            }
-            else
-            {
-                ARMARX_WARNING << "Reachability map for kinematic chain '" << chainName << "' already loaded";
-                return false;
-            }
-        }
-        catch (Exception e)
-        {
-            throw;
-        }
-
-        return true;
-    }
-
-    bool RobotIK::saveReachabilitySpace(const std::string& robotNodeSet, const std::string& filename, const Ice::Current&) const
-    {
-        std::lock_guard<std::recursive_mutex> lock(_accessReachabilityCacheMutex);
-        bool success = false;
-        if (_reachabilities.count(robotNodeSet) > 0)
-        {
-            ReachabilityCacheType::const_iterator it = _reachabilities.find(robotNodeSet);
-            try 
-            {
-                filesystem::path savePath(filename);
-                filesystem::create_directories(savePath.parent_path());        
-                it->second->save(filename);
-                success = true;
-            } catch (Exception e)
-            { // no need to unlock, this is done automatically once we leave this context
-                throw;
-            }
-        }
-        return success;
-    }
-
-    void RobotIK::computeIK(const std::string& robotNodeSetName, const Eigen::Matrix4f& tcpPose,
-        armarx::CartesianSelection cs, NameValueMap& ikSolution) const
-    {
-        if (!_robotModel->hasRobotNodeSet(robotNodeSetName))
-        {
-            throw UserException("The robot model does not contain the robot node set " + robotNodeSetName);
-        }
-        RobotNodeSetPtr rns = _robotModel->getRobotNodeSet(robotNodeSetName);
-        computeIK(rns, tcpPose, cs, ikSolution);
-    }
-
-    void RobotIK::computeIK(const std::string& robotNodeSetName, const Eigen::Matrix4f& tcpPose,
-        armarx::CartesianSelection cs, ExtendedIKResult& ikSolution) const
-    {
-        if (!_robotModel->hasRobotNodeSet(robotNodeSetName))
-        {
-            throw UserException("The robot model does not contain the robot node set " + robotNodeSetName);
-        }
-        RobotNodeSetPtr rns = _robotModel->getRobotNodeSet(robotNodeSetName);
-        computeIK(rns, tcpPose, cs, ikSolution);
-    }
-
-    void RobotIK::computeIK(VirtualRobot::RobotNodeSetPtr nodeSet, const Eigen::Matrix4f& tcpPose,
-        armarx::CartesianSelection cs, NameValueMap& ikSolution) const 
-    {
-        
-        ikSolution.clear();
-        // For the rest of this function we need to lock access to the robot,
-        // because we need to make sure we read the correct result from the robot node set.
-        std::lock_guard<std::recursive_mutex> lock(_modifyRobotModelMutex);
-        // Synch the internal robot state with that of the robot state component
-        synchRobot();
-
-        GenericIKSolver ikSolver(nodeSet, JacobiProvider::eSVDDamped);
-        bool success = ikSolver.solve(tcpPose, convertCartesianSelection(cs), _numIKTrials);
-        // Read solution from node set
-        if (success)
-        {
-            const std::vector<RobotNodePtr> robotNodes = nodeSet->getAllRobotNodes();
-            BOOST_FOREACH(RobotNodePtr rnode, robotNodes)
-            {
-                NameValueMap::value_type jointPair(rnode->getName(), rnode->getJointValue());
-                ikSolution.insert(jointPair);
-            }
-        } 
-        // Lock is automatically released
-    }
-
-    void RobotIK::computeIK(VirtualRobot::RobotNodeSetPtr nodeSet, const Eigen::Matrix4f& tcpPose,
-        armarx::CartesianSelection cs, ExtendedIKResult& ikSolution) const
-    {
-        ikSolution.jointAngles.clear();
-        // For the rest of this function we need to lock access to the robot,
-        // because we need to make sure we read the correct result from the robot node set.
-        std::lock_guard<std::recursive_mutex> lock(_modifyRobotModelMutex);
-        // Synch the internal robot state with that of the robot state component
-        synchRobot();
-
-        GenericIKSolver ikSolver(nodeSet, JacobiProvider::eSVDDamped);
-
-        bool success = ikSolver.solve(tcpPose, convertCartesianSelection(cs), _numIKTrials);
-        // Read solution from node set
-        const std::vector<RobotNodePtr> robotNodes = nodeSet->getAllRobotNodes();
-        BOOST_FOREACH(RobotNodePtr rnode, robotNodes)
-        {
-            NameValueMap::value_type jointPair(rnode->getName(), rnode->getJointValue());
-            ikSolution.jointAngles.insert(jointPair);
-        }
-
-        //Calculate error
-        ikSolution.error = (nodeSet->getTCP()->getGlobalPose().block<3, 1>(0, 3) - tcpPose.block<3, 1>(0, 3)).norm();
-
-        ikSolution.isReachable = success;
-        // Lock is automatically released
-    }
-
-
-    Eigen::Matrix4f RobotIK::toGlobalPose(const FramedPoseBasePtr& tcpPose) const 
-    {
-        FramedPose framedTcpPose(tcpPose->position, tcpPose->orientation, tcpPose->frame, tcpPose->agent);
-        FramedPosePtr globalTcpPose = framedTcpPose.toGlobal(_synchronizedRobot);
-        return globalTcpPose->toEigen();
-    }
-
-    Eigen::Matrix4f RobotIK::toReachabilityMapFrame(const FramedPoseBasePtr &tcpPose, const std::string &chainName) const
-    {
-        FramedPosePtr p = FramedPosePtr::dynamicCast(tcpPose);
-
-        PosePtr p_global(new Pose(toGlobalPose(tcpPose)));
-        debugDrawer->setPoseDebugLayerVisu("Grasp Pose", p_global);
-
-        std::lock_guard<std::recursive_mutex> lock(_accessReachabilityCacheMutex);
-        if (_reachabilities.count(chainName))
-        {
-            ReachabilityCacheType::const_iterator it = _reachabilities.find(chainName);
-
-            p->changeFrame(_synchronizedRobot, it->second->getBaseNode()->getName());
-        }
-        else
-        {
-            ARMARX_WARNING << "Could not convert TCP pose to reachability map frame: Map not found.";
-        }
-
-        return p->toEigen();
-    }
-
-    bool RobotIK::isReachable(const std::string& setName, const Eigen::Matrix4f& tcpPose) const 
-    {
-        ARMARX_INFO << "Checking reachability for kinematic chain '" << setName << "': " << tcpPose;
-
-        std::lock_guard<std::recursive_mutex> lock(_accessReachabilityCacheMutex);
-        if (_reachabilities.count(setName)) 
-        {
-            ReachabilityCacheType::const_iterator it = _reachabilities.find(setName);
-            return it->second->isCovered(tcpPose);
-        }
-        else
-        {
-            ARMARX_WARNING << "Could not find reachability map for kinematic chain '" << setName << "'";
-            return false;
-        }
-    }
-
-    VirtualRobot::IKSolver::CartesianSelection RobotIK::convertCartesianSelection(armarx::CartesianSelection cs) const
-    {
-        switch(cs) {
-            case armarx::CartesianSelection::eX:
-                return VirtualRobot::IKSolver::CartesianSelection::X;
-            case armarx::CartesianSelection::eY:
-                return VirtualRobot::IKSolver::CartesianSelection::Y;
-            case armarx::CartesianSelection::eZ:
-                return VirtualRobot::IKSolver::CartesianSelection::Z;
-            case armarx::CartesianSelection::ePosition:
-                return VirtualRobot::IKSolver::CartesianSelection::Position;
-            case armarx::CartesianSelection::eOrientation:
-                return VirtualRobot::IKSolver::CartesianSelection::Orientation;
-            case armarx::CartesianSelection::eAll:
-                return VirtualRobot::IKSolver::CartesianSelection::All;
-        }
-        return VirtualRobot::IKSolver::CartesianSelection::All;
-    }
-
-    VirtualRobot::JacobiProvider::InverseJacobiMethod RobotIK::convertInverseJacobiMethod(armarx::InverseJacobiMethod aenum) const
-    {
-        switch(aenum)
-        {
-            case armarx::InverseJacobiMethod::eSVD:
-                return VirtualRobot::JacobiProvider::InverseJacobiMethod::eSVD;
-            case armarx::InverseJacobiMethod::eSVDDamped:
-                return VirtualRobot::JacobiProvider::InverseJacobiMethod::eSVDDamped;
-            case armarx::InverseJacobiMethod::eTranspose: 
-                return VirtualRobot::JacobiProvider::InverseJacobiMethod::eTranspose;
-        }
-        return VirtualRobot::JacobiProvider::InverseJacobiMethod::eSVD;
-    }
-
-    void RobotIK::synchRobot() const 
-    {
-        std::lock_guard<std::recursive_mutex> lock(_modifyRobotModelMutex);
-        RemoteRobot::synchronizeLocalClone(_robotModel, _synchronizedRobot);
-    }
-
-}
-
-
-
diff --git a/source/RobotAPI/components/RobotIK/RobotIK.h b/source/RobotAPI/components/RobotIK/RobotIK.h
deleted file mode 100644
index 9e3582c0b90ba59904f11468eeb77c799d3fe2c6..0000000000000000000000000000000000000000
--- a/source/RobotAPI/components/RobotIK/RobotIK.h
+++ /dev/null
@@ -1,374 +0,0 @@
-/*
- * This file is part of ArmarX.
- *
- * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
- *
- * ArmarX is distributed in the hope that it will be useful, but
- * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with this program. If not, see <http://www.gnu.org/licenses/>.
- *
- * @package    RobotAPI::ArmarXObjects::RobotIK
- * @author     Joshua Haustein ( joshua dot haustein at gmail dot com )
- * @date       2015
- * @copyright  http://www.gnu.org/licenses/gpl.txt
- *             GNU General Public License
- */
-
-#ifndef _ARMARX_COMPONENT_RobotAPI_RobotIK_H
-#define _ARMARX_COMPONENT_RobotAPI_RobotIK_H
-
-#include <Core/core/Component.h>
-#include <Core/core/application/properties/Properties.h>
-#include <Core/core/system/ImportExportComponent.h>
-
-#include <RobotAPI/libraries/core/RobotAPIObjectFactories.h>
-#include <RobotAPI/interface/core/RobotIK.h>
-#include <RobotAPI/interface/visualization/DebugDrawerInterface.h>
-
-#include <VirtualRobot/IK/GenericIKSolver.h>
-
-#include <mutex>
-
-namespace armarx
-{
-    /**
-     * \class RobotIKPropertyDefinition
-     * \brief
-     */
-    class RobotIKPropertyDefinitions:
-            public ComponentPropertyDefinitions
-    {
-    public:
-        RobotIKPropertyDefinitions(std::string prefix):
-            ComponentPropertyDefinitions(prefix)
-        {
-            defineRequiredProperty<std::string>("RobotFileName", "Filename of VirtualRobot robot model (e.g. robot_model.xml)");
-            defineRequiredProperty<std::string>("RobotStateComponentName", "Name of the robot state component that should be used");
-            //Define optional properties
-            defineOptionalProperty<std::string>("ReachabilitySpacesFolder", "Path to a folder containing reachability spaces");
-            defineOptionalProperty<int>("NumIKTrials", 10, "Number of trials to find an ik solution");
-            defineOptionalProperty<std::string>("InitialReachabilitySpaces", "", "Reachability spaces to load initially (semi-colon separated)");
-        }
-    };
-
-
-    /**
-     * \class RobotIK
-     * \ingroup RobotAPI-Components
-     * \brief Provides IK solving methods from VirtualRobot (see [Simox](http://simox.sourceforge.net/)).
-     *
-     * RobotIK provides a set of functions that allow computing IKs for any kinematic chain
-     * in a robot. This component requires the following properties:
-     *  - RobotFileName: The VirtualRobot robot model to be used.
-     *  - RobotStateComponentName: The name of a robot state component.
-     *
-     * Furthermore, there are the following optional properties:
-     *  - ReachabilitySpacesFolder: A Path to a folder containing reachability spaces.
-     *  - NumIKTrials: The number of trials the underlying ik solver tries to find a solution before giving up (default: 10).
-     *  
-     * The robot model is required to solve the IK. Some of the provided functionalities require the current robot state,
-     * which is retrieved from the robot state component specified in the properties. These functions will only work properly,
-     * if the robot model used by the robot state component is identical to the robot model of this component.
-     * 
-     * The functionalities include:
-     *  - computation of an IK solution for a kinematic chain given a goal TCP pose.
-     *  - computation of an IK solution for a set of robot joints such that 
-     *  the projection of the center of mass to the support surface lies within a goal region.
-     *  - computation of a joint value gradient to minimize the workspace error for several tasks simultaneously.
-     *  - creation and query of reachability spaces for kinematic chains.
-     *
-     * A reachability space for a kinematic chain allows a fast check whether 
-     * a TCP pose is reachable. Creating a reachability space, however, is a computational intensive process
-     * that should be done offline. You may create a reachability space by calling the respective function
-     * or by specifying a path to a folder, ReachabilitySpacesFolder, that contains a set of reachability spaces.
-     * If ReachabilitySpacesFolder is specified, each file in the folder is attempted to be loaded as reachability space 
-     * during initialization.
-     *
-     * While this implementation allows parallel access to its interface functions, 
-     * it is not optimized towards maximizing parallelism.
-     * If you need to access this component from a large number of threads/processes 
-     * and you care about performance, you should consider creating multiple instances 
-     * of this component or using local instances of the IK solver from Simox instead.
-     *
-     * Furthermore, at the beginning of an operation this component synchronizes its
-     * internal robot state with that provided by the robot state component. 
-     * This can lead to invalid IK solutions if the robot state changes while computation is still in progress.
-     * For example, imagine you compute an IK solution just 
-     * for the forearm and the wrist given a global eef pose. If during the computation the configuration
-     * of the elbow changes, the computed ik solution will no longer achieve the desired eef pose.  
-     * 
-     * Also see [Simox-Tutorial] (http://sourceforge.net/p/simox/wiki/VirtualRobot/) for more information
-     * of how to use Simox for IK solving.
-     */
-    class ARMARXCOMPONENT_IMPORT_EXPORT RobotIK :
-        virtual public Component,
-        virtual public RobotIKInterface
-    {
-    public:
-        
-        /**
-         * \return the robot xml filename as specified in the configuration
-         */
-        virtual std::string getRobotFilename(const Ice::Current&) const;
-
-        /**
-         * Create an instance of RobotIKPropertyDefinitions.
-         */
-        virtual PropertyDefinitionsPtr createPropertyDefinitions();
-
-        virtual std::string getDefaultName() const
-        {
-            return "RobotIK";
-        }
-
-        /**
-         * @brief Computes a single IK solution for the given robot node set and desired TCP pose.
-         * @details The TCP pose can be defined in any frame and is converted internally to a global pose 
-         * according to the current robot state. The CartesianSelection
-         * parameter defines which part of the target pose should be reached.
-         * 
-         * @param robotNodeSetName The name of a robot node set (robot node set) that is either stored 
-         * within the robot model or has been defined via \ref defineRobotNodeSet.
-         * @param tcpPose The framed target pose for the TCP.
-         * @param cs Specifies which part of the pose needs to be reached by the IK, e.g. the position only,
-         *           the orientation only or all.
-         * @return A map that maps each joint name to its value in the found IK solution. 
-         */
-        virtual NameValueMap computeIKFramedPose(const std::string& robotNodeSetName, 
-            const FramedPoseBasePtr& tcpPose, armarx::CartesianSelection cs, const Ice::Current& = Ice::Current()) const;
-
-        /**
-         * @brief Computes a single IK solution for the given robot node set and desired global TCP pose.
-         * @details The TCP pose is assumed to be in the global frame. The CartesianSelection
-         * parameter defines which part of the target pose should be reached.
-         * 
-         * @param robotNodeSetName The name of a robot node set (robot node set) that is either stored 
-         * within the robot model or has been defined via \ref defineRobotNodeSet.
-         * @param tcpPose The global target pose for the TCP.
-         * @param cs Specifies which part of the pose needs to be reached by the IK, e.g. the position only,
-         *           the orientation only or all.
-         * @return A map that maps each joint name to its value in the found IK solution. 
-         */
-        virtual NameValueMap computeIKGlobalPose(const std::string& robotNodeSetName, 
-            const PoseBasePtr& tcpPose, armarx::CartesianSelection cs, const Ice::Current& = Ice::Current()) const;
-
-        /**
-         * @brief Computes a single IK solution, error and reachability for the given robot node set and desired global TCP pose.
-         * @details The TCP pose is assumed to be in the global frame. The CartesianSelection
-         * parameter defines which part of the target pose should be reached.
-         *
-         * @param robotNodeSetName The name of a robot node set (robot node set) that is either stored
-         * within the robot model or has been defined via \ref defineRobotNodeSet.
-         * @param tcpPose The global target pose for the TCP.
-         * @param cs Specifies which part of the pose needs to be reached by the IK, e.g. the position only,
-         *           the orientation only or all.
-         * @return A map that maps each joint name to its value in the found IK solution, the reachability and computational error.
-         */
-        virtual ExtendedIKResult computeExtendedIKGlobalPose(const std::string& robotNodeSetName,
-            const PoseBasePtr& tcpPose, armarx::CartesianSelection cs, const Ice::Current& = Ice::Current()) const;
-
-        /**
-         * @brief Computes an IK solution for the given robot joints such that the center of mass lies above the 
-         * given point.
-         * @details 
-         * 
-         * @param robotNodeSetJoints Name of the robot node set that contains the joints you wish to compute the IK for.
-         * @param comIK A center of mass description. Note that the priority field is relevant for this function as there
-         * is only a single CoM of descriptor.
-         * 
-         * @return The ik-solution. Returns an empty vector if there is no solution.
-         */
-        virtual NameValueMap computeCoMIK(const std::string& robotNodeSetJoints, const CoMIKDescriptor& desc, const Ice::Current& = Ice::Current()) const;
-
-        /**
-         * @brief Computes a configuration gradient in order to solve several tasks/constraints simultaneously.
-         * @details This function allows you to use the HierarchicalIK solver provided by Simox. 
-         * It computes a configuration gradient for the given robot node set that minimizes the workspace errors
-         * for multiple tasks simultaneously. You can specify IK tasks, a center of mass task and a joint limit avoidance task.
-         * For details for the different type of tasks, see the parameter description. You must define a priority for each task.
-         * The task with maximal priority is the first task to be solved. Each subsequent task is then solved 
-         * within the null space of the previous task. <b> Note that this function returns a gradient and NOT
-         * an absolute IK solution. The gradient is computed on the current configuration of the robot. <\b>.
-         * The gradient is computed from the current robot configuration.
-         *
-         * See @url http://simox.sourceforge.net/documentation/class_virtual_robot_1_1_hierarchical_i_k.html 
-         * and @url http://sourceforge.net/p/simox/wiki/VirtualRobot/#hierarchical-ik-solving for more information.
-         * 
-         * @param robotNodeSet The robot node set (e.g. kinematic tree) you wish to compute the gradient for.
-         * @param diffIKs A list of IK tasks. Each IK task specifies a TCP and a desired pose for this TCP.
-         * @param comIK A center of mass tasks. Defines where the center should be and its priority. Is only used if the 
-                        CoM-task is enabled.
-         * @param stepSize
-         * @param avoidJointLimits Set whether or not to avoid joint limits.
-         * @param enableCenterOfMass Set whether or not to adjust the center of mass.
-         * @return A configuration gradient...
-         */
-        virtual NameValueMap computeHierarchicalDeltaIK(const std::string& robotNodeSet, 
-            const IKTasks& iktasks, const CoMIKDescriptor& comIK,
-            float stepSize, bool avoidJointLimits, bool enableCenterOfMass, const Ice::Current& = Ice::Current()) const;
-
-        /**
-         * @brief Creates a new reachability space for the given robot node set.
-         * @details If there is no reachability space for the given robot node set yet, a new one is created. This may take 
-         *          some time. The function returns true iff a reachability space for the given robot node set exists after 
-         *          execution of this function.
-         * 
-         * @param chainName The name of a defined robot node set. This can be either a robot node set that is defined in the 
-         *                  robot model or a robot node set that has been manually defined calling \ref defineRobotNodeSet.
-         * @param coordinateSystem The name of the robot node in whose coordinate system the reachability space shall be defined
-         *                  in. If you wish to choose the global coordinate system, pass an empty string.
-         *                  Note, however, that any reachability space defined in the 
-         *                  global coordinate system gets invalidated once the robot moves.
-         * @param stepTranslation The extend of a voxel dimension in translational dimensions (x,y,z) [mm]
-         * @param stepRotation The extend of a voxel dimension in rotational dimensions (roll,pitch,yaw) [rad]
-         * @param minBounds The minimum workspace poses (x,y,z,ro,pi,ya) given in the base node's coordinate system [mm and rad]
-         * @param maxBounds The maximum workspace poses (x,y,z,ro,pi,ya) given in base node's coordinate system [mm and rad]
-         * @param numSamples The number of tcp samples to take to create the reachability space (e.g 1000000)
-         * @return True iff the a reachability space for the given robot node set is available after execution of this function.
-         *         False in case of a failure, e.g. there is no chain with the given name.
-         */
-        virtual bool createReachabilitySpace(const std::string& chainName, const std::string& coordinateSystem, float stepTranslation, float stepRotation,
-            const WorkspaceBounds& minBounds, const WorkspaceBounds& maxBounds, int numSamples, const Ice::Current& = Ice::Current());
-
-        /**
-         * @brief Defines a new robot node set.
-         * @details Define a new robot node set with the given name that consists out of the given list of nodes with given 
-         *          TCP and root frame. Iff the chain is successfully added or already exists, <it>true</it> is returned.
-         * @param name The name of the robot node set.
-         * @param nodes The list of robot nodes that make up the robot node set.
-         * @param tcpName The name of the TCP node.
-         * @param rootNode The name of the kinematic root.
-         * 
-         * @return True, iff chain was added or already exists. False, iff a different chain with similar name already exists.
-         */
-        virtual bool defineRobotNodeSet(const std::string& name, const NodeNameList& nodes,
-            const std::string& tcpName, const std::string& rootNode, const Ice::Current& = Ice::Current());
-
-         /**
-         * @brief Returns whether this component has a reachability space for the given robot node set.
-         * @details True if there is a reachability space available, else false.
-         * 
-         * @param chainName Name of the robot node set.
-         * @return True if there is a reachability space available, else false.
-         */
-        virtual bool hasReachabilitySpace(const std::string& chainName, const Ice::Current& = Ice::Current()) const;
-
-        /**
-         * @brief Returns whether a given framed pose is currently reachable by the TCP of the given robot node set.
-         * @details To determine whether a pose is reachable a reachability space for the given robot node set is 
-         *          required. If no such space exists, the function returns <it>false<\it>. 
-         *          Call \ref createReachabilitySpace first to ensure there is such a space.
-         * 
-         * @param chainName A name of a robot node set either defined in the robot model or previously defined via 
-         *                  \ref defineRobotNodeSet. 
-         * @param framedPose A framed pose to check for reachability. The pose is transformed into a global pose using the 
-         *                   current robot state.
-         * 
-         * @return True, if the pose is reachable by the TCP of the given chain. False, if it is not reachable or 
-         *         there is no reachability space for the given chain available.
-         */
-        virtual bool isFramedPoseReachable(const std::string& chainName, const FramedPoseBasePtr& tcpPose, const Ice::Current& = Ice::Current()) const;
-
-        /**
-         * @brief Returns whether a given global pose is currently reachable by the TCP of the given robot node set.
-         * @details To determine whether a pose is reachable a reachability space for the given robot node set is 
-         *          required. If no such space exists, the function returns <it>false<\it>. 
-         *          Call \ref createReachabilitySpace first to ensure there is such a space.
-         * 
-         * @param chainName A name of a robot node set either defined in the robot model or previously defined via 
-         *                  \ref defineRobotNodeSet. 
-         * @param pose A global pose to check for reachability. 
-         * 
-         * @return True, if the pose is reachable by the TCP of the given chain. False, if it is not reachable or 
-         *         there is no reachability space for the given chain available.
-         */
-        virtual bool isPoseReachable(const std::string& chainName, const PoseBasePtr& tcpPose, const Ice::Current& = Ice::Current()) const;
-
-        /**
-         * @brief Loads the reachability space from the given file.
-         * @details If loading the reachability space succeeds, the reachability space is ready to be used after this function 
-         *          terminates. A reachability space can only be loaded if there is no reachability space for the respective 
-         *          robot node set yet.
-         * 
-         * @param filename Binary file containing a reachability space. Ensure that the path is valid and accessible from
-         *                 where this component is running.
-         * @return True iff loading the reachability space was successful.
-         */
-        virtual bool loadReachabilitySpace(const std::string& filename, const Ice::Current& = Ice::Current());
-
-        /**
-         * @brief Saves a previously created reachability space of the given robot node set.
-         * @details A reachability space for a robot node set can only be saved, if actually is one.
-         *          You can check whether a reachability space is available by calling \ref hasReachabilitySpace(robotNodeSet).
-         * 
-         * @param robotNodeSet The robot node set for which you wish to save the reachability space.
-         * @param filename The filename if the file(must be an accessible path for this component) you wish to save the space in.
-         * @return True iff saving was successful.
-         */
-        virtual bool saveReachabilitySpace(const std::string& robotNodeSet, const std::string& filename, const Ice::Current& = Ice::Current()) const;
-
-    protected:
-        /**
-         * Load and create a VirtualRobot::Robot instance from the RobotFileName
-         * property. 
-         */
-        virtual void onInitComponent();
-        virtual void onConnectComponent();
-        virtual void onDisconnectComponent();
-
-    private:
-        void computeIK(const std::string& robotNodeSetName, const Eigen::Matrix4f& tcpPose, 
-            armarx::CartesianSelection cs, NameValueMap& iksolution) const;
-        
-        void computeIK(VirtualRobot::RobotNodeSetPtr nodeSet, const Eigen::Matrix4f& tcpPose, 
-            armarx::CartesianSelection cs, NameValueMap& iksolution) const;
-
-        void computeIK(const std::string& robotNodeSetName, const Eigen::Matrix4f& tcpPose,
-            armarx::CartesianSelection cs, ExtendedIKResult& iksolution) const;
-
-        void computeIK(VirtualRobot::RobotNodeSetPtr nodeSet, const Eigen::Matrix4f& tcpPose,
-            armarx::CartesianSelection cs, ExtendedIKResult& iksolution) const;
-        
-        Eigen::Matrix4f toGlobalPose(const FramedPoseBasePtr& tcpPose) const;
-        Eigen::Matrix4f toReachabilityMapFrame(const FramedPoseBasePtr &tcpPose, const std::string &chainName) const;
-        
-        bool isReachable(const std::string& setName, const Eigen::Matrix4f& tcpPose) const;
-        
-        VirtualRobot::IKSolver::CartesianSelection convertCartesianSelection(armarx::CartesianSelection cs) const;
-
-        VirtualRobot::JacobiProvider::InverseJacobiMethod convertInverseJacobiMethod(armarx::InverseJacobiMethod aenum) const;
-
-        void synchRobot() const;
-
-        // Lock this mutex if you plan to modify the robot model
-        // Exception: When adding node sets we don't need to. 
-        // Invariant: We never delete node sets nor nodes!
-        mutable std::recursive_mutex _modifyRobotModelMutex;
-        // Lock this mutex if you are adding a node set, to ensure we do not add
-        // a similar node set at the same time.
-        mutable std::recursive_mutex _editRobotNodeSetsMutex;
-        // Lock this mutex if you are reading or editing the reachability cache.
-        mutable std::recursive_mutex _accessReachabilityCacheMutex;
-        // Needs to be locked when computing IKs! Internally thread safe though.
-        VirtualRobot::RobotPtr _robotModel;
-        std::string _robotFile;
-        RobotStateComponentInterfacePrx _robotStateComponentPrx;
-        SharedRobotInterfacePrx _synchronizedRobot;
-        DebugDrawerInterfacePrx debugDrawer;
-
-        // Reachability cache: not thread safe, always lock!
-        typedef std::map<std::string, VirtualRobot::WorkspaceRepresentationPtr> ReachabilityCacheType;
-        ReachabilityCacheType _reachabilities;
-        int _numIKTrials;
-    };
-
-}
-
-#endif
diff --git a/source/RobotAPI/components/RobotIK/test/CMakeLists.txt b/source/RobotAPI/components/RobotIK/test/CMakeLists.txt
deleted file mode 100644
index d3b627f916b7bb36a258bd5aa418c3607e468005..0000000000000000000000000000000000000000
--- a/source/RobotAPI/components/RobotIK/test/CMakeLists.txt
+++ /dev/null
@@ -1,2 +0,0 @@
-SET(LIBS ${LIBS} ArmarXCore RobotAPICore RobotAPIRobotIK RobotAPIRobotStateComponent)
-armarx_add_test(RobotIKTest RobotIKTest.cpp "${LIBS}")
\ No newline at end of file
diff --git a/source/RobotAPI/components/RobotIK/test/RobotIKTest.cpp b/source/RobotAPI/components/RobotIK/test/RobotIKTest.cpp
deleted file mode 100644
index 532c8e5795786921aa2f541aaaeeff109c5209b7..0000000000000000000000000000000000000000
--- a/source/RobotAPI/components/RobotIK/test/RobotIKTest.cpp
+++ /dev/null
@@ -1,647 +0,0 @@
-/*
- * This file is part of ArmarX.
- *
- * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
- *
- * ArmarX is distributed in the hope that it will be useful, but
- * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with this program. If not, see <http://www.gnu.org/licenses/>.
- *
- * @package    RobotAPI::ArmarXObjects::RobotIK
- * @author     Joshua Haustein ( joshua dot haustein at gmail dot com )
- * @date       2015
- * @copyright  http://www.gnu.org/licenses/gpl.txt
- *             GNU General Public License
- */
-
-#define BOOST_TEST_MODULE RobotAPI::ArmarXObjects::RobotIK
-
-#define ARMARX_BOOST_TEST
-
-#define EPSILON_POS 1.0f
-#define EPSILON_ROT 0.1f
-#define NUMBER_THREADS 10
-
-#include <RobotAPI/Test.h>
-#include <RobotAPI/components/RobotIK/RobotIK.h>
-#include <RobotAPI/components/RobotIK/test/RobotIKTestEnvironment.h>
-
-#include <VirtualRobot/RobotNodeSet.h>
-
-#include <iostream>
-#include <thread>
-// #include <chrono>
-// #include <ctime>
-#include <ratio>
-#include <random>
-
-bool comparePosition(const Eigen::Matrix4f& m1, const Eigen::Matrix4f& m2)
-{
-    bool equal = true;
-    for (size_t i = 0; i < 3; ++i)
-    {
-        equal &= (m1(i, 3) - m2(i, 3)) * (m1(i, 3) - m2(i, 3)) <= EPSILON_POS;
-    }
-
-    if (!equal)
-    {
-        BOOST_TEST_MESSAGE("Positions not equal for poses: " << m1 << ", " << m2);
-    }
-    return equal;
-}
-
-bool compareOrientation(const Eigen::Matrix4f& m1, const Eigen::Matrix4f& m2)
-{
-    bool equal = true;
-    for (size_t i = 0; i < 3; ++i)
-    {
-        for (size_t j = 0; j < 3; ++j)
-        {
-            equal &= (m1(i, j) - m2(i, j)) * (m1(i, j) - m2(i, j)) <= EPSILON_ROT;
-        }
-    }
-
-    if (!equal)
-    {
-        BOOST_TEST_MESSAGE("Poses not equal: " << m1 << ", " << m2);
-    }
-    return equal;
-}
-
-bool compareResults(const Eigen::Matrix4f& m1, const Eigen::Matrix4f& m2, CartesianSelection csel) 
-{
-    bool success;
-    if (csel == CartesianSelection::ePosition) 
-    {
-        success = comparePosition(m1, m2);
-    } 
-    else if (csel == CartesianSelection::eAll)
-    {
-        success = comparePosition(m1, m2) && compareOrientation(m1, m2);
-    }
-    else
-    { // TODO extend in case other values of CartesianSelection should be tested
-        success = false;
-    }
-    return success;
-}
-
-void synchRobot(VirtualRobot::RobotPtr localRobot, RobotStateComponentInterfacePrx robotState)
-{
-    VirtualRobot::RobotConfigPtr robotConfig = localRobot->getConfig();
-    SharedRobotInterfacePrx sharedRobot = robotState->getSynchronizedRobot();
-    BOOST_FOREACH(auto roboNode, robotConfig->getNodes())
-    {
-        SharedRobotNodeInterfacePrx sharedRoboNode = sharedRobot->getRobotNode(roboNode->getName());
-        float val = sharedRoboNode->getJointValue();
-        localRobot->getRobotNode(roboNode->getName())->setJointValue(val);
-    }
-}
-
-void testIKGlobalPose(const std::string& setName, PosePtr pose, bool& success, CartesianSelection csel,
-                     VirtualRobot::RobotPtr localRobot, RobotIKInterfacePrx robotIK, RobotStateComponentInterfacePrx sharedRobot)
-{
-    // Test component
-    synchRobot(localRobot, sharedRobot);
-    NameValueMap iksolution = robotIK->computeIKGlobalPose(setName, pose, csel);
-    
-    // Check validity of output
-    if (iksolution.size() > 0)
-    {
-        BOOST_TEST_MESSAGE("Pose " << pose);
-        BOOST_TEST_MESSAGE("Validating ik solution" << iksolution);
-        localRobot->setJointValues(iksolution);
-        BOOST_TEST_MESSAGE("configuration after setting:");
-        BOOST_FOREACH(auto ikEntry, iksolution)
-        {
-            float val = localRobot->getRobotNode(ikEntry.first)->getJointValue();
-            BOOST_TEST_MESSAGE(ikEntry.first << ": " << val);
-        }
-        VirtualRobot::RobotNodeSetPtr nodeset = localRobot->getRobotNodeSet(setName);
-        Eigen::Matrix4f tcpPose = nodeset->getTCP()->getGlobalPose();   
-        // BOOST_TEST_MESSAGE("Comparing tcp pose");
-        success = compareResults(tcpPose, pose->toEigen(), csel);
-    } else {
-        BOOST_TEST_MESSAGE("Empty solution");
-        success = false;
-    }
-}
-
-void testIKFramedPose(const std::string& setName, FramedPosePtr fpose, bool& success, CartesianSelection csel,
-                    VirtualRobot::RobotPtr localRobot, RobotIKInterfacePrx robotIK, RobotStateComponentInterfacePrx roboState)
-{
-    FramedPosePtr globalPose = fpose->toGlobal(roboState->getSynchronizedRobot());
-    Eigen::Matrix4f poseGlobal = globalPose->toEigen();
-
-    // Test component
-    synchRobot(localRobot, roboState);
-    NameValueMap iksolution = robotIK->computeIKFramedPose(setName, fpose, csel);
-    
-    // Check validity of output
-    if (iksolution.size() > 0)
-    {
-        VirtualRobot::RobotNodeSetPtr nodeset = localRobot->getRobotNodeSet(setName);
-        localRobot->setJointValues(iksolution);
-        Eigen::Matrix4f tcpPose = nodeset->getTCP()->getGlobalPose();   
-        
-        success = compareResults(tcpPose, poseGlobal, csel);
-    } else {
-        success = false;
-    }
-}
-
-void doGlobalPoseTests(const RobotIKTestEnvironment& testEnv, bool& finished) 
-{
-    // Create test input
-    std::string nodeSetName1("TorsoLeftArm");
-    Eigen::Matrix4f poseMatrix1;
-    poseMatrix1 << 1.0f, 0.0f, 0.0f, 400.0f,
-               0.0f, 1.0f, 0.0f, 600.0f,
-               0.0f, 0.0f, 1.0f, 900.0f,
-               0.0f, 0.0f, 0.0f, 1.0f;
-    PosePtr pose1 = new Pose(poseMatrix1);
-    // Create test input 2
-    std::string nodeSetName2 = "TorsoRightArm";
-    Eigen::Matrix4f poseMatrix2;
-    poseMatrix2 << 1.0f, 0.0f, 0.0f, 400.0f,
-               0.0f, -1.0f, 0.0f, 100.0f,
-               0.0f, 0.0f, -1.0f, 600.0f,
-               0.0f, 0.0f, 0.0f, 1.0f;
-    PosePtr pose2 = new Pose(poseMatrix2);
-
-    Eigen::Matrix4f unreachablePoseMatrix;
-    unreachablePoseMatrix << 1.0f, 0.0f, 0.0f, 1000.0f,
-               0.0f, 1.0f, 0.0f, 1000.0f,
-               0.0f, 0.0f, 1.0f, 1300.0f,
-               0.0f, 0.0f, 0.0f, 1.0f;
-    PosePtr unreachablePose = new Pose(unreachablePoseMatrix);
-
-    bool testSuccesses[3 * NUMBER_THREADS]; 
-    // bool testSuccesses[2 * NUMBER_THREADS];  
-    std::vector<std::thread> threads;
-    for (unsigned int tid = 0; tid < NUMBER_THREADS; ++tid) 
-    {
-        VirtualRobot::RobotPtr localRobot1 = testEnv._robotModel->clone("LocalRobot1");
-        threads.push_back(std::thread(testIKGlobalPose, std::ref(nodeSetName1), pose1, 
-                          std::ref(testSuccesses[3 * tid]), CartesianSelection::ePosition, localRobot1, testEnv._robotIK, testEnv._robotStateComponent));
-        VirtualRobot::RobotPtr localRobot2 = testEnv._robotModel->clone("LocalRobot2");
-        threads.push_back(std::thread(testIKGlobalPose, std::ref(nodeSetName2), pose2, 
-                          std::ref(testSuccesses[3 * tid + 1]), CartesianSelection::eAll, localRobot2, testEnv._robotIK, testEnv._robotStateComponent)); 
-        VirtualRobot::RobotPtr localRobot3 = testEnv._robotModel->clone("LocalRobot3");
-        threads.push_back(std::thread(testIKGlobalPose, std::ref(nodeSetName2), unreachablePose, 
-                          std::ref(testSuccesses[3 * tid + 2]), CartesianSelection::eAll, localRobot3, testEnv._robotIK, testEnv._robotStateComponent)); 
-    }
-    
-    for (size_t tid = 0; tid < threads.size(); ++tid)
-    {
-        threads[tid].join();
-    }
-
-    BOOST_CHECK(threads.size() == 3 * NUMBER_THREADS);
-    for (size_t tid = 0; tid < NUMBER_THREADS; ++tid) {
-        BOOST_CHECK(testSuccesses[3 * tid]);
-        BOOST_CHECK(testSuccesses[3 * tid + 1]);
-        BOOST_CHECK(!testSuccesses[3 * tid + 2]);
-    }
-    finished = true;
-}
-
-void doFramedPoseTests(const RobotIKTestEnvironment& testEnv, bool& finished)
-{
-    // Create test input
-    std::string nodeSetName("TorsoLeftArm");
-    std::string frame("TCP L");
-    Eigen::Matrix4f poseMatrix;
-    poseMatrix << 0.86603f, -0.5f, 0.0f, 50.0f,
-                  0.5f, 0.86603f, 0.0f, 60.0f,
-                  0.0f, 0.0f, 1.0f, 40.0f,
-                  0.0f, 0.0f, 0.0f, 1.0f;
-    FramedPosePtr pose = new FramedPose(poseMatrix, frame, testEnv._robotStateComponent->getRobotName());
-
-    bool testSuccesses[NUMBER_THREADS]; 
-    std::vector<std::thread> threads;
-    for (unsigned int tid = 0; tid < NUMBER_THREADS; ++tid) 
-    {
-        VirtualRobot::RobotPtr localRobot = testEnv._robotModel->clone("LocalRobot");
-        threads.push_back(std::thread(testIKFramedPose, std::ref(nodeSetName), pose, 
-                          std::ref(testSuccesses[tid]), CartesianSelection::eAll, localRobot, testEnv._robotIK, testEnv._robotStateComponent));
-    }
-    
-    for (size_t tid = 0; tid < threads.size(); ++tid)
-    {
-        threads[tid].join();
-    }
-
-    for (size_t tid = 0; tid < NUMBER_THREADS; ++tid) {
-        BOOST_CHECK(testSuccesses[tid]);
-    }
-    finished = true;
-}
-
-void doReachabilityTests(const RobotIKTestEnvironment& testEnv, bool& finished)
-{
-    std::string nodeSetName("TorsoLeftArm");
-    std::string frame("TCP L");
-    std::string baseFrame("Armar3_Base");
-  
-    // Define two global poses  
-    // First, a reachable pose
-    Eigen::Matrix4f matrix;
-    matrix << 0.275582f,  0.950628f,  0.142693f,  -363.636f,
-              0.892777f, -0.198076f, -0.404616f,   181.818f,
-              -0.356376f,  0.238898f, -0.903285f,   727.273f,
-              1.0f,         1.0f,         1.0f,         1.0f;
-    PosePtr reachablePose = new Pose(matrix);
-    // Second, a unreachable pose
-    matrix << 1.0f, 0.0f, 0.0f, 1000.0f,
-               0.0f, 1.0f, 0.0f, 1000.0f,
-               0.0f, 0.0f, 1.0f, 1300.0f,
-               0.0f, 0.0f, 0.0f, 1.0f;
-    PosePtr unreachablePose = new Pose(matrix);
-    // Now define two framed poses
-    // Again, first reachable
-    // matrix << 1.0f, 0.0f, 0.0f, 5.0f,
-    //           0.0f, 1.0f, 0.0f, 6.0f,
-    //           0.0f, 0.0f, 1.0f, 4.0f,
-    //           0.0f, 0.0f, 0.0f, 1.0f;
-    // FramedPosePtr reachableFramedPose = new FramedPose(matrix, frame, testEnv._robotStateComponent->getRobotName());
-    // and an unreachable
-    matrix << 0.86603f, -0.5f, 0.0f, 1000.0f,
-              0.5f, 0.86603f, 0.0f, 600.0f,
-              0.0f, 0.0f, 1.0f, 400.0f,
-              0.0f, 0.0f, 0.0f, 1.0f;
-    FramedPosePtr unreachableFramedPose = new FramedPose(matrix, frame, testEnv._robotStateComponent->getRobotName());
-    
-    // To create a reachability space we need workspace bounds.
-    WorkspaceBounds minBounds;
-    minBounds.x = -1000.0f;
-    minBounds.y = -1000.0f;
-    minBounds.z = -1000.0f;
-    minBounds.ro = -3.15f;
-    minBounds.pi = -3.15f;
-    minBounds.ya = -3.15f;
-
-    WorkspaceBounds maxBounds;
-    maxBounds.x = 1000.0f;
-    maxBounds.y = 1000.0f;
-    maxBounds.z = 1000.0f;
-    maxBounds.ro = 3.15f;
-    maxBounds.pi = 3.15f;
-    maxBounds.ya = 3.15f;
-
-    // Now start testing
-    // First, make a sanity check on hasReachabilitySpace
-    BOOST_CHECK(!testEnv._robotIK->hasReachabilitySpace(nodeSetName));
-
-    // We don't have a reachability space yet, so isPoseReachable should always return false.
-    BOOST_CHECK(!testEnv._robotIK->isPoseReachable(nodeSetName, reachablePose));
-    BOOST_CHECK(!testEnv._robotIK->isPoseReachable(nodeSetName, unreachablePose));
-    // BOOST_CHECK(!testEnv._robotIK->isFramedPoseReachable(nodeSetName, reachableFramedPose));
-    BOOST_CHECK(!testEnv._robotIK->isFramedPoseReachable(nodeSetName, unreachableFramedPose));
-
-    bool createdReachabilitySpace = testEnv._robotIK->createReachabilitySpace(nodeSetName, baseFrame, 200.0f, 0.3f, minBounds, maxBounds, 1000000);
-    // This should work
-    BOOST_CHECK(createdReachabilitySpace);
-
-    // Now we should have a reachability space:
-    BOOST_CHECK(testEnv._robotIK->hasReachabilitySpace(nodeSetName));
-
-    // Finally test the poses:
-    BOOST_CHECK(testEnv._robotIK->isPoseReachable(nodeSetName, reachablePose));
-    BOOST_CHECK(!testEnv._robotIK->isPoseReachable(nodeSetName, unreachablePose));
-    // BOOST_CHECK(testEnv._robotIK->isFramedPoseReachable(nodeSetName, reachableFramedPose));
-    BOOST_CHECK(!testEnv._robotIK->isFramedPoseReachable(nodeSetName, unreachableFramedPose));
-
-    std::string savepath(testEnv._spaceSavePath + "testReachabilitySpace.bin");
-    BOOST_TEST_MESSAGE(savepath);
-    BOOST_CHECK(testEnv._robotIK->saveReachabilitySpace(nodeSetName, savepath));
-    finished = true;
-
-}
-
-void doLoadReachabilityTest(const RobotIKTestEnvironment& testEnv, bool& finished)
-{
-    std::string nodeSetName("TorsoLeftArm");
-    std::string frame("TCP L");
-    std::string baseFrame("Armar3_Base");
-  
-    // Define two global poses  
-    // First, a reachable pose
-    Eigen::Matrix4f matrix;
-    matrix << 0.275582f,  0.950628f,  0.142693f,  -363.636f,
-              0.892777f, -0.198076f, -0.404616f,   181.818f,
-              -0.356376f,  0.238898f, -0.903285f,   727.273f,
-              1.0f,         1.0f,         1.0f,         1.0f;
-    PosePtr reachablePose = new Pose(matrix);
-    // Second, a unreachable pose
-    matrix << 1.0f, 0.0f, 0.0f, 1000.0f,
-               0.0f, 1.0f, 0.0f, 1000.0f,
-               0.0f, 0.0f, 1.0f, 1300.0f,
-               0.0f, 0.0f, 0.0f, 1.0f;
-    PosePtr unreachablePose = new Pose(matrix);
-
-    matrix << 0.86603f, -0.5f, 0.0f, 1000.0f,
-              0.5f, 0.86603f, 0.0f, 600.0f,
-              0.0f, 0.0f, 1.0f, 400.0f,
-              0.0f, 0.0f, 0.0f, 1.0f;
-    FramedPosePtr unreachableFramedPose = new FramedPose(matrix, frame, testEnv._robotStateComponent->getRobotName());
-    
-    // To create a reachability space we need workspace bounds.
-    WorkspaceBounds minBounds;
-    minBounds.x = -1000.0f;
-    minBounds.y = -1000.0f;
-    minBounds.z = -1000.0f;
-    minBounds.ro = -3.15f;
-    minBounds.pi = -3.15f;
-    minBounds.ya = -3.15f;
-
-    WorkspaceBounds maxBounds;
-    maxBounds.x = 1000.0f;
-    maxBounds.y = 1000.0f;
-    maxBounds.z = 1000.0f;
-    maxBounds.ro = 3.15f;
-    maxBounds.pi = 3.15f;
-    maxBounds.ya = 3.15f;
-
-    // Now start testing
-    testEnv._robotIK->createReachabilitySpace(nodeSetName, baseFrame, 200.0f, 0.3f, minBounds, maxBounds, 1000000);
-    
-    // Now we should have a reachability space:
-    BOOST_CHECK(testEnv._robotIK->hasReachabilitySpace(nodeSetName));
-
-    // Finally test the poses:
-    BOOST_CHECK(testEnv._robotIK->isPoseReachable(nodeSetName, reachablePose));
-    BOOST_CHECK(!testEnv._robotIK->isPoseReachable(nodeSetName, unreachablePose));
-    // BOOST_CHECK(testEnv._robotIK->isFramedPoseReachable(nodeSetName, reachableFramedPose));
-    BOOST_CHECK(!testEnv._robotIK->isFramedPoseReachable(nodeSetName, unreachableFramedPose));
-
-    finished = true;
-}
-
-void doDefineNodeSetTests(const RobotIKTestEnvironment& testEnv, bool& finished)
-{
-    std::string setName1("TestSet1");
-    std::string tcpName("TCP L");
-    std::string rootNode("Platform");
-    NodeNameList jointList;
-    jointList.push_back("Shoulder 1 L");
-    jointList.push_back("Shoulder 2 L");
-    jointList.push_back("Upperarm L");
-    jointList.push_back("Elbow L");
-    jointList.push_back("Underarm L");
-
-    VirtualRobot::RobotPtr localRobot = testEnv._robotModel->clone("MyLocalRobot");
-    
-    bool defineSuccessful = testEnv._robotIK->defineRobotNodeSet(setName1, jointList, tcpName, rootNode);
-    BOOST_CHECK(defineSuccessful);
-
-    VirtualRobot::RobotNodeSet::createRobotNodeSet(localRobot, setName1, jointList, rootNode, tcpName, true);
-
-    Eigen::Matrix4f poseMatrix1;
-    poseMatrix1 << -0.258819f, -0.965926f, 0.0f, -315.0f,
-                0.0f, 0.0f, 1.0f, 550.0f,
-                -0.965926f, 0.258819f, 0.0f, 1077.5f,
-                0.0f, 0.0f, 0.0f, 1.0f;
-
-    PosePtr pose1 = new Pose(poseMatrix1);
-   
-    bool ikSuccess = false;
-    testIKGlobalPose(setName1, pose1, ikSuccess, CartesianSelection::ePosition, localRobot, testEnv._robotIK, testEnv._robotStateComponent);
-    BOOST_CHECK(ikSuccess);
-
-    // Redefine should always return true.
-    BOOST_CHECK(testEnv._robotIK->defineRobotNodeSet(setName1, jointList, tcpName, rootNode));
-
-    // Redefine with different parameters, however, always false
-    NodeNameList modifiedJointList(jointList);
-    modifiedJointList.pop_back();
-    BOOST_CHECK(!testEnv._robotIK->defineRobotNodeSet(setName1, modifiedJointList, tcpName, rootNode));
-    std::string tcpName2("TCP R");
-    BOOST_CHECK(!testEnv._robotIK->defineRobotNodeSet(setName1, jointList, tcpName2, rootNode));
-    std::string rootNode2("Shoulder 1 L");
-    BOOST_CHECK(!testEnv._robotIK->defineRobotNodeSet(setName1, jointList, tcpName, rootNode2));
-    finished = true;
-}
-
-void doRobotIKComputeCoMIKTests(const RobotIKTestEnvironment& testEnv, bool& finished)
-{
-    std::string completeRobotSetname("Robot");
-    CoMIKDescriptor comdesc;
-    comdesc.priority = 0;
-    comdesc.gx = 4.0;
-    comdesc.gy = 45.0;
-    comdesc.robotNodeSetBodies = completeRobotSetname;
-    comdesc.tolerance = 2.0f;
-    comdesc.coordSysName = "Armar3_Base";
-    std::string jointsSetName("TorsoBothArms");
-    VirtualRobot::RobotPtr localRobot = testEnv._robotModel->clone("MyLocalRobot");
-    
-    NameValueMap ikSolution = testEnv._robotIK->computeCoMIK(jointsSetName, comdesc);
-    VirtualRobot::RobotNodeSetPtr robotNodeSet = localRobot->getRobotNodeSet(completeRobotSetname);
-    
-    localRobot->setJointValues(ikSolution);
-    Eigen::Vector3f resultCoM = robotNodeSet->getCoM();
-
-    // BOOST_TEST_MESSAGE("desired com " << comdesc.gx << " " << comdesc.gy);
-    // BOOST_TEST_MESSAGE("is com " << resultCoM[0] << " " << resultCoM[1]);
-    BOOST_CHECK((comdesc.gx - resultCoM[0])*(comdesc.gx - resultCoM[0]) <= comdesc.tolerance * comdesc.tolerance);
-    BOOST_CHECK((comdesc.gy - resultCoM[1])*(comdesc.gy - resultCoM[1]) <= comdesc.tolerance * comdesc.tolerance);
-    finished = true;
-}
-
-void doRobotIKComputeHierarchicalDeltaIKTests(const RobotIKTestEnvironment& testEnv, bool& finished)
-{
-    std::string jointsSetName("TorsoBothArms");
-    IKTasks ikTasks;
-    // Set up a task for the left arm first
-    DifferentialIKDescriptor leftArmGoal;
-    leftArmGoal.priority = 2;
-    leftArmGoal.tcpName = "TCP L";
-    leftArmGoal.csel = CartesianSelection::ePosition;
-    leftArmGoal.ijm = InverseJacobiMethod::eSVD;
-    Eigen::Matrix4f poseMatrix1;
-    poseMatrix1 << 1.0f, 0.0f, 0.0f, -285.0f,
-               0.0f, 1.0f, 0.0f, 540.0f,
-               0.0f, 0.0f, 1.0f, 1125.0f,
-               0.0f, 0.0f, 0.0f, 1.0f;
-    PosePtr pose1 = new Pose(poseMatrix1);
-    leftArmGoal.tcpGoal = pose1;
-    ikTasks.push_back(leftArmGoal);
-    VirtualRobot::RobotPtr localRobot = testEnv._robotModel->clone("MyLocalRobot");
-
-    // now let's set up a task for the right arm
-    DifferentialIKDescriptor rightArmGoal;
-    rightArmGoal.priority = 1;
-    rightArmGoal.tcpName = "TCP R";
-    rightArmGoal.csel = CartesianSelection::ePosition;
-    rightArmGoal.ijm = InverseJacobiMethod::eSVD;
-    Eigen::Matrix4f poseMatrix2;
-    poseMatrix2 << 1.0f, 0.0f, 0.0f, 400.0f,
-               0.0f, 1.0f, 0.0f, 100.0f,
-               0.0f, 0.0f, 1.0f, 900.0f,
-               0.0f, 0.0f, 0.0f, 1.0f;
-    PosePtr pose2 = new Pose(poseMatrix2);
-    rightArmGoal.tcpGoal = pose2;
-    ikTasks.push_back(rightArmGoal);
-
-    // finally let's add a center of mass task
-    std::string completeRobotSetname("Robot");
-    CoMIKDescriptor comdesc;
-    comdesc.priority = 0;
-    comdesc.gx = 4.0;
-    comdesc.gy = 45.0;
-    comdesc.robotNodeSetBodies = completeRobotSetname;
-    comdesc.tolerance = 2.0f;
-    comdesc.coordSysName = "Armar3_Base";
-
-    float stepSize = 0.1;
-    NameValueMap ikGradient;
-    BOOST_TEST_MESSAGE(poseMatrix1);
-    while (!compareResults(poseMatrix1, localRobot->getRobotNodeSet("TorsoLeftArm")->getTCP()->getGlobalPose(), CartesianSelection::ePosition)
-        || !compareResults(poseMatrix2, localRobot->getRobotNodeSet("TorsoRightArm")->getTCP()->getGlobalPose(), CartesianSelection::ePosition))
-    {
-        ikGradient = testEnv._robotIK->computeHierarchicalDeltaIK(jointsSetName, ikTasks, comdesc, stepSize, true, true);
-        BOOST_CHECK(ikGradient.size() > 0);
-        
-        VirtualRobot::RobotNodeSetPtr rns = localRobot->getRobotNodeSet(jointsSetName);
-        const std::vector<VirtualRobot::RobotNodePtr> robotNodes = rns->getAllRobotNodes();
-        
-        NameValueMap newConfig;
-        BOOST_FOREACH(auto node, robotNodes) 
-        {
-            float val = node->getJointValue();
-            float delta = ikGradient.find(node->getName())->second;
-            newConfig.insert(NameValueMap::value_type(node->getName(), val + delta));
-        }
-        localRobot->setJointValues(newConfig);
-        testEnv._robotStateComponent->reportJointAngles(newConfig, true);
-    }
-
-    BOOST_CHECK(compareResults(poseMatrix1, localRobot->getRobotNodeSet("TorsoLeftArm")->getTCP()->getGlobalPose(), CartesianSelection::ePosition));
-    BOOST_CHECK(compareResults(poseMatrix2, localRobot->getRobotNodeSet("TorsoRightArm")->getTCP()->getGlobalPose(), CartesianSelection::ePosition));
-
-    Eigen::Vector3f resultCoM = localRobot->getRobotNodeSet(completeRobotSetname)->getCoM();
-    BOOST_TEST_MESSAGE("desired com " << comdesc.gx << " " << comdesc.gy);
-    BOOST_TEST_MESSAGE("is com " << resultCoM[0] << " " << resultCoM[1]);
-    
-    BOOST_CHECK((comdesc.gx - resultCoM[0])*(comdesc.gx - resultCoM[0]) <= comdesc.tolerance * comdesc.tolerance);
-    BOOST_CHECK((comdesc.gy - resultCoM[1])*(comdesc.gy - resultCoM[1]) <= comdesc.tolerance * comdesc.tolerance);
-    finished = true;
-}
-
-BOOST_AUTO_TEST_CASE(RobotIKGlobalPoseTest)
-{
-    // Create test environment first
-    RobotIKTestEnvironment testEnv("RobotIKGlobalPoseTest");
-    bool finished = false;
-    doGlobalPoseTests(testEnv, finished);
-}
-
-BOOST_AUTO_TEST_CASE(RobotIKFramedPoseTest)
-{
-    // Create test environment first
-    RobotIKTestEnvironment testEnv("RobotIKFramedPoseTest");
-    bool finished = false;
-    doFramedPoseTests(testEnv, finished);
-}
-
-BOOST_AUTO_TEST_CASE(RobotIKReachabilityTest)
-{
-    RobotIKTestEnvironment testEnv("RobotIKReachabilityTest");
-    bool finished = false;
-    doReachabilityTests(testEnv, finished);
-}
-
-BOOST_AUTO_TEST_CASE(RobotIKDefineRobotSetTest)
-{
-    RobotIKTestEnvironment testEnv("RobotIKDefineNodeTest");
-    bool finished = false;
-    doDefineNodeSetTests(testEnv, finished);
-}
-
-BOOST_AUTO_TEST_CASE(RobotIKComputeCoMIKTest)
-{
-    RobotIKTestEnvironment testEnv("RobotIKComputeCoMIKTest");
-    bool finished = false;
-    doRobotIKComputeCoMIKTests(testEnv, finished);
-}
-
-BOOST_AUTO_TEST_CASE(RobotIKComputeHierarchicalDeltaIK)
-{
-    RobotIKTestEnvironment testEnv("RobotIKComputeHierarchicalDeltaIK");
-    bool finished = false;
-    doRobotIKComputeHierarchicalDeltaIKTests(testEnv, finished);
-}
-
-BOOST_AUTO_TEST_CASE(RobotIKLoadReachabilitySpaceTest)
-{
-    RobotIKTestEnvironment testEnv("RobotIKLoadReachabilitySpaceTest", true);
-    std::string nodeSetName("TorsoLeftArm");
-    BOOST_CHECK(testEnv._robotIK->hasReachabilitySpace(nodeSetName));
-}
-
-// BOOST_AUTO_TEST_CASE(RobotIKLoadTest)
-// {
-//     RobotIKTestEnvironment testEnv("RobotIKLoadTest");
-//     // set up time stuff
-//     std::chrono::steady_clock::time_point startPoint = std::chrono::steady_clock::now();
-//     std::chrono::duration<double> time_span = std::chrono::duration_cast< std::chrono::duration<double> >(std::chrono::steady_clock::now() - startPoint);
-//     // set up random generators
-//     std::default_random_engine generator; //1234567890
-//     // std::uniform_int_distribution<int> uniDistribution(0, 5);
-//     std::uniform_int_distribution<int> uniDistribution(0, 5); 
-//     // some bookkeeping data structures
-//     std::vector<std::thread> threads;
-//     bool hikStarted = false;
-//     bool hikFinished = false;
-//     bool dummyFinished = false;
-
-//     while (time_span.count() < 120.0)
-//     {
-//         int testNumber = uniDistribution(generator);
-//         switch (testNumber)
-//         {
-//             case 0:
-//                 threads.push_back(std::thread(doGlobalPoseTests, std::ref(testEnv), std::ref(dummyFinished)));
-//                 break;
-//             case 1:
-//                 threads.push_back(std::thread(doFramedPoseTests, std::ref(testEnv), std::ref(dummyFinished)));
-//                 break;
-//             case 2:
-//                 threads.push_back(std::thread(doLoadReachabilityTest, std::ref(testEnv), std::ref(dummyFinished)));
-//                 break;
-//             case 3:
-//                 threads.push_back(std::thread(doDefineNodeSetTests, std::ref(testEnv), std::ref(dummyFinished)));
-//                 break;
-//             case 4:
-//                 threads.push_back(std::thread(doRobotIKComputeCoMIKTests, std::ref(testEnv), std::ref(dummyFinished)));
-//                 break;
-//             case 5:
-//                 if (!hikStarted)
-//                 {
-//                     hikStarted = true;
-//                     // threads.push_back(std::thread(doRobotIKComputeHierarchicalDeltaIKTests, std::ref(testEnv), std::ref(hikFinished)));
-//                 }
-//                 break;
-//         }
-//         if (hikFinished)
-//         {
-//             hikStarted = false;
-//             hikFinished = false;
-//         }
-//         std::this_thread::sleep_for(std::chrono::seconds(uniDistribution(generator)));
-//         time_span = std::chrono::duration_cast< std::chrono::duration<double> >(std::chrono::steady_clock::now() - startPoint);
-//     }
-
-//     for (size_t i = 0; i < threads.size(); ++i)
-//     {
-//         threads[i].join();
-//     }
-// }
diff --git a/source/RobotAPI/components/RobotIK/test/RobotIKTestEnvironment.h b/source/RobotAPI/components/RobotIK/test/RobotIKTestEnvironment.h
deleted file mode 100644
index 5f704e7810d967f4aca5433fb8383783304bb3c6..0000000000000000000000000000000000000000
--- a/source/RobotAPI/components/RobotIK/test/RobotIKTestEnvironment.h
+++ /dev/null
@@ -1,88 +0,0 @@
-/*
-* This file is part of ArmarX.
-*
-* ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
-*
-* ArmarX is distributed in the hope that it will be useful, but
-* WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
-*
-* You should have received a copy of the GNU General Public License
-* along with this program. If not, see <http://www.gnu.org/licenses/>.
-*
-* @package    RobotAPI::ArmarXObjects::RobotIKTestEnvironment
-* @author     Joshua Haustein ( joshua dot haustein at gmail dot com)
-* @date       2015
-* @copyright  http://www.gnu.org/licenses/gpl.txt
-*             GNU General Public License
-*/
-
-#include <RobotAPI/components/RobotIK/RobotIK.h>
-#include <RobotAPI/components/RobotState/RobotStateComponent.h>
-
-#include <Core/core/test/IceTestHelper.h>
-#include <Core/core/application/Application.h>
-#include <Core/core/system/FactoryCollectionBase.h>
-
-#include <VirtualRobot/XML/RobotIO.h>
-
-#include <RobotAPI/Test.h>
-
-using namespace armarx;
-
-class RobotIKTestEnvironment
-{
-public:
-    RobotIKTestEnvironment(const std::string& testName, bool loadSpaces = false, int registryPort = 11220, bool addObjects = true)
-    {
-        Ice::PropertiesPtr properties = Ice::createProperties();
-        armarx::Application::LoadDefaultConfig(properties);
-        std::string robotFilename = test::getCmakeValue("PROJECT_DATA_DIR") + "/RobotAPI/tests/robotmodel/ArmarIII.xml";
-        properties->setProperty("ArmarX.RobotStateComponent.RobotFileName", robotFilename);
-        properties->setProperty("ArmarX.RobotStateComponent.ObjectName", "RobotStateComponent");
-        properties->setProperty("ArmarX.RobotStateComponent.AgentName", "Armar3");
-        properties->setProperty("ArmarX.RobotStateComponent.RobotNodeSetName", "Robot");
-        properties->setProperty("ArmarX.RobotIK.RobotFileName", robotFilename);
-        properties->setProperty("ArmarX.RobotIK.RobotStateComponentName", "RobotStateComponent");
-        
-        _spaceSavePath = test::getCmakeValue("PROJECT_BINARY_DIR") + "/Testing/Temporary/spaces/";
-        
-        if (loadSpaces)
-        {
-            properties->setProperty("ArmarX.RobotIK.ReachabilitySpacesFolder", _spaceSavePath);
-            properties->setProperty("ArmarX.RobotIK.InitialReachabilitySpaces", "testReachabilitySpace.bin");
-        }
-
-        _iceTestHelper = new IceTestHelper(registryPort, registryPort + 1);
-        _iceTestHelper->startEnvironment();
-        
-        _manager = new TestArmarXManager(testName, _iceTestHelper->getCommunicator(), properties);
-
-        if (addObjects)
-        {
-            _robotStateComponent = _manager->createComponentAndRun<RobotStateComponent, RobotStateComponentInterfacePrx>("ArmarX", "RobotStateComponent");
-            _robotIK = _manager->createComponentAndRun<RobotIK, RobotIKInterfacePrx>("ArmarX", "RobotIK");
-        }
-
-        _robotModel = VirtualRobot::RobotIO::loadRobot(robotFilename, VirtualRobot::RobotIO::eStructure);
-    }
-
-    ~RobotIKTestEnvironment()
-    {
-        _manager->shutdown();
-    }
-
-    RobotStateComponentInterfacePrx _robotStateComponent;
-    RobotIKInterfacePrx _robotIK;
-    TestArmarXManagerPtr _manager;
-    IceTestHelperPtr _iceTestHelper;
-    VirtualRobot::RobotPtr _robotModel;
-    std::string _spaceSavePath;
-};
-
-typedef boost::shared_ptr<RobotIKTestEnvironment> RobotIKTestEnvironmentPtr;
-
diff --git a/source/RobotAPI/components/RobotState/CMakeLists.txt b/source/RobotAPI/components/RobotState/CMakeLists.txt
index 1f6c68863792b14286f039b47c6dd498ab377061..fa39860ac77df6f7e32fd8d86392cd06ba2537b6 100644
--- a/source/RobotAPI/components/RobotState/CMakeLists.txt
+++ b/source/RobotAPI/components/RobotState/CMakeLists.txt
@@ -10,8 +10,8 @@ include_directories(${Eigen3_INCLUDE_DIR})
 include_directories(${Simox_INCLUDE_DIRS})
 
 set(LIB_NAME       RobotAPIRobotStateComponent)
-set(LIB_VERSION    0.1.0)
-set(LIB_SOVERSION  0)
+
+
 
 set(LIBS ArmarXCore RobotAPICore)
 
@@ -25,4 +25,4 @@ set(LIB_HEADERS
         SharedRobotServants.h
 )
 
-armarx_add_library("${LIB_NAME}" "${LIB_VERSION}" "${LIB_SOVERSION}" "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
+armarx_add_library("${LIB_NAME}"  "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
diff --git a/source/RobotAPI/components/RobotState/RobotStateComponent.cpp b/source/RobotAPI/components/RobotState/RobotStateComponent.cpp
index b874c7b9c903de746cf3d436232836159dfbd862..10319136430a482f414e9773c574edbabe62b07d 100644
--- a/source/RobotAPI/components/RobotState/RobotStateComponent.cpp
+++ b/source/RobotAPI/components/RobotState/RobotStateComponent.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    RobotStateComponent::
  * @author     ( at kit dot edu)
  * @date
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -28,10 +27,10 @@
 #include <VirtualRobot/RobotNodeSet.h>
 #include <boost/format.hpp>
 #include <boost/foreach.hpp>
-#include <Core/core/system/ArmarXDataPath.h>
-#include <Core/core/ArmarXManager.h>
-#include <Core/core/ArmarXObjectScheduler.h>
-#include <Core/core/application/Application.h>
+#include <ArmarXCore/core/system/ArmarXDataPath.h>
+#include <ArmarXCore/core/ArmarXManager.h>
+#include <ArmarXCore/core/ArmarXObjectScheduler.h>
+#include <ArmarXCore/core/application/Application.h>
 
 using namespace std;
 using namespace VirtualRobot;
@@ -52,7 +51,7 @@ namespace armarx
                 _synchronizedPrx->unref();
             }
         }
-        catch(...)
+        catch (...)
         {}
     }
 
@@ -60,13 +59,15 @@ namespace armarx
     void RobotStateComponent::onInitComponent()
     {
         relativeRobotFile = getProperty<std::string>("RobotFileName").getValue();
-        if (!ArmarXDataPath::getAbsolutePath(relativeRobotFile,robotFile))
+
+        if (!ArmarXDataPath::getAbsolutePath(relativeRobotFile, robotFile))
         {
             throw UserException("Could not find robot file " + robotFile);
         }
 
         this->_synchronized = VirtualRobot::RobotIO::loadRobot(robotFile, VirtualRobot::RobotIO::eStructure);
         _synchronized->setName(getProperty<std::string>("AgentName").getValue());
+
         if (this->_synchronized)
         {
             ARMARX_VERBOSE << "Loaded robot from file " << robotFile << ". Robot name: " << this->_synchronized->getName();
@@ -79,15 +80,16 @@ namespace armarx
         string robotNodeSetName = getProperty<std::string>("RobotNodeSetName").getValue();
 
 
-        if(robotNodeSetName == "")
+        if (robotNodeSetName == "")
         {
             throw UserException("RobotNodeSet not defined");
         }
 
         VirtualRobot::RobotNodeSetPtr rns =  this->_synchronized->getRobotNodeSet(robotNodeSetName);
+
         if (!rns)
         {
-             throw UserException("RobotNodeSet not defined");
+            throw UserException("RobotNodeSet not defined");
         }
 
         vector<RobotNodePtr> nodes = rns->getAllRobotNodes();
@@ -129,20 +131,24 @@ namespace armarx
     }
 
 
-    SharedRobotInterfacePrx RobotStateComponent::getSynchronizedRobot(const Current & current) const
+    SharedRobotInterfacePrx RobotStateComponent::getSynchronizedRobot(const Current& current) const
     {
         if (!this->_synchronizedPrx)
         {
             throw NotInitializedException("Shared Robot is NULL", "getSynchronizedRobot");
         }
+
         return this->_synchronizedPrx;
     }
 
 
-    SharedRobotInterfacePrx RobotStateComponent::getRobotSnapshot(const string & time,const Current & current)
+    SharedRobotInterfacePrx RobotStateComponent::getRobotSnapshot(const string& time, const Current& current)
     {
-        if(!_synchronized)
+        if (!_synchronized)
+        {
             throw NotInitializedException("Shared Robot is NULL", "getRobotSnapshot");
+        }
+
         auto clone = this->_synchronized->clone(_synchronized->getName());
 
         SharedRobotInterfacePtr p = new SharedRobotServant(clone);
@@ -154,15 +160,15 @@ namespace armarx
 
     void RobotStateComponent::reportJointAngles(const NameValueMap& jointAngles, bool aValueChanged, const Current& c)
     {
-//        IceUtil::Time start = IceUtil::Time::now();
-        if(aValueChanged)
+        //        IceUtil::Time start = IceUtil::Time::now();
+        if (aValueChanged)
         {
             {
                 WriteLockPtr lock = _synchronized->getWriteLock();
 
                 std::vector<float> jv;
                 std::vector< RobotNodePtr > nodes;
-                BOOST_FOREACH(NameValueMap::value_type namedAngle, jointAngles )
+                BOOST_FOREACH(NameValueMap::value_type namedAngle, jointAngles)
                 {
                     RobotNodePtr node = this->_synchronized->getRobotNode(namedAngle.first);
                     nodes.push_back(node);
@@ -170,52 +176,64 @@ namespace armarx
                 }
                 _synchronized->setJointValues(nodes, jv);
             }
-            if(robotStateObs)
+
+            if (robotStateObs)
+            {
                 robotStateObs->updatePoses();
+            }
         }
-        if(_sharedRobotServant)
+
+        if (_sharedRobotServant)
+        {
             _sharedRobotServant->setTimestamp(IceUtil::Time::now());
-//        ARMARX_VERBOSE << deactivateSpam(2) << "my duration: " << (IceUtil::Time::now() - start).toMicroSecondsDouble() << " ms";
+        }
+
+        //        ARMARX_VERBOSE << deactivateSpam(2) << "my duration: " << (IceUtil::Time::now() - start).toMicroSecondsDouble() << " ms";
 
 
     }
 
     std::string RobotStateComponent::getRobotFilename(const Ice::Current&) const
-    {		
+    {
         return relativeRobotFile;
     }
 
-    std::vector<string> RobotStateComponent::getArmarXPackages(const Current &) const
+    std::vector<string> RobotStateComponent::getArmarXPackages(const Current&) const
     {
         std::vector<string> result;
         auto packages = armarx::Application::GetProjectDependencies();
         packages.push_back(Application::GetProjectName());
-        for(const std::string &projectName : packages)
+
+        for (const std::string& projectName : packages)
         {
-            if(projectName.empty())
+            if (projectName.empty())
+            {
                 continue;
+            }
 
             result.push_back(projectName);
         }
 
         return result;
     }
-	
-    void RobotStateComponent::reportControlModeChanged(const NameControlModeMap& jointModes,  bool aValueChanged,const Current& c){}
-    void RobotStateComponent::reportJointVelocities(const NameValueMap& jointVelocities,  bool aValueChanged,const Current& c)
+
+    void RobotStateComponent::reportControlModeChanged(const NameControlModeMap& jointModes,  bool aValueChanged, const Current& c) {}
+    void RobotStateComponent::reportJointVelocities(const NameValueMap& jointVelocities,  bool aValueChanged, const Current& c)
     {
-        if(robotStateObs)
+        if (robotStateObs)
+        {
             robotStateObs->updateNodeVelocities(jointVelocities);
+        }
     }
-    void RobotStateComponent::reportJointTorques(const NameValueMap& jointTorques,  bool aValueChanged,const Current& c){}
+    void RobotStateComponent::reportJointTorques(const NameValueMap& jointTorques,  bool aValueChanged, const Current& c) {}
 
-    void RobotStateComponent::reportJointAccelerations(const NameValueMap &jointAccelerations, bool aValueChanged, const Current &c)
+    void RobotStateComponent::reportJointAccelerations(const NameValueMap& jointAccelerations, bool aValueChanged, const Current& c)
     {
 
     }
-    void RobotStateComponent::reportJointCurrents(const NameValueMap& jointCurrents,  bool aValueChanged,const Current& c){}
-    void RobotStateComponent::reportJointMotorTemperatures(const NameValueMap& jointMotorTemperatures, bool aValueChanged, const Current& c){}
-    void RobotStateComponent::reportJointStatuses(const NameStatusMap& jointStatuses, bool aValueChanged, const Current& c){}
+    void RobotStateComponent::reportJointCurrents(const NameValueMap& jointCurrents,  bool aValueChanged, const Current& c) {}
+    void RobotStateComponent::reportJointMotorTemperatures(const NameValueMap& jointMotorTemperatures, bool aValueChanged, const Current& c) {}
+    void RobotStateComponent::reportJointStatuses(const NameStatusMap& jointStatuses, bool aValueChanged, const Current& c) {}
 
     /*void RobotStateComponent::reportPlatformPose(float currentPlatformPositionX, float currentPlatformPositionY, float currentPlatformRotation, const Ice::Current& c)
     {
@@ -252,12 +270,16 @@ namespace armarx
         robotStateObs = observer;
     }
 
-    string RobotStateComponent::getRobotName(const Current &) const
+    string RobotStateComponent::getRobotName(const Current&) const
     {
-        if(_synchronized)
+        if (_synchronized)
+        {
             return _synchronizedPrx->getName();
+        }
         else
+        {
             throw NotInitializedException("Robot Ptr is NULL", "getName");
+        }
 
     }
 }
diff --git a/source/RobotAPI/components/RobotState/RobotStateComponent.h b/source/RobotAPI/components/RobotState/RobotStateComponent.h
index 0afb8f32c3d3c545e3a1722eeb98433cba500485..617d938e6e3644604f56e7be7fc7e7f750da9e29 100644
--- a/source/RobotAPI/components/RobotState/RobotStateComponent.h
+++ b/source/RobotAPI/components/RobotState/RobotStateComponent.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    RobotStateComponent::
  * @author     ( stefan dot ulbrich at kit dot edu)
  * @date
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -26,9 +25,9 @@
 
 #include "SharedRobotServants.h"
 
-#include <Core/core/Component.h>
-#include <Core/core/application/properties/Properties.h>
-#include <Core/core/system/ImportExportComponent.h>
+#include <ArmarXCore/core/Component.h>
+#include <ArmarXCore/core/application/properties/Properties.h>
+#include <ArmarXCore/core/system/ImportExportComponent.h>
 #include <RobotAPI/interface/core/RobotState.h>
 #include "SharedRobotServants.h"
 
@@ -43,13 +42,13 @@ namespace armarx
      * \brief
      */
     class RobotStatePropertyDefinitions:
-            public ComponentPropertyDefinitions
+        public ComponentPropertyDefinitions
     {
     public:
         RobotStatePropertyDefinitions(std::string prefix):
             ComponentPropertyDefinitions(prefix)
         {
-            defineRequiredProperty<std::string>("RobotNodeSetName","Set of nodes that is controlled by the KinematicUnit");
+            defineRequiredProperty<std::string>("RobotNodeSetName", "Set of nodes that is controlled by the KinematicUnit");
             defineRequiredProperty<std::string>("RobotFileName", "Filename of VirtualRobot robot model (e.g. robot_model.xml)");
             defineRequiredProperty<std::string>("AgentName", "Name of the agent for which the sensor values are provided");
         }
@@ -57,7 +56,7 @@ namespace armarx
 
 
     /**
-     * \class RobotStateComponent
+     * \defgroup Component-RobotStateComponent RobotStateComponent
      * \ingroup RobotAPI-Components
      * \brief Maintains a robot representation based on VirtualRobot (see [Simox](http://simox.sourceforge.net/)).
      *
@@ -72,6 +71,11 @@ namespace armarx
      * to calculate on the same values.
      * See \ref armarx::RemoteRobot "RemoteRobot" for more details and the usage of this component.
      */
+
+    /**
+     * @brief The RobotStateComponent class
+     * @ingroup Component-RobotStateComponent
+     */
     class ARMARXCOMPONENT_IMPORT_EXPORT RobotStateComponent :
         virtual public Component,
         virtual public RobotStateComponentInterface
@@ -87,8 +91,8 @@ namespace armarx
         /**
          * \return Clone of the internal synchronized robot.
          */
-        virtual SharedRobotInterfacePrx getRobotSnapshot(const std::string & time, const Ice::Current&);
-        
+        virtual SharedRobotInterfacePrx getRobotSnapshot(const std::string& time, const Ice::Current&);
+
         /**
          * \return the robot xml filename as specified in the configuration
          */
@@ -104,7 +108,7 @@ namespace armarx
          *
          * \return  The name of this robot instance.
          */
-        virtual std::string getRobotName(const Ice::Current &) const;
+        virtual std::string getRobotName(const Ice::Current&) const;
 
         /**
          * Create an instance of RobotStatePropertyDefinitions.
diff --git a/source/RobotAPI/components/RobotState/SharedRobotServants.cpp b/source/RobotAPI/components/RobotState/SharedRobotServants.cpp
index ac0def3d77e4deabb85a065bf2240c47bd1100ca..ba706483d794fe354d875367db1be3a02e49dea2 100644
--- a/source/RobotAPI/components/RobotState/SharedRobotServants.cpp
+++ b/source/RobotAPI/components/RobotState/SharedRobotServants.cpp
@@ -1,6 +1,6 @@
 #include "SharedRobotServants.h"
 
-#include <Core/core/logging/Logging.h>
+#include <ArmarXCore/core/logging/Logging.h>
 
 #include <boost/foreach.hpp>
 
@@ -14,7 +14,7 @@
 #include <VirtualRobot/Robot.h>
 #include <VirtualRobot/RobotNodeSet.h>
 #include <Ice/ObjectAdapter.h>
-#include <Core/observers/variant/TimestampVariant.h>
+#include <ArmarXCore/observers/variant/TimestampVariant.h>
 
 
 using namespace std;
@@ -31,360 +31,407 @@ using namespace Ice;
 namespace armarx
 {
 
-typedef std::map<std::string, SharedRobotNodeInterfacePrx> NodeCache;
+    typedef std::map<std::string, SharedRobotNodeInterfacePrx> NodeCache;
 
-///////////////////////////////
-// SharedObjectBase
-///////////////////////////////
+    ///////////////////////////////
+    // SharedObjectBase
+    ///////////////////////////////
 
-SharedObjectBase::SharedObjectBase()
-{
-    this-> _referenceCount=0;
-    #ifdef VERBOSE
-    ARMARX_LOG_S << "construct " << this << flush;
-    #endif
-}
+    SharedObjectBase::SharedObjectBase()
+    {
+        this-> _referenceCount = 0;
+#ifdef VERBOSE
+        ARMARX_LOG_S << "construct " << this << flush;
+#endif
+    }
 
 
-void SharedObjectBase::ref(const Current &current)
-{
-    boost::lock_guard<boost::mutex> lock(this->_counterMutex);
+    void SharedObjectBase::ref(const Current& current)
+    {
+        boost::lock_guard<boost::mutex> lock(this->_counterMutex);
 
-    _referenceCount++;
+        _referenceCount++;
 
-    #ifdef VERBOSE
-    ARMARX_LOG_S << "ref: " <<  _referenceCount << " " << this << flush;
-    #endif
-}
+#ifdef VERBOSE
+        ARMARX_LOG_S << "ref: " <<  _referenceCount << " " << this << flush;
+#endif
+    }
 
-void SharedObjectBase::unref(const Current &current)
-{
-    boost::lock_guard<boost::mutex> lock(this->_counterMutex);
+    void SharedObjectBase::unref(const Current& current)
+    {
+        boost::lock_guard<boost::mutex> lock(this->_counterMutex);
 
 #ifdef VERBOSE
-    ARMARX_LOG_S << "unref: " <<   _referenceCount << " " << this << flush;
+        ARMARX_LOG_S << "unref: " <<   _referenceCount << " " << this << flush;
 #endif
-    _referenceCount --;
-    if (_referenceCount==0)
-        this->destroy(current);
-}
+        _referenceCount --;
 
-void SharedObjectBase::destroy(const Current &current)
-{
-    try {
-        current.adapter->remove(current.id);
-    #ifdef VERBOSE
-        ARMARX_ERROR_S << "[SharedObject] destroy " << " " << this << flush;
-    #endif
-    } catch (const NotRegisteredException&e){
-//        ARMARX_INFO_S << "destroy failed with: " << e.what();
-        throw ObjectNotExistException(__FILE__, __LINE__);
-    };
-}
+        if (_referenceCount == 0)
+        {
+            this->destroy(current);
+        }
+    }
+
+    void SharedObjectBase::destroy(const Current& current)
+    {
+        try
+        {
+            current.adapter->remove(current.id);
+#ifdef VERBOSE
+            ARMARX_ERROR_S << "[SharedObject] destroy " << " " << this << flush;
+#endif
+        }
+        catch (const NotRegisteredException& e)
+        {
+            //        ARMARX_INFO_S << "destroy failed with: " << e.what();
+            throw ObjectNotExistException(__FILE__, __LINE__);
+        };
+    }
 
-///////////////////////////////
-// SharedRobotNodeServant
-///////////////////////////////
+    ///////////////////////////////
+    // SharedRobotNodeServant
+    ///////////////////////////////
 
-SharedRobotNodeServant::SharedRobotNodeServant(RobotNodePtr node) :
-    _node(node)
-{
+    SharedRobotNodeServant::SharedRobotNodeServant(RobotNodePtr node) :
+        _node(node)
+    {
 #ifdef VERBOSE
-    ARMARX_LOG_S << "[SharedRobotNodeServant] construct " << " " << this << flush;
+        ARMARX_LOG_S << "[SharedRobotNodeServant] construct " << " " << this << flush;
 #endif
-}
+    }
 
 
-SharedRobotNodeServant::~SharedRobotNodeServant()
-{
+    SharedRobotNodeServant::~SharedRobotNodeServant()
+    {
 #ifdef VERBOSE
-    ARMARX_FATAL_S << "[SharedRobotNodeServant] destruct " << " " << this << flush;
+        ARMARX_FATAL_S << "[SharedRobotNodeServant] destruct " << " " << this << flush;
 #endif
-}
+    }
 
-float SharedRobotNodeServant::getJointValue(const Current &current) const
-{
-    ReadLockPtr lock = _node->getRobot()->getReadLock();
-    return _node->getJointValue();
-}
+    float SharedRobotNodeServant::getJointValue(const Current& current) const
+    {
+        ReadLockPtr lock = _node->getRobot()->getReadLock();
+        return _node->getJointValue();
+    }
 
-string SharedRobotNodeServant::getName(const Current &current) const
-{
-    ReadLockPtr lock = _node->getRobot()->getReadLock();
-    return _node->getName();
-}
+    string SharedRobotNodeServant::getName(const Current& current) const
+    {
+        ReadLockPtr lock = _node->getRobot()->getReadLock();
+        return _node->getName();
+    }
 
-PoseBasePtr SharedRobotNodeServant::getLocalTransformation(const Current &current) const
-{
-    ReadLockPtr lock = _node->getRobot()->getReadLock();
-    return new Pose(_node->getLocalTransformation());
-}
+    PoseBasePtr SharedRobotNodeServant::getLocalTransformation(const Current& current) const
+    {
+        ReadLockPtr lock = _node->getRobot()->getReadLock();
+        return new Pose(_node->getLocalTransformation());
+    }
 
-FramedPoseBasePtr SharedRobotNodeServant::getGlobalPose(const Current &current) const
-{
-    ReadLockPtr lock = _node->getRobot()->getReadLock();
-    return new FramedPose(_node->getGlobalPose(),
-                          GlobalFrame,
-                          "");
-}
+    FramedPoseBasePtr SharedRobotNodeServant::getGlobalPose(const Current& current) const
+    {
+        ReadLockPtr lock = _node->getRobot()->getReadLock();
+        return new FramedPose(_node->getGlobalPose(),
+                              GlobalFrame,
+                              "");
+    }
 
-FramedPoseBasePtr SharedRobotNodeServant::getPoseInRootFrame(const Current &current) const
-{
-    ReadLockPtr lock = _node->getRobot()->getReadLock();
-    return new FramedPose(_node->getPoseInRootFrame(),
-                          _node->getRobot()->getRootNode()->getName(),
-                          _node->getRobot()->getName());
-}
+    FramedPoseBasePtr SharedRobotNodeServant::getPoseInRootFrame(const Current& current) const
+    {
+        ReadLockPtr lock = _node->getRobot()->getReadLock();
+        return new FramedPose(_node->getPoseInRootFrame(),
+                              _node->getRobot()->getRootNode()->getName(),
+                              _node->getRobot()->getName());
+    }
 
 
-JointType SharedRobotNodeServant::getType(const Current &current) const
-{
-    ReadLockPtr lock = _node->getRobot()->getReadLock();
-    if (_node->isRotationalJoint()) return eRevolute;
-    else if (_node->isTranslationalJoint()) return ePrismatic;
-    else return eFixed;
-}
+    JointType SharedRobotNodeServant::getType(const Current& current) const
+    {
+        ReadLockPtr lock = _node->getRobot()->getReadLock();
 
-Vector3BasePtr SharedRobotNodeServant::getJointTranslationDirection(const Current &current) const
-{
-    ReadLockPtr lock = _node->getRobot()->getReadLock();
-    boost::shared_ptr<RobotNodePrismatic> prismatic = dynamic_pointer_cast<RobotNodePrismatic>(_node);
-    if (prismatic)
-        return new Vector3(prismatic->getJointTranslationDirection());
-    else
-        return new Vector3;
-}
+        if (_node->isRotationalJoint())
+        {
+            return eRevolute;
+        }
+        else if (_node->isTranslationalJoint())
+        {
+            return ePrismatic;
+        }
+        else
+        {
+            return eFixed;
+        }
+    }
 
-Vector3BasePtr SharedRobotNodeServant::getJointRotationAxis(const Current &current) const
-{
-    ReadLockPtr lock = _node->getRobot()->getReadLock();
-    boost::shared_ptr<RobotNodeRevolute> revolute = dynamic_pointer_cast<RobotNodeRevolute>(_node);
-    if (revolute)
-        return new Vector3(revolute->getJointRotationAxis());
-    else
-        return new Vector3;
-}
+    Vector3BasePtr SharedRobotNodeServant::getJointTranslationDirection(const Current& current) const
+    {
+        ReadLockPtr lock = _node->getRobot()->getReadLock();
+        boost::shared_ptr<RobotNodePrismatic> prismatic = dynamic_pointer_cast<RobotNodePrismatic>(_node);
+
+        if (prismatic)
+        {
+            return new Vector3(prismatic->getJointTranslationDirection());
+        }
+        else
+        {
+            return new Vector3;
+        }
+    }
 
+    Vector3BasePtr SharedRobotNodeServant::getJointRotationAxis(const Current& current) const
+    {
+        ReadLockPtr lock = _node->getRobot()->getReadLock();
+        boost::shared_ptr<RobotNodeRevolute> revolute = dynamic_pointer_cast<RobotNodeRevolute>(_node);
 
-bool SharedRobotNodeServant::hasChild(const string &name, bool recursive, const Current &current) const
-{
-    ReadLockPtr lock = _node->getRobot()->getReadLock();
-    //return _node->hasChild(name,recursive);
-    return false;
-}
+        if (revolute)
+        {
+            return new Vector3(revolute->getJointRotationAxis());
+        }
+        else
+        {
+            return new Vector3;
+        }
+    }
 
-string SharedRobotNodeServant::getParent(const Current &current) const
-{
-    ReadLockPtr lock = _node->getRobot()->getReadLock();
-    SceneObjectPtr parent = _node->getParent();
-    if (!parent) throw UserException("This RobotNode has no parent.");
-    return parent->getName();
-}
 
-NameList SharedRobotNodeServant::getChildren(const Current &current) const
-{
-    ReadLockPtr lock = _node->getRobot()->getReadLock();
-    vector<SceneObjectPtr> children = _node->getChildren();
-    NameList names;
-    BOOST_FOREACH(SceneObjectPtr node, children){
-        names.push_back(node->getName());
+    bool SharedRobotNodeServant::hasChild(const string& name, bool recursive, const Current& current) const
+    {
+        ReadLockPtr lock = _node->getRobot()->getReadLock();
+        //return _node->hasChild(name,recursive);
+        return false;
     }
-    return names;
-}
 
-NameList SharedRobotNodeServant::getAllParents(const std::string &name, const Ice::Current &current) const
-{
-    ReadLockPtr lock = _node->getRobot()->getReadLock();
-    vector<RobotNodePtr> parents = _node->getAllParents(_node->getRobot()->getRobotNodeSet(name));
-    NameList names;
-    BOOST_FOREACH(RobotNodePtr node, parents){
-        names.push_back(node->getName());
+    string SharedRobotNodeServant::getParent(const Current& current) const
+    {
+        ReadLockPtr lock = _node->getRobot()->getReadLock();
+        SceneObjectPtr parent = _node->getParent();
+
+        if (!parent)
+        {
+            throw UserException("This RobotNode has no parent.");
+        }
+
+        return parent->getName();
     }
-    return names;
-}
 
-float SharedRobotNodeServant::getJointValueOffest(const Current &current) const
-{
-    ReadLockPtr lock = _node->getRobot()->getReadLock();
-    return _node->getJointValueOffset();
-}
+    NameList SharedRobotNodeServant::getChildren(const Current& current) const
+    {
+        ReadLockPtr lock = _node->getRobot()->getReadLock();
+        vector<SceneObjectPtr> children = _node->getChildren();
+        NameList names;
+        BOOST_FOREACH(SceneObjectPtr node, children)
+        {
+            names.push_back(node->getName());
+        }
+        return names;
+    }
 
-float SharedRobotNodeServant::getJointLimitHigh(const Current &current) const
-{
-    ReadLockPtr lock = _node->getRobot()->getReadLock();
-    return _node->getJointLimitHigh();
-}
+    NameList SharedRobotNodeServant::getAllParents(const std::string& name, const Ice::Current& current) const
+    {
+        ReadLockPtr lock = _node->getRobot()->getReadLock();
+        vector<RobotNodePtr> parents = _node->getAllParents(_node->getRobot()->getRobotNodeSet(name));
+        NameList names;
+        BOOST_FOREACH(RobotNodePtr node, parents)
+        {
+            names.push_back(node->getName());
+        }
+        return names;
+    }
 
-float SharedRobotNodeServant::getJointLimitLow(const Current &current) const
-{
-    ReadLockPtr lock = _node->getRobot()->getReadLock();
-    return _node->getJointLimitLow();
-}
+    float SharedRobotNodeServant::getJointValueOffest(const Current& current) const
+    {
+        ReadLockPtr lock = _node->getRobot()->getReadLock();
+        return _node->getJointValueOffset();
+    }
 
+    float SharedRobotNodeServant::getJointLimitHigh(const Current& current) const
+    {
+        ReadLockPtr lock = _node->getRobot()->getReadLock();
+        return _node->getJointLimitHigh();
+    }
 
-///////////////////////////////
-// SharedRobotServant
-///////////////////////////////
+    float SharedRobotNodeServant::getJointLimitLow(const Current& current) const
+    {
+        ReadLockPtr lock = _node->getRobot()->getReadLock();
+        return _node->getJointLimitLow();
+    }
 
-SharedRobotServant::SharedRobotServant(RobotPtr robot)
-    : _robot(robot)
-{
+
+    ///////////////////////////////
+    // SharedRobotServant
+    ///////////////////////////////
+
+    SharedRobotServant::SharedRobotServant(RobotPtr robot)
+        : _robot(robot)
+    {
 #ifdef VERBOSE
-    ARMARX_WARNING_S << "construct " << this << flush;
+        ARMARX_WARNING_S << "construct " << this << flush;
 #endif
-}
+    }
 
-SharedRobotServant::~SharedRobotServant()
-{
+    SharedRobotServant::~SharedRobotServant()
+    {
 #ifdef VERBOSE
-    ARMARX_WARNING_S << "destruct " << this << flush;
+        ARMARX_WARNING_S << "destruct " << this << flush;
 #endif
-    boost::recursive_mutex::scoped_lock cloneLock(m);
+        boost::recursive_mutex::scoped_lock cloneLock(m);
 
-    for(auto value: this->_cachedNodes)
-    {
-        try
+        for (auto value : this->_cachedNodes)
         {
-            value.second->unref();
+            try
+            {
+                value.second->unref();
+            }
+            catch (...) {}
         }
-        catch(...){}
     }
-}
 
-SharedRobotNodeInterfacePrx SharedRobotServant::getRobotNode(const string &name, const Current &current)
-{
-//    ARMARX_LOG_S << "Looking for node: " << name << flush;
-    assert(_robot);
-    boost::recursive_mutex::scoped_lock cloneLock(m);
-    SharedRobotNodeInterfacePrx prx;
-    if (this->_cachedNodes.find(name) == this->_cachedNodes.end()){
-        RobotNodePtr robotNode = _robot->getRobotNode(name);
-        if (!robotNode){
-            ARMARX_WARNING_S << "RobotNode \"" + name + "\" not defined.";
-            throw UserException("RobotNode \"" + name + "\" not defined.");
+    SharedRobotNodeInterfacePrx SharedRobotServant::getRobotNode(const string& name, const Current& current)
+    {
+        //    ARMARX_LOG_S << "Looking for node: " << name << flush;
+        assert(_robot);
+        boost::recursive_mutex::scoped_lock cloneLock(m);
+        SharedRobotNodeInterfacePrx prx;
+
+        if (this->_cachedNodes.find(name) == this->_cachedNodes.end())
+        {
+            RobotNodePtr robotNode = _robot->getRobotNode(name);
+
+            if (!robotNode)
+            {
+                ARMARX_WARNING_S << "RobotNode \"" + name + "\" not defined.";
+                throw UserException("RobotNode \"" + name + "\" not defined.");
+            }
+
+            SharedRobotNodeInterfacePtr servant = new SharedRobotNodeServant(
+                _robot->getRobotNode(name));
+            //servant->ref();
+            prx = SharedRobotNodeInterfacePrx::uncheckedCast(current.adapter->addWithUUID(servant));
+            prx->ref();
+            //        return prx;
+            this->_cachedNodes[name] = prx;
         }
 
-        SharedRobotNodeInterfacePtr servant = new SharedRobotNodeServant(
-            _robot->getRobotNode(name));
-        //servant->ref();
-        prx = SharedRobotNodeInterfacePrx::uncheckedCast(current.adapter->addWithUUID(servant));
-        prx->ref();
-//        return prx;
-        this->_cachedNodes[name] = prx;
+        return this->_cachedNodes[name];
     }
-    return this->_cachedNodes[name];
-}
-
-SharedRobotNodeInterfacePrx SharedRobotServant::getRootNode(const Current &current)
-{
-    assert(_robot);
-    boost::recursive_mutex::scoped_lock cloneLock(m);
-    string name = _robot->getRootNode()/*,current*/->getName();
-    return this->getRobotNode(name, current);
-}
 
+    SharedRobotNodeInterfacePrx SharedRobotServant::getRootNode(const Current& current)
+    {
+        assert(_robot);
+        boost::recursive_mutex::scoped_lock cloneLock(m);
+        string name = _robot->getRootNode()/*,current*/->getName();
+        return this->getRobotNode(name, current);
+    }
 
-bool SharedRobotServant::hasRobotNode(const string & name, const Current &current)
-{
-    return _robot->hasRobotNode(name);
-}
 
-NameList SharedRobotServant::getRobotNodes(const Current &current)
-{
-    vector<RobotNodePtr> robotNodes = _robot->getRobotNodes();
-    NameList names;
-    BOOST_FOREACH(RobotNodePtr node, robotNodes){
-        names.push_back(node->getName());
+    bool SharedRobotServant::hasRobotNode(const string& name, const Current& current)
+    {
+        return _robot->hasRobotNode(name);
     }
-    return names;
-}
 
-RobotNodeSetInfoPtr SharedRobotServant::getRobotNodeSet(const string & name, const Current &current)
-{
-    RobotNodeSetPtr robotNodeSet = _robot->getRobotNodeSet(name);
-    if (!robotNodeSet) throw UserException("RobotNodeSet \""+name+"\" not defined");
-    vector<RobotNodePtr> robotNodes = robotNodeSet->getAllRobotNodes();
-    NameList names;
-    BOOST_FOREACH(RobotNodePtr node, robotNodes){
-        names.push_back(node->getName());
+    NameList SharedRobotServant::getRobotNodes(const Current& current)
+    {
+        vector<RobotNodePtr> robotNodes = _robot->getRobotNodes();
+        NameList names;
+        BOOST_FOREACH(RobotNodePtr node, robotNodes)
+        {
+            names.push_back(node->getName());
+        }
+        return names;
     }
 
-    RobotNodeSetInfoPtr info = new RobotNodeSetInfo;
-    info->names = names;
-    info->name = name;
-    info->tcpName = robotNodeSet->getTCP()->getName();
-    info->rootName = robotNodeSet->getKinematicRoot()->getName();
+    RobotNodeSetInfoPtr SharedRobotServant::getRobotNodeSet(const string& name, const Current& current)
+    {
+        RobotNodeSetPtr robotNodeSet = _robot->getRobotNodeSet(name);
+
+        if (!robotNodeSet)
+        {
+            throw UserException("RobotNodeSet \"" + name + "\" not defined");
+        }
 
-    return info;
+        vector<RobotNodePtr> robotNodes = robotNodeSet->getAllRobotNodes();
+        NameList names;
+        BOOST_FOREACH(RobotNodePtr node, robotNodes)
+        {
+            names.push_back(node->getName());
+        }
 
-}
+        RobotNodeSetInfoPtr info = new RobotNodeSetInfo;
+        info->names = names;
+        info->name = name;
+        info->tcpName = robotNodeSet->getTCP()->getName();
+        info->rootName = robotNodeSet->getKinematicRoot()->getName();
+
+        return info;
 
-NameList SharedRobotServant::getRobotNodeSets(const Current &current)
-{
-    vector<RobotNodeSetPtr> robotNodeSets = _robot->getRobotNodeSets();
-    NameList names;
-    BOOST_FOREACH(RobotNodeSetPtr set, robotNodeSets){
-        names.push_back(set->getName());
     }
 
-    return names;
-}
+    NameList SharedRobotServant::getRobotNodeSets(const Current& current)
+    {
+        vector<RobotNodeSetPtr> robotNodeSets = _robot->getRobotNodeSets();
+        NameList names;
+        BOOST_FOREACH(RobotNodeSetPtr set, robotNodeSets)
+        {
+            names.push_back(set->getName());
+        }
 
-bool SharedRobotServant::hasRobotNodeSet(const string & name, const Current &current)
-{
-    return _robot->hasRobotNodeSet(name);
-}
+        return names;
+    }
 
-string SharedRobotServant::getName(const Current &current)
-{
-    //ARMARX_VERBOSE_S << "SharedRobotServant::getname:" << _robot->getName();
-    return _robot->getName();
-}
+    bool SharedRobotServant::hasRobotNodeSet(const string& name, const Current& current)
+    {
+        return _robot->hasRobotNodeSet(name);
+    }
 
-string SharedRobotServant::getType(const Current &current)
-{
-    return _robot->getType();
-}
+    string SharedRobotServant::getName(const Current& current)
+    {
+        //ARMARX_VERBOSE_S << "SharedRobotServant::getname:" << _robot->getName();
+        return _robot->getName();
+    }
 
-void SharedRobotServant::setTimestamp(const IceUtil::Time &updateTime)
-{
-    updateTimestamp = updateTime;
-}
+    string SharedRobotServant::getType(const Current& current)
+    {
+        return _robot->getType();
+    }
 
-PoseBasePtr SharedRobotServant::getGlobalPose(const Current &current)
-{
-    ReadLockPtr lock = _robot->getReadLock();
-    return new Pose(_robot->getGlobalPose());
-}
+    void SharedRobotServant::setTimestamp(const IceUtil::Time& updateTime)
+    {
+        updateTimestamp = updateTime;
+    }
 
-NameValueMap SharedRobotServant::getConfig(const Current &current)
-{
-    if(!_robot)
+    PoseBasePtr SharedRobotServant::getGlobalPose(const Current& current)
     {
-        ARMARX_WARNING_S << "no robot set";
-        return NameValueMap();
+        ReadLockPtr lock = _robot->getReadLock();
+        return new Pose(_robot->getGlobalPose());
     }
-    ReadLockPtr lock = _robot->getReadLock();
-    std::map < std::string, float > values = _robot->getConfig()->getRobotNodeJointValueMap();
-    NameValueMap result(values.begin(), values.end());
-    return result;
-}
 
-TimestampBasePtr SharedRobotServant::getTimestamp(const Current &) const
-{
-    return new TimestampVariant(updateTimestamp);
-}
+    NameValueMap SharedRobotServant::getConfig(const Current& current)
+    {
+        if (!_robot)
+        {
+            ARMARX_WARNING_S << "no robot set";
+            return NameValueMap();
+        }
 
-void SharedRobotServant::setGlobalPose(const armarx::PoseBasePtr &pose, const Current &)
-{
-    WriteLockPtr lock = _robot->getWriteLock();
-    _robot->setGlobalPose(PosePtr::dynamicCast(pose)->toEigen(), true);
-}
+        ReadLockPtr lock = _robot->getReadLock();
+        std::map < std::string, float > values = _robot->getConfig()->getRobotNodeJointValueMap();
+        NameValueMap result(values.begin(), values.end());
+        return result;
+    }
 
-RobotPtr SharedRobotServant::getRobot() const
-{
-    return this->_robot;
-}
+    TimestampBasePtr SharedRobotServant::getTimestamp(const Current&) const
+    {
+        return new TimestampVariant(updateTimestamp);
+    }
+
+    void SharedRobotServant::setGlobalPose(const armarx::PoseBasePtr& pose, const Current&)
+    {
+        WriteLockPtr lock = _robot->getWriteLock();
+        _robot->setGlobalPose(PosePtr::dynamicCast(pose)->toEigen(), true);
+    }
+
+    RobotPtr SharedRobotServant::getRobot() const
+    {
+        return this->_robot;
+    }
 
 }
 
diff --git a/source/RobotAPI/components/RobotState/SharedRobotServants.h b/source/RobotAPI/components/RobotState/SharedRobotServants.h
index 5c6637590876a868d0ff7cd9e5b479b02316e288..845ed5465c4d5a4a43ad52f7ad9551b9c878f340 100644
--- a/source/RobotAPI/components/RobotState/SharedRobotServants.h
+++ b/source/RobotAPI/components/RobotState/SharedRobotServants.h
@@ -1,8 +1,8 @@
 #ifndef __SHARED_ROBOT_SERVANTS_H__
 #define __SHARED_ROBOT_SERVANTS_H__
 
-#include <Core/core/Component.h>
-#include <Core/core/system/ImportExportComponent.h>
+#include <ArmarXCore/core/Component.h>
+#include <ArmarXCore/core/system/ImportExportComponent.h>
 #include <RobotAPI/libraries/core/FramedPose.h>
 
 
@@ -18,7 +18,8 @@ namespace VirtualRobot
     typedef boost::shared_ptr<RobotNode> RobotNodePtr;
 }
 
-namespace armarx {
+namespace armarx
+{
     // Zugriff muss mutex geschuetzt werden!
 
     /**
@@ -29,22 +30,22 @@ namespace armarx {
     class SharedObjectBase :
         virtual public SharedObjectInterface
     {
-        public:
-            virtual void ref(const Ice::Current &c = Ice::Current());
-            virtual void unref(const Ice::Current &c = Ice::Current());
-            void destroy(const Ice::Current &c = Ice::Current());
-            SharedObjectBase();
-        private:
-            unsigned int _referenceCount;
-            boost::mutex _counterMutex;
+    public:
+        virtual void ref(const Ice::Current& c = Ice::Current());
+        virtual void unref(const Ice::Current& c = Ice::Current());
+        void destroy(const Ice::Current& c = Ice::Current());
+        SharedObjectBase();
+    private:
+        unsigned int _referenceCount;
+        boost::mutex _counterMutex;
     };
 
     /**
      * @brief The SharedRobotNodeServant class is a remote represenation of a Simox VirtualRobot::Robot
-     *
+     * @ingroup Component-RobotStateComponent
      * @details This class is used only internally by the the RobotStateComponent. Other classes such as the LinkedPose, RemoteRobot,
      * TCPControlUnit and HeadIKUnit classes address this class by the SharedRobotNodeInterface and SharedRobotNodeInterfacePrx generated by
-     * ICE.
+     * Ice.
      */
     class SharedRobotNodeServant :
         virtual public SharedRobotNodeInterface,
@@ -54,25 +55,25 @@ namespace armarx {
         SharedRobotNodeServant(VirtualRobot::RobotNodePtr node /*,const Ice::Current & current = Ice::Current()*/);
         ~SharedRobotNodeServant();
 
-        virtual float getJointValue(const Ice::Current & current = Ice::Current()) const;
-        virtual std::string getName(const Ice::Current & current = Ice::Current()) const;
+        virtual float getJointValue(const Ice::Current& current = Ice::Current()) const;
+        virtual std::string getName(const Ice::Current& current = Ice::Current()) const;
 
-        virtual PoseBasePtr getLocalTransformation(const Ice::Current & current = Ice::Current()) const;
-        virtual FramedPoseBasePtr getGlobalPose(const Ice::Current & current = Ice::Current()) const;
-        virtual FramedPoseBasePtr getPoseInRootFrame(const Ice::Current &current = Ice::Current()) const;
+        virtual PoseBasePtr getLocalTransformation(const Ice::Current& current = Ice::Current()) const;
+        virtual FramedPoseBasePtr getGlobalPose(const Ice::Current& current = Ice::Current()) const;
+        virtual FramedPoseBasePtr getPoseInRootFrame(const Ice::Current& current = Ice::Current()) const;
 
-        virtual JointType getType(const Ice::Current & current = Ice::Current()) const;
-        virtual Vector3BasePtr getJointTranslationDirection(const Ice::Current & current = Ice::Current()) const;
-        virtual Vector3BasePtr getJointRotationAxis(const Ice::Current & current = Ice::Current()) const;
+        virtual JointType getType(const Ice::Current& current = Ice::Current()) const;
+        virtual Vector3BasePtr getJointTranslationDirection(const Ice::Current& current = Ice::Current()) const;
+        virtual Vector3BasePtr getJointRotationAxis(const Ice::Current& current = Ice::Current()) const;
 
-        virtual bool hasChild(const std::string &name, bool recursive, const Ice::Current & current = Ice::Current()) const;
-        virtual std::string getParent(const Ice::Current & current = Ice::Current()) const;
-        virtual NameList getChildren(const Ice::Current & current = Ice::Current()) const;
-        virtual NameList getAllParents(const std::string &name, const Ice::Current & current = Ice::Current()) const;
+        virtual bool hasChild(const std::string& name, bool recursive, const Ice::Current& current = Ice::Current()) const;
+        virtual std::string getParent(const Ice::Current& current = Ice::Current()) const;
+        virtual NameList getChildren(const Ice::Current& current = Ice::Current()) const;
+        virtual NameList getAllParents(const std::string& name, const Ice::Current& current = Ice::Current()) const;
 
-        virtual float getJointValueOffest(const Ice::Current & current = Ice::Current()) const;
-        virtual float getJointLimitHigh(const Ice::Current & current = Ice::Current()) const;
-        virtual float getJointLimitLow(const Ice::Current & current = Ice::Current()) const;
+        virtual float getJointValueOffest(const Ice::Current& current = Ice::Current()) const;
+        virtual float getJointLimitHigh(const Ice::Current& current = Ice::Current()) const;
+        virtual float getJointLimitLow(const Ice::Current& current = Ice::Current()) const;
 
 
 
@@ -81,6 +82,7 @@ namespace armarx {
     };
 
     /**
+     * @ingroup Component-RobotStateComponent
      * @brief The SharedRobotNodeServant class is a remote represenation of a Simox VirtualRobot::Robot
      *
      * @details This class is used only internally by the the RobotStateComponent. The RemoteRobot class SharedRobotInterface and SharedRobotInterfacePrx
@@ -95,26 +97,26 @@ namespace armarx {
         SharedRobotServant(VirtualRobot::RobotPtr robot);
         ~SharedRobotServant();
 
-        virtual SharedRobotNodeInterfacePrx getRobotNode(const std::string & name, const Ice::Current & current = Ice::Current());
-        virtual SharedRobotNodeInterfacePrx getRootNode(const Ice::Current & current = Ice::Current());
-        virtual bool hasRobotNode(const std::string & name, const Ice::Current & current = Ice::Current());
+        virtual SharedRobotNodeInterfacePrx getRobotNode(const std::string& name, const Ice::Current& current = Ice::Current());
+        virtual SharedRobotNodeInterfacePrx getRootNode(const Ice::Current& current = Ice::Current());
+        virtual bool hasRobotNode(const std::string& name, const Ice::Current& current = Ice::Current());
 
-        virtual NameList getRobotNodes(const Ice::Current & current = Ice::Current());
-        virtual RobotNodeSetInfoPtr getRobotNodeSet(const std::string & name, const Ice::Current & current = Ice::Current());
-        virtual NameList getRobotNodeSets(const Ice::Current & current = Ice::Current());
-        virtual bool hasRobotNodeSet(const std::string & name, const Ice::Current & current = Ice::Current());
+        virtual NameList getRobotNodes(const Ice::Current& current = Ice::Current());
+        virtual RobotNodeSetInfoPtr getRobotNodeSet(const std::string& name, const Ice::Current& current = Ice::Current());
+        virtual NameList getRobotNodeSets(const Ice::Current& current = Ice::Current());
+        virtual bool hasRobotNodeSet(const std::string& name, const Ice::Current& current = Ice::Current());
 
-        virtual std::string getName(const Ice::Current & current = Ice::Current());
-        virtual std::string getType(const Ice::Current & current = Ice::Current());
+        virtual std::string getName(const Ice::Current& current = Ice::Current());
+        virtual std::string getType(const Ice::Current& current = Ice::Current());
 
-        virtual PoseBasePtr getGlobalPose(const Ice::Current & current = Ice::Current());
-        NameValueMap getConfig(const Ice::Current & current = Ice::Current());
-        virtual void setGlobalPose(const PoseBasePtr& pose, const Ice::Current &current);
+        virtual PoseBasePtr getGlobalPose(const Ice::Current& current = Ice::Current());
+        NameValueMap getConfig(const Ice::Current& current = Ice::Current());
+        virtual void setGlobalPose(const PoseBasePtr& pose, const Ice::Current& current);
 
         VirtualRobot::RobotPtr getRobot() const;
 
-        void setTimestamp(const IceUtil::Time &updateTime);
-        TimestampBasePtr getTimestamp(const Ice::Current &) const;
+        void setTimestamp(const IceUtil::Time& updateTime);
+        TimestampBasePtr getTimestamp(const Ice::Current&) const;
     protected:
         VirtualRobot::RobotPtr _robot;
         boost::recursive_mutex m;
diff --git a/source/RobotAPI/components/units/ATINetFTUnit.cpp b/source/RobotAPI/components/units/ATINetFTUnit.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..e0cf62d91b1b371ab5a6012a65cb720c7f03572a
--- /dev/null
+++ b/source/RobotAPI/components/units/ATINetFTUnit.cpp
@@ -0,0 +1,292 @@
+/*
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @package    VisionX::ArmarXObjects::ATINetFTUnit
+ * @author     Jonas Rauber ( kit at jonasrauber dot de )
+ * @date       2014
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#include "ATINetFTUnit.h"
+#include <sys/socket.h>
+#include <arpa/inet.h>
+#include <iostream>
+#include <string>
+#include <netdb.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <vector>
+#include <inttypes.h>
+using namespace armarx;
+
+
+
+void ATINetFTUnit::onInitComponent()
+{
+
+}
+
+void ATINetFTUnit::onConnectComponent()
+{
+    /*
+     * Read ATINetFT hostname and port from properties
+     * std::string receiverHostName("192.168.1.1:49152");
+     */
+    
+    std::string ATINetFTReceiverHostName = getProperty<std::string>("ATINetFTReceiveHostName").getValue();
+    std::string captureName = getProperty<std::string>("CaptureName").getValue();
+    ARMARX_INFO << "Capture Name " << captureName;
+    size_t pos = captureName.find("0");
+    captureNamePrefix = captureName.substr(0,pos);
+    ARMARX_INFO << "Capture Name Prefix " << captureNamePrefix;
+    std::string captureNameSuffix = captureName.substr(pos,captureName.size());
+    ARMARX_INFO << "Capture Name Suffix " << captureNameSuffix;
+    nPaddingZeros = captureNameSuffix.size();
+    captureNumber = std::stoi(captureNameSuffix);
+    establishATINetFTReceiveHostConnection(ATINetFTReceiverHostName);
+    ftDataSize = 6;
+    sendPacketSize = 8;
+    receivePacketSize = 36;
+    recordingStopped = true;
+    recordingCompleted = true;
+    recordingStarted = false;
+    
+    /*
+     * Connect to ATINetFT
+     */
+    /*if (ATINetFT.Connect(hostName).Result != Result::Success)
+    {
+        ARMARX_ERROR << "Could not connect to ATINetFT at " << hostName << flush;
+        return;
+    }
+    else
+    {
+        ARMARX_IMPORTANT << "Connected to ATINetFT at " << hostName << flush;
+    }*/
+
+    /*
+     * Enable Marker Data
+     */
+    /*Result::Enum result = ATINetFT.EnableMarkerData().Result;
+
+    if (result != Result::Success)
+    {
+        ARMARX_ERROR << "ATINetFT EnableMarkerData() returned error code " << result << flush;
+        return;
+    }*/
+}
+
+void ATINetFTUnit::onDisconnectComponent()
+{
+    ARMARX_IMPORTANT << "Disconnecting from ATINetFT" << flush;
+	
+}
+
+
+void ATINetFTUnit::onExitComponent()
+{
+
+}
+
+void ATINetFTUnit::periodicExec()
+{
+	if (recordingStarted)
+	
+	
+    {
+		
+		float ftdata[ftDataSize];
+		char receivePacketContent[receivePacketSize];
+      
+		if (!receivePacket(receivePacketContent))
+        {
+			ARMARX_INFO << "recvfrom() failed  :";
+		}
+		else
+		{
+			convertToFTValues(receivePacketContent, ftdata, ftDataSize);
+			writeFTValuesToFile(ftdata, ftDataSize);
+			sampleIndex++;
+		}
+       
+    }
+  
+}
+
+PropertyDefinitionsPtr ATINetFTUnit::createPropertyDefinitions()
+{
+    return PropertyDefinitionsPtr(new ATINetFTUnitPropertyDefinitions(
+                                      getConfigIdentifier()));
+}
+
+void ATINetFTUnit::startRecording(const std::string& customName, const Ice::Current& c)
+{
+    if (remoteTriggerEnabled)
+    {
+        if (recordingCompleted)
+        { 
+	  int bpSize = sendPacketSize;
+	  char bytePacket[bpSize];
+	  *(uint16_t*)&bytePacket[0] = htons(0x1234); /* standard header. */
+	  *(uint16_t*)&bytePacket[2] = htons(2); /* per table 9.1 in Net F/T user manual. */
+	  *(uint32_t*)&bytePacket[4] = htonl(0); /* see section 9.1 in Net F/T user manual. */
+	  recordingStarted = sendPacket(bytePacket,bpSize);
+	    
+            if (recordingStarted)
+            {	
+                recordingStopped = false;
+                recordingCompleted = false;
+					//TODO build filename captureNamePrefic+customName
+                recordingFile.open(captureNamePrefix);
+                sampleIndex = 0;
+            }
+        }
+    }
+}
+
+void ATINetFTUnit::stopRecording(const Ice::Current& c)
+{
+    if (remoteTriggerEnabled)
+    {
+        int bpSize = 8;
+	char bytePacket[bpSize];
+	*(uint16_t*)&bytePacket[0] = htons(0x1234); /* standard header. */
+	*(uint16_t*)&bytePacket[2] = htons(0); /* per table 9.1 in Net F/T user manual. */
+	*(uint32_t*)&bytePacket[4] = htonl(0); /* see section 9.1 in Net F/T user manual. */
+
+        recordingStopped = sendPacket(bytePacket,bpSize);
+        if (recordingStopped)
+        {
+			recordingFile.close();
+			recordingStarted = false;	
+		}
+        
+    }
+}
+
+bool ATINetFTUnit::sendPacket(char *bytePacket, int bpSize)
+{
+    if (remoteTriggerEnabled)
+    {
+		if(sendto(senderSocket, bytePacket, bpSize, 0, (struct sockaddr *)&receiveHostAddr, sizeof(receiveHostAddr))!= bpSize) {
+    
+        return false;
+        }
+        return true;
+    }
+    return false;
+}
+
+bool ATINetFTUnit::receivePacket(char *receiveBuf)
+{
+  
+  int test = sizeof(receiveHostAddr);
+  
+  int receiveint = recvfrom(senderSocket, receiveBuf, receivePacketSize, 0, ( struct sockaddr *) &receiveHostAddr, ((socklen_t*)&test));
+  
+  if (receiveint < 0)
+    {
+  
+      return false;
+    }
+
+  
+  return true;
+}
+
+void ATINetFTUnit::convertToFTValues(char *receiveBuf, float *ftdata, int ftdataSize)
+{
+	uint32_t rdt_sequence = ntohl(*(uint32_t*)&receiveBuf[0]);
+	uint32_t ft_sequence = ntohl(*(uint32_t*)&receiveBuf[4]);
+	uint32_t status = ntohl(*(uint32_t*)&receiveBuf[8]);
+	
+	for( int i = 0; i < ftdataSize; i++ ) {
+		ftdata[i] = float(int32_t(ntohl(*(uint32_t*)&receiveBuf[12 + i * 4])))/ 1000000.0f;
+	}
+}
+
+void ATINetFTUnit::writeFTValuesToFile(float *ftdata, int ftdataSize)
+{
+	recordingFile << sampleIndex << " ";
+	for (int i = 0; i < ftdataSize; i++)
+		recordingFile << ftdata[i] << " ";
+	recordingFile << "\n";
+}
+
+void ATINetFTUnit::establishATINetFTReceiveHostConnection(std::string receiverHostName)
+{
+     remoteTriggerEnabled = false;
+
+    //Construct the server sockaddr_ structure
+    memset(&senderHostAddr, 0, sizeof(senderHostAddr));
+    senderHostAddr.sin_family=AF_INET;
+    senderHostAddr.sin_addr.s_addr=htonl(INADDR_ANY);
+    senderHostAddr.sin_port=htons(0);
+
+    //Create the socket
+    if((senderSocket=socket(AF_INET, SOCK_DGRAM, 0))<0) {
+        return;
+    }
+   
+    if(bind(senderSocket,( struct sockaddr *) &senderHostAddr, sizeof(senderHostAddr))<0) {
+        return;
+    }
+   
+     //Construct the server sockaddr_ structure
+    memset(&receiveHostAddr, 0, sizeof(receiveHostAddr));
+    size_t pos = receiverHostName.find(":");
+    std::string hostname = receiverHostName.substr(0, pos);
+
+    std::string hostport = receiverHostName.substr(pos+1, receiverHostName.size());
+
+    struct hostent *he;
+    struct in_addr **addr_list;
+    int i;
+
+    if ( (he = gethostbyname( hostname.c_str() ) ) == NULL)
+    {
+            // get the host info
+         herror("gethostbyname");
+         return;
+    }
+
+    addr_list = (struct in_addr **) he->h_addr_list;
+
+    for(i = 0; addr_list[i] != NULL; i++)
+    {
+
+        char ip[100];
+            //Return the first one;
+        strcpy(ip , inet_ntoa(*addr_list[i]) );
+
+        inet_pton(AF_INET,ip,&receiveHostAddr.sin_addr.s_addr);
+
+        receiveHostAddr.sin_port=htons(atoi(hostport.c_str()));
+        remoteTriggerEnabled = true;
+	ARMARX_INFO << "Connection established to " <<  hostname << ":"<< hostport;
+	//if((receiverSocket=socket(AF_INET, SOCK_DGRAM, 0))<0) {
+	//  return;
+	//}
+	//if(bind(receiverSocket,( struct sockaddr *) &receiveHostAddr, sizeof(receiveHostAddr))<0) {
+	//  return;
+	//}
+
+        return;
+    }
+    return;
+    
+}
+
diff --git a/source/RobotAPI/components/units/ATINetFTUnit.h b/source/RobotAPI/components/units/ATINetFTUnit.h
new file mode 100644
index 0000000000000000000000000000000000000000..6cc20722f52ec9c1a612ce9d4bdfbbd399af3a3a
--- /dev/null
+++ b/source/RobotAPI/components/units/ATINetFTUnit.h
@@ -0,0 +1,181 @@
+/*
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @package    VisionX::ArmarXObjects::ATINetFTUnit
+ * @author     Jonas Rauber ( kit at jonasrauber dot de )
+ * @date       2014
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#ifndef _ROBOTAPI_UNITS_ATINetFTUnit_H
+#define _ROBOTAPI_UNITS_ATINetFTUnit_H
+
+
+#include <ArmarXCore/core/Component.h>
+#include <RobotAPI/interface/units/ATINetFTUnit.h>
+#include <RobotAPI/interface/units/UnitInterface.h>
+#include <netinet/in.h>
+#include <fstream>
+
+namespace armarx
+{
+    /**
+     * @class ATINetFTUnitPropertyDefinitions
+     * @brief
+     */
+    class ATINetFTUnitPropertyDefinitions:
+        public ComponentPropertyDefinitions
+    {
+    public:
+        ATINetFTUnitPropertyDefinitions(std::string prefix):
+            ComponentPropertyDefinitions(prefix)
+        {
+            defineOptionalProperty<std::string>(
+                "ATINetFTHostName",
+                "i61ATINetFT1:801",
+                "ATINetFT host name and port, usually i61ATINetFT1:801 or i61ATINetFT2:801");
+            defineOptionalProperty<std::string>(
+                "DatabasePathName",
+                "",
+                "Path name to motion database on receiving ATINetFT host");
+            defineOptionalProperty<std::string>(
+                "CaptureName",
+                "Trial01",
+                "Custom name of first trial in motion recording session");
+            defineOptionalProperty<std::string>(
+                "ATINetFTReceiveHostName",
+                "i61ATINetFT1:801",
+                "ATINetFT host name and port, usually i61ATINetFT1:801 or i61ATINetFT2:801");
+            defineOptionalProperty<float>(
+                "xOffset",
+                0.0f,
+                "Offset along x axis from VirtualRobot origin to ATINetFT reference marker");
+            defineOptionalProperty<float>(
+                "yOffset",
+                0.0f,
+                "Offset along y axis from VirtualRobot origin to ATINetFT reference marker");
+            defineOptionalProperty<float>(
+                "zOffset",
+                0.0f,
+                "Offset along z axis from VirtualRobot origin to ATINetFT reference marker");
+        }
+    };
+
+    /**
+     * @class ATINetFTUnit
+     * @ingroup VisionX-Components
+     * @brief ArmarX wrapper of the ATINetFT DataStream SDK
+     *
+     * Documentation mainly uses the term subject instead of object, as that's the
+     * common term in the context of ATINetFT.
+     */
+    class ATINetFTUnit :
+        virtual public armarx::Component,
+        virtual public ATINetFTUnitInterface
+    {
+    public:
+        /**
+         * @see armarx::ManagedIceObject::getDefaultName()
+         */
+        virtual std::string getDefaultName() const
+        {
+            return "ATINetFTUnit";
+        }
+
+        virtual void startRecording(const std::string& customName, const Ice::Current& c);
+
+
+        virtual void stopRecording(const Ice::Current& c);
+
+        bool isComponentOnline(const Ice::Current& c){return remoteTriggerEnabled;};
+
+        void request(const Ice::Current& c){};
+
+
+        void release(const Ice::Current& c) { }
+
+        void init(const Ice::Current& c) { }
+
+        void start(const Ice::Current& c) { }
+
+        void stop(const Ice::Current& c) { }
+
+        armarx::UnitExecutionState getExecutionState(const Ice::Current& c) { return armarx::eUndefinedUnitExecutionState; }
+    protected:
+        /**
+         * @see armarx::ManagedIceObject::onInitComponent()
+         */
+        virtual void onInitComponent();
+
+        /**
+         * @see armarx::ManagedIceObject::onConnectComponent()
+         */
+        virtual void onConnectComponent();
+
+        /**
+         * @see armarx::ManagedIceObject::onDisconnectComponent()
+         */
+        virtual void onDisconnectComponent();
+
+        /**
+         * @see armarx::ManagedIceObject::onExitComponent()
+         */
+        virtual void onExitComponent();
+
+        /**
+         * @see PropertyUser::createPropertyDefinitions()
+         */
+        virtual PropertyDefinitionsPtr createPropertyDefinitions();
+
+
+    private:
+        /**
+         * The ATINetFT DataStream SDK Client
+         */
+
+
+	void periodicExec();
+        void establishATINetFTReceiveHostConnection(std::string receiverHostName);
+        bool sendPacket(char *bytePacket, int bpSize);
+        bool receivePacket(char *bytePacket);
+		void convertToFTValues(char *receiveBuf, float *ftdata, int ftdataSize);
+		void writeFTValuesToFile(float *ftdata, int ftdataSize);
+
+		std::ofstream recordingFile;
+
+        bool remoteTriggerEnabled;
+        bool recordingStarted;
+        bool recordingStopped;
+        bool recordingCompleted;
+
+        int packetID;
+        int ftDataSize;
+        int sendPacketSize;
+        int receivePacketSize;
+        int captureNumber;
+        int senderSocket;
+        int nPaddingZeros;
+        int sampleIndex;
+
+        std::string captureNamePrefix;
+        std::string databasePathName;
+        struct sockaddr_in receiveHostAddr;
+        struct sockaddr_in senderHostAddr;
+
+    };
+}
+
+#endif
diff --git a/source/RobotAPI/components/units/BusInspectionUnit.cpp b/source/RobotAPI/components/units/BusInspectionUnit.cpp
index 20506415423cfeba683533a9d2b4d267c5694e46..6bf0479059deefcdb3ef94496ff7d3878c41e69d 100644
--- a/source/RobotAPI/components/units/BusInspectionUnit.cpp
+++ b/source/RobotAPI/components/units/BusInspectionUnit.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    Core
  * @author     Matthias Hadlich (matthias dot hadlich at student dot kit dot edu)
  * @copyright  2014 Matthias Hadlich
- * @license    http://www.gnu.org/licenses/gpl.txt
+ * @license    http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -32,12 +31,14 @@ using namespace std;
 using namespace armarx;
 
 
-void BusInspectionUnit::onInitComponent() {
-     this->onInitBusInspectionUnit();
-     offeringTopic("HardwareValues");
+void BusInspectionUnit::onInitComponent()
+{
+    this->onInitBusInspectionUnit();
+    offeringTopic("HardwareValues");
 }
 
-void BusInspectionUnit::onConnectComponent() {
+void BusInspectionUnit::onConnectComponent()
+{
 
     ARMARX_INFO << flush;
 
@@ -52,24 +53,29 @@ void BusInspectionUnit::onConnectComponent() {
     this->onConnectBusInspectionUnit();
 }
 
-void BusInspectionUnit::onExitComponent() {
-  this->onExitBusInspectionUnit();
+void BusInspectionUnit::onExitComponent()
+{
+    this->onExitBusInspectionUnit();
 }
 
 
-BusNames BusInspectionUnit::getConfiguredBusses( const Ice::Current& c) {
+BusNames BusInspectionUnit::getConfiguredBusses(const Ice::Current& c)
+{
     return *(new vector<string>());
 }
-BusInformation BusInspectionUnit::getBusInformation(const std::string& bus, const Ice::Current& c){
+BusInformation BusInspectionUnit::getBusInformation(const std::string& bus, const Ice::Current& c)
+{
     return *(new BusInformation);
-  
+
 }
-DeviceNames BusInspectionUnit::getDevicesOnBus(const std::string &bus, const Ice::Current& c ){
-      return *(new vector<string>());
+DeviceNames BusInspectionUnit::getDevicesOnBus(const std::string& bus, const Ice::Current& c)
+{
+    return *(new vector<string>());
 }
 
-DeviceInformation BusInspectionUnit::getDeviceInformation(const std::string& device,  const Ice::Current& c ) {
-  return *(new DeviceInformation);
+DeviceInformation BusInspectionUnit::getDeviceInformation(const std::string& device,  const Ice::Current& c)
+{
+    return *(new DeviceInformation);
 }
 
 Ice::Int BusInspectionUnit::performDeviceOperation(BasicOperation operation, Ice::Int device,  const Ice::Current& c)
@@ -77,7 +83,7 @@ Ice::Int BusInspectionUnit::performDeviceOperation(BasicOperation operation, Ice
     return 0;
 }
 
-Ice::Int BusInspectionUnit::performBusOperation(BasicOperation operation, const std::string &bus,  const Ice::Current& c)
+Ice::Int BusInspectionUnit::performBusOperation(BasicOperation operation, const std::string& bus,  const Ice::Current& c)
 {
     return 0;
 }
@@ -88,7 +94,8 @@ bool BusInspectionUnit::isInRealTimeMode(const Ice::Current& c)
 }
 
 
-std::string BusInspectionUnit::sendCommand(const std::string& command,  Ice::Int device, const Ice::Current& c ) {
+std::string BusInspectionUnit::sendCommand(const std::string& command,  Ice::Int device, const Ice::Current& c)
+{
     return "";
 }
 
@@ -96,7 +103,7 @@ std::string BusInspectionUnit::sendCommand(const std::string& command,  Ice::Int
 PropertyDefinitionsPtr BusInspectionUnit::createPropertyDefinitions()
 {
     return PropertyDefinitionsPtr(new BusInspectionUnitPropertyDefinitions(
-                                           getConfigIdentifier()));
+                                      getConfigIdentifier()));
 }
 
 
diff --git a/source/RobotAPI/components/units/BusInspectionUnit.h b/source/RobotAPI/components/units/BusInspectionUnit.h
index e0983a4c2b1f5a18f29d82bb89274de31e898f73..98a3dcaa788c7df5198b24b99cb45aea39d561e8 100644
--- a/source/RobotAPI/components/units/BusInspectionUnit.h
+++ b/source/RobotAPI/components/units/BusInspectionUnit.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    Core
  * @author     Matthias Hadlich (matthias dot hadlich at student dot kit dot edu)
  * @copyright  2014 Matthias Hadlich
- * @license    http://www.gnu.org/licenses/gpl.txt
+ * @license    http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -26,9 +25,9 @@
 
 #include <string>
 
-#include <Core/core/Component.h>
-#include <Core/core/application/properties/Properties.h>
-#include <Core/core/system/ImportExportComponent.h>
+#include <ArmarXCore/core/Component.h>
+#include <ArmarXCore/core/application/properties/Properties.h>
+#include <ArmarXCore/core/system/ImportExportComponent.h>
 
 #include <RobotAPI/interface/hardware/BusInspectionInterface.h>
 
@@ -39,15 +38,15 @@ namespace armarx
      * \brief
      */
     class BusInspectionUnitPropertyDefinitions:
-           public ComponentPropertyDefinitions
+        public ComponentPropertyDefinitions
     {
-        public:
-            BusInspectionUnitPropertyDefinitions(std::string prefix) :
-                ComponentPropertyDefinitions(prefix)
-            {
-            }
+    public:
+        BusInspectionUnitPropertyDefinitions(std::string prefix) :
+            ComponentPropertyDefinitions(prefix)
+        {
+        }
     };
-  
+
     /**
      * \class BusInspectionUnit
      * \ingroup RobotAPI-SensorActorUnits
@@ -56,40 +55,43 @@ namespace armarx
      * BusInspectionUnit is the base class of a unit that allows the introspection of a connected bus system.
      */
     class BusInspectionUnit :
-            virtual public BusInspectionInterface, virtual public Component
+        virtual public BusInspectionInterface, virtual public Component
+    {
+    public:
+        // inherited from Component
+        virtual std::string getDefaultName() const
         {
-        public:
-            // inherited from Component
-            virtual std::string getDefaultName() const { return "BusInspectionUnit"; }
-            virtual void onInitComponent();
-            virtual void onConnectComponent();
-            virtual void onExitComponent();
-
-            virtual void onInitBusInspectionUnit() = 0;
-            virtual void onConnectBusInspectionUnit() = 0;
-            virtual void onExitBusInspectionUnit() = 0;
-
-             virtual BusNames getConfiguredBusses( const Ice::Current& c = ::Ice::Current());
-             virtual BusInformation getBusInformation(const std::string &bus, const Ice::Current& c = ::Ice::Current());
-             virtual DeviceNames getDevicesOnBus(const std::string &bus, const Ice::Current& c = ::Ice::Current());
-             virtual DeviceInformation getDeviceInformation(const std::string &device,  const Ice::Current& c = ::Ice::Current());
-
-             virtual Ice::Int performDeviceOperation(BasicOperation operation, Ice::Int device,  const Ice::Current& c = ::Ice::Current());
-             virtual Ice::Int performBusOperation(BasicOperation operation, const std::string &bus,  const Ice::Current& c = ::Ice::Current());
-             virtual bool isInRealTimeMode(const Ice::Current& c = ::Ice::Current());
-
-             virtual std::string sendCommand(const std::string &command,  Ice::Int device, const Ice::Current& c = ::Ice::Current());
-
-             /**
-              * \see PropertyUser::createPropertyDefinitions()
-              */
-             virtual PropertyDefinitionsPtr createPropertyDefinitions();
-
-          protected:
-            std::string channel;
-            BusInspectionInterfacePrx busInspectionValuePrx; // gets commands from hardware
-
-        };
+            return "BusInspectionUnit";
+        }
+        virtual void onInitComponent();
+        virtual void onConnectComponent();
+        virtual void onExitComponent();
+
+        virtual void onInitBusInspectionUnit() = 0;
+        virtual void onConnectBusInspectionUnit() = 0;
+        virtual void onExitBusInspectionUnit() = 0;
+
+        virtual BusNames getConfiguredBusses(const Ice::Current& c = ::Ice::Current());
+        virtual BusInformation getBusInformation(const std::string& bus, const Ice::Current& c = ::Ice::Current());
+        virtual DeviceNames getDevicesOnBus(const std::string& bus, const Ice::Current& c = ::Ice::Current());
+        virtual DeviceInformation getDeviceInformation(const std::string& device,  const Ice::Current& c = ::Ice::Current());
+
+        virtual Ice::Int performDeviceOperation(BasicOperation operation, Ice::Int device,  const Ice::Current& c = ::Ice::Current());
+        virtual Ice::Int performBusOperation(BasicOperation operation, const std::string& bus,  const Ice::Current& c = ::Ice::Current());
+        virtual bool isInRealTimeMode(const Ice::Current& c = ::Ice::Current());
+
+        virtual std::string sendCommand(const std::string& command,  Ice::Int device, const Ice::Current& c = ::Ice::Current());
+
+        /**
+         * \see PropertyUser::createPropertyDefinitions()
+         */
+        virtual PropertyDefinitionsPtr createPropertyDefinitions();
+
+    protected:
+        std::string channel;
+        BusInspectionInterfacePrx busInspectionValuePrx; // gets commands from hardware
+
+    };
 }
 
 
diff --git a/source/RobotAPI/components/units/CMakeLists.txt b/source/RobotAPI/components/units/CMakeLists.txt
index d5244fe973aa2a31d5cad9cd903b068f7e072fbe..88a819376ebf0782b936810614319d8adef17994 100644
--- a/source/RobotAPI/components/units/CMakeLists.txt
+++ b/source/RobotAPI/components/units/CMakeLists.txt
@@ -14,8 +14,8 @@ if (Eigen3_FOUND AND Simox_FOUND)
 endif()
 
 set(LIB_NAME       RobotAPIUnits)
-set(LIB_VERSION    0.1.0)
-set(LIB_SOVERSION  0)
+
+
 
 set(LIBS
     RobotAPICore
@@ -45,6 +45,7 @@ set(LIB_HEADERS
     KinematicUnitObserver.h
     PlatformUnitObserver.h
     SensorActorUnit.h
+    ATINetFTUnit.h
 )
 
 set(LIB_FILES
@@ -69,6 +70,7 @@ set(LIB_FILES
     KinematicUnitObserver.cpp
     PlatformUnitObserver.cpp
     SensorActorUnit.cpp
+    ATINetFTUnit.cpp
 )
 
-armarx_add_library("${LIB_NAME}" "${LIB_VERSION}" "${LIB_SOVERSION}" "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
+armarx_add_library("${LIB_NAME}"  "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
diff --git a/source/RobotAPI/components/units/ForceTorqueObserver.cpp b/source/RobotAPI/components/units/ForceTorqueObserver.cpp
index 540e657d73028dbb89f89b3494fd98e325a266fd..2fa220da656ab2d002693284a68f4e4ab660f74e 100644
--- a/source/RobotAPI/components/units/ForceTorqueObserver.cpp
+++ b/source/RobotAPI/components/units/ForceTorqueObserver.cpp
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,21 +16,21 @@
 * @package    ArmarX::
 * @author     Mirko Waechter ( mirko.waechter at kit dot edu)
 * @date       2013
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
 #include "ForceTorqueObserver.h"
 
-#include <Core/observers/checks/ConditionCheckUpdated.h>
-#include <Core/observers/checks/ConditionCheckEquals.h>
-#include <Core/observers/checks/ConditionCheckInRange.h>
-#include <Core/observers/checks/ConditionCheckLarger.h>
-#include <Core/observers/checks/ConditionCheckSmaller.h>
-#include <Core/observers/checks/ConditionCheckEqualsWithTolerance.h>
+#include <ArmarXCore/observers/checks/ConditionCheckUpdated.h>
+#include <ArmarXCore/observers/checks/ConditionCheckEquals.h>
+#include <ArmarXCore/observers/checks/ConditionCheckInRange.h>
+#include <ArmarXCore/observers/checks/ConditionCheckLarger.h>
+#include <ArmarXCore/observers/checks/ConditionCheckSmaller.h>
+#include <ArmarXCore/observers/checks/ConditionCheckEqualsWithTolerance.h>
 #include <RobotAPI/libraries/core/checks/ConditionCheckMagnitudeChecks.h>
 #include <RobotAPI/libraries/core/observerfilters/OffsetFilter.h>
-#include <Core/observers/variant/DatafieldRef.h>
+#include <ArmarXCore/observers/variant/DatafieldRef.h>
 
 #include <RobotAPI/libraries/core/RobotAPIObjectFactories.h>
 
@@ -57,10 +56,14 @@ void ForceTorqueObserver::setTopicName(std::string topicName)
 
 void ForceTorqueObserver::onInitObserver()
 {
-    if(topicName.empty())
+    if (topicName.empty())
+    {
         usingTopic(getProperty<std::string>("ForceTorqueTopicName").getValue());
+    }
     else
+    {
         usingTopic(topicName);
+    }
 
     // register all checks
     offerConditionCheck("updated", new ConditionCheckUpdated());
@@ -84,20 +87,20 @@ void ForceTorqueObserver::onConnectObserver()
 PropertyDefinitionsPtr ForceTorqueObserver::createPropertyDefinitions()
 {
     return PropertyDefinitionsPtr(new ForceTorqueObserverPropertyDefinitions(
-                                           getConfigIdentifier()));
+                                      getConfigIdentifier()));
 }
 
 
-void ForceTorqueObserver::offerValue(std::string nodeName, const std::string &type, FramedDirectionBasePtr value, const DataFieldIdentifierPtr& id)
+void ForceTorqueObserver::offerValue(std::string nodeName, const std::string& type, FramedDirectionBasePtr value, const DataFieldIdentifierPtr& id)
 {
     FramedDirectionPtr vec = FramedDirectionPtr::dynamicCast(value);
 
-    if(!existsChannel(id->channelName))
+    if (!existsChannel(id->channelName))
     {
         offerChannel(id->channelName, type + " vectors on specific parts of the robot.");
     }
 
-    if(!existsDataField(id->channelName, id->datafieldName))
+    if (!existsDataField(id->channelName, id->datafieldName))
     {
         offerDataFieldWithDefault(id->channelName, id->datafieldName, Variant(value), "3D vector for " + type + " of " + nodeName);
     }
@@ -109,39 +112,44 @@ void ForceTorqueObserver::offerValue(std::string nodeName, const std::string &ty
 
     // pod = plain old data
     std::string pod_channelName = id->channelName + POD_SUFFIX;
-    if(!existsChannel(pod_channelName) )
+
+    if (!existsChannel(pod_channelName))
     {
         offerChannel(pod_channelName, id->datafieldName + " on " + nodeName + " as plain old data (pod)");
     }
+
     offerOrUpdateDataField(pod_channelName, id->datafieldName + "_x", Variant(vec->x), type + " on X axis");
     offerOrUpdateDataField(pod_channelName, id->datafieldName + "_y", Variant(vec->y), type + " on Y axis");
     offerOrUpdateDataField(pod_channelName, id->datafieldName + "_z", Variant(vec->z), type + " on Z axis");
     offerOrUpdateDataField(pod_channelName, id->datafieldName + "_frame", Variant(vec->frame), "Frame of " + value->frame);
 }
 
-void armarx::ForceTorqueObserver::reportSensorValues(const std::string &sensorNodeName, const FramedDirectionBasePtr &forces, const FramedDirectionBasePtr &torques, const Ice::Current &)
+void armarx::ForceTorqueObserver::reportSensorValues(const std::string& sensorNodeName, const FramedDirectionBasePtr& forces, const FramedDirectionBasePtr& torques, const Ice::Current&)
 {
     ScopedLock lock(dataMutex);
 
     try
     {
         DataFieldIdentifierPtr id;
-        if(forces)
+
+        if (forces)
         {
             id = getForceDatafieldId(sensorNodeName, forces->frame);
             std::string type = "forces";
             offerValue(sensorNodeName, type, forces, id);
         }
-        if(torques)
+
+        if (torques)
         {
             id = getTorqueDatafieldId(sensorNodeName, torques->frame);
             std::string type = "torques";
             offerValue(sensorNodeName, type, torques, id);
         }
+
         updateChannel(id->channelName);
         updateChannel(id->channelName + POD_SUFFIX);
     }
-    catch(std::exception&e)
+    catch (std::exception& e)
     {
         ARMARX_ERROR << "Reporting force torque for " << sensorNodeName << " failed! ";
         handleExceptions();
@@ -149,53 +157,77 @@ void armarx::ForceTorqueObserver::reportSensorValues(const std::string &sensorNo
 }
 
 
-DatafieldRefBasePtr armarx::ForceTorqueObserver::createNulledDatafield(const DatafieldRefBasePtr &forceTorqueDatafieldRef, const Ice::Current &)
+DatafieldRefBasePtr armarx::ForceTorqueObserver::createNulledDatafield(const DatafieldRefBasePtr& forceTorqueDatafieldRef, const Ice::Current&)
 {
     return createFilteredDatafield(new filters::OffsetFilter(), forceTorqueDatafieldRef);
 }
 
-DatafieldRefBasePtr ForceTorqueObserver::getForceDatafield(const std::string &nodeName, const Ice::Current &)
+DatafieldRefBasePtr ForceTorqueObserver::getForceDatafield(const std::string& nodeName, const Ice::Current&)
 {
     auto id = getForceDatafieldId(nodeName, nodeName);
-    if(!existsChannel(id->channelName))
+
+    if (!existsChannel(id->channelName))
+    {
         throw UserException("No sensor for node '" + nodeName + "'available: channel " + id->channelName);
-    if(!existsDataField(id->channelName, id->datafieldName))
+    }
+
+    if (!existsDataField(id->channelName, id->datafieldName))
+    {
         throw UserException("No sensor for node '" + nodeName + "'available: datafield " + id->datafieldName);
+    }
 
     return new DatafieldRef(this, id->channelName, id->datafieldName);
 
 }
 
-DatafieldRefBasePtr ForceTorqueObserver::getTorqueDatafield(const std::string &nodeName, const Ice::Current &)
+DatafieldRefBasePtr ForceTorqueObserver::getTorqueDatafield(const std::string& nodeName, const Ice::Current&)
 {
     auto id = getTorqueDatafieldId(nodeName, nodeName);
-    if(!existsChannel(id->channelName))
+
+    if (!existsChannel(id->channelName))
+    {
         throw UserException("No sensor for node '" + nodeName + "'available: channel " + id->channelName);
-    if(!existsDataField(id->channelName, id->datafieldName))
+    }
+
+    if (!existsDataField(id->channelName, id->datafieldName))
+    {
         throw UserException("No sensor for node '" + nodeName + "'available: datafield " + id->datafieldName);
+    }
 
     return new DatafieldRef(this, id->channelName, id->datafieldName);
 }
 
-DataFieldIdentifierPtr ForceTorqueObserver::getForceDatafieldId(const std::string &nodeName, const std::string &frame)
+DataFieldIdentifierPtr ForceTorqueObserver::getForceDatafieldId(const std::string& nodeName, const std::string& frame)
 {
     std::string channelName;
-    if(frame == nodeName)
+
+    if (frame == nodeName)
+    {
         channelName = nodeName;
+    }
     else
+    {
         channelName = nodeName + "_" + frame;
+    }
+
     std::string datafieldName = "forces";
     DataFieldIdentifierPtr id = new DataFieldIdentifier(getName(), channelName, datafieldName);
     return id;
 }
 
-DataFieldIdentifierPtr ForceTorqueObserver::getTorqueDatafieldId(const std::string &nodeName, const std::string &frame)
+DataFieldIdentifierPtr ForceTorqueObserver::getTorqueDatafieldId(const std::string& nodeName, const std::string& frame)
 {
     std::string channelName;
-    if(frame == nodeName)
+
+    if (frame == nodeName)
+    {
         channelName = nodeName;
+    }
     else
+    {
         channelName = nodeName + "_" + frame;
+    }
+
     std::string datafieldName = "torques";
     DataFieldIdentifierPtr id = new DataFieldIdentifier(getName(), channelName, datafieldName);
     return id;
diff --git a/source/RobotAPI/components/units/ForceTorqueObserver.h b/source/RobotAPI/components/units/ForceTorqueObserver.h
index 4554f0e98c69bd6a7ea13dd426ec50fdd4e1c701..8aa5dbd05cf2ebcd1b8ebe227c6fe70823811215 100644
--- a/source/RobotAPI/components/units/ForceTorqueObserver.h
+++ b/source/RobotAPI/components/units/ForceTorqueObserver.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::
 * @author     Mirko Waechter ( mirko.waechter at kit dot edu)
 * @date       2013
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -26,7 +25,7 @@
 
 #include <RobotAPI/interface/units/ForceTorqueUnit.h>
 #include <RobotAPI/libraries/core/FramedPose.h>
-#include <Core/observers/Observer.h>
+#include <ArmarXCore/observers/Observer.h>
 
 namespace armarx
 {
@@ -35,13 +34,13 @@ namespace armarx
      * \brief
      */
     class ForceTorqueObserverPropertyDefinitions:
-            public ComponentPropertyDefinitions
+        public ComponentPropertyDefinitions
     {
     public:
         ForceTorqueObserverPropertyDefinitions(std::string prefix):
             ComponentPropertyDefinitions(prefix)
         {
-            defineRequiredProperty<std::string>("ForceTorqueTopicName","Name of the ForceTorqueUnit Topic");
+            defineRequiredProperty<std::string>("ForceTorqueTopicName", "Name of the ForceTorqueUnit Topic");
         }
     };
 
@@ -54,8 +53,8 @@ namespace armarx
      * Available condition checks are: *updated*, *larger*, *equals*, *smaller* and *magnitudelarger*.
      */
     class ForceTorqueObserver :
-            virtual public Observer,
-            virtual public ForceTorqueUnitObserverInterface
+        virtual public Observer,
+        virtual public ForceTorqueUnitObserverInterface
     {
     public:
         ForceTorqueObserver();
@@ -63,11 +62,14 @@ namespace armarx
         void setTopicName(std::string topicName);
 
         // framework hooks
-        virtual std::string getDefaultName() const { return "ForceTorqueUnitObserver"; }
+        virtual std::string getDefaultName() const
+        {
+            return "ForceTorqueUnitObserver";
+        }
         void onInitObserver();
         void onConnectObserver();
 
-        virtual void reportSensorValues(const std::string &sensorNodeName, const FramedDirectionBasePtr &forces, const FramedDirectionBasePtr &torques, const Ice::Current &);
+        virtual void reportSensorValues(const std::string& sensorNodeName, const FramedDirectionBasePtr& forces, const FramedDirectionBasePtr& torques, const Ice::Current&);
 
         /**
          * @see PropertyUser::createPropertyDefinitions()
@@ -84,17 +86,17 @@ namespace armarx
         std::string topicName;
 
 
-        void offerValue(std::string nodeName, const std::string &type, FramedDirectionBasePtr value, const DataFieldIdentifierPtr& id);
+        void offerValue(std::string nodeName, const std::string& type, FramedDirectionBasePtr value, const DataFieldIdentifierPtr& id);
 
         // ForceTorqueUnitObserverInterface interface
     public:
-        DatafieldRefBasePtr createNulledDatafield(const DatafieldRefBasePtr &forceTorqueDatafieldRef, const Ice::Current &);
+        DatafieldRefBasePtr createNulledDatafield(const DatafieldRefBasePtr& forceTorqueDatafieldRef, const Ice::Current&);
 
-        DatafieldRefBasePtr getForceDatafield(const std::string &nodeName, const Ice::Current &);
-        DatafieldRefBasePtr getTorqueDatafield(const std::string &nodeName, const Ice::Current &);
+        DatafieldRefBasePtr getForceDatafield(const std::string& nodeName, const Ice::Current&);
+        DatafieldRefBasePtr getTorqueDatafield(const std::string& nodeName, const Ice::Current&);
 
-        DataFieldIdentifierPtr getForceDatafieldId(const std::string &nodeName, const std::string &frame);
-        DataFieldIdentifierPtr getTorqueDatafieldId(const std::string &nodeName, const std::string &frame);
+        DataFieldIdentifierPtr getForceDatafieldId(const std::string& nodeName, const std::string& frame);
+        DataFieldIdentifierPtr getTorqueDatafieldId(const std::string& nodeName, const std::string& frame);
     };
 }
 
diff --git a/source/RobotAPI/components/units/ForceTorqueUnit.cpp b/source/RobotAPI/components/units/ForceTorqueUnit.cpp
index dd18a056d60b74988898c824235960f98f731c11..38684050cbb157d1e6e6be9770714f75426ed3ef 100644
--- a/source/RobotAPI/components/units/ForceTorqueUnit.cpp
+++ b/source/RobotAPI/components/units/ForceTorqueUnit.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    ArmarXCore::units
  * @author     Peter Kaiser <peter dot kaiser at kit dot edu>
  * @date       2011
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
diff --git a/source/RobotAPI/components/units/ForceTorqueUnit.h b/source/RobotAPI/components/units/ForceTorqueUnit.h
index b239859437bddfcc6538b61a8cf7460d7fb9ca2c..2ec0ae0c4d7eed1c3210fede45a023322131fc0a 100644
--- a/source/RobotAPI/components/units/ForceTorqueUnit.h
+++ b/source/RobotAPI/components/units/ForceTorqueUnit.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    ArmarXCore::units
  * @author     Peter Kaiser <peter dot kaiser at kit dot edu>
  * @date       2011
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -25,9 +24,9 @@
 #define _ARMARX_COMPONENT_FORCE_TORQUE_UNIT_H
 
 
-#include <Core/core/Component.h>
-#include <Core/core/application/properties/Properties.h>
-#include <Core/core/system/ImportExportComponent.h>
+#include <ArmarXCore/core/Component.h>
+#include <ArmarXCore/core/application/properties/Properties.h>
+#include <ArmarXCore/core/system/ImportExportComponent.h>
 #include "RobotAPI/components/units/SensorActorUnit.h"
 
 #include <RobotAPI/interface/units/ForceTorqueUnit.h>
@@ -42,20 +41,20 @@ namespace armarx
      */
     class ForceTorqueUnitPropertyDefinitions : public ComponentPropertyDefinitions
     {
-        public:
-            ForceTorqueUnitPropertyDefinitions(std::string prefix) :
-                ComponentPropertyDefinitions(prefix)
-            {
-                defineRequiredProperty<std::string>("AgentName", "Name of the agent for which the sensor values are provided");
-                defineOptionalProperty<std::string>("ForceTorqueTopicName","ForceTorqueValues", "Name of the topic on which the sensor values are provided");
+    public:
+        ForceTorqueUnitPropertyDefinitions(std::string prefix) :
+            ComponentPropertyDefinitions(prefix)
+        {
+            defineRequiredProperty<std::string>("AgentName", "Name of the agent for which the sensor values are provided");
+            defineOptionalProperty<std::string>("ForceTorqueTopicName", "ForceTorqueValues", "Name of the topic on which the sensor values are provided");
 
 
-                // No required properties
-            }
+            // No required properties
+        }
     };
-    
+
     /**
-     * \class ForceTorqueUnit
+     * \defgroup Component-ForceTorqueUnit ForceTorqueUnit
      * \ingroup RobotAPI-SensorActorUnits
      * \brief Base unit for force/torque sensors.
      *
@@ -64,26 +63,34 @@ namespace armarx
      * RobotAPI contains the ForceTorqueUnitSimulation class that does a very basic simulation of F/T-sensors.
      * Other (hardware related) implementations of this unit can be found in the respective ArmarX projects.
      */
+
+    /**
+     * @ingroup Component-ForceTorqueUnit
+     * @brief The ForceTorqueUnit class
+     */
     class ForceTorqueUnit :
         virtual public ForceTorqueUnitInterface,
         virtual public SensorActorUnit
     {
-        public:
-            virtual std::string getDefaultName() const { return "ForceTorqueUnit"; }
-            
-            virtual void onInitComponent();
-            virtual void onConnectComponent();
-            virtual void onExitComponent();
-            
-            virtual void onInitForceTorqueUnit() = 0;
-            virtual void onStartForceTorqueUnit() = 0;
-            virtual void onExitForceTorqueUnit() = 0;
-            
-            virtual PropertyDefinitionsPtr createPropertyDefinitions();
-            
-        protected:
-            ForceTorqueUnitListenerPrx listenerPrx;
-            std::string listenerName;
+    public:
+        virtual std::string getDefaultName() const
+        {
+            return "ForceTorqueUnit";
+        }
+
+        virtual void onInitComponent();
+        virtual void onConnectComponent();
+        virtual void onExitComponent();
+
+        virtual void onInitForceTorqueUnit() = 0;
+        virtual void onStartForceTorqueUnit() = 0;
+        virtual void onExitForceTorqueUnit() = 0;
+
+        virtual PropertyDefinitionsPtr createPropertyDefinitions();
+
+    protected:
+        ForceTorqueUnitListenerPrx listenerPrx;
+        std::string listenerName;
     };
 }
 
diff --git a/source/RobotAPI/components/units/ForceTorqueUnitSimulation.cpp b/source/RobotAPI/components/units/ForceTorqueUnitSimulation.cpp
index 42fb1c8ba4bdc24bd7bdd8fe10bb49b8f970d6ec..e0a44e3f16e29f25a5322ec6b247c2e9ba36a152 100644
--- a/source/RobotAPI/components/units/ForceTorqueUnitSimulation.cpp
+++ b/source/RobotAPI/components/units/ForceTorqueUnitSimulation.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    RobotAPI::units
  * @author     Peter Kaiser (peter dot kaiser at kit dot edu)
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -40,7 +39,7 @@ void ForceTorqueUnitSimulation::onInitForceTorqueUnit()
     //{
     //    forces[*s] = new armarx::FramedDirection(Eigen::Vector3f(0, 0, 0), *s);
     //    torques[*s] = new armarx::FramedDirection(Eigen::Vector3f(0, 0, 0), *s);
-   // }
+    // }
     forces = new armarx::FramedDirection(Eigen::Vector3f(0, 0, 0), sensorName, getProperty<std::string>("AgentName").getValue());
     torques = new armarx::FramedDirection(Eigen::Vector3f(0, 0, 0), sensorName, getProperty<std::string>("AgentName").getValue());
 
@@ -68,12 +67,12 @@ void ForceTorqueUnitSimulation::simulationFunction()
     //listenerPrx->reportSensorValues(torques);
 }
 
-void ForceTorqueUnitSimulation::setOffset(const FramedDirectionBasePtr &forceOffsets, const FramedDirectionBasePtr &torqueOffsets, const Ice::Current &c)
+void ForceTorqueUnitSimulation::setOffset(const FramedDirectionBasePtr& forceOffsets, const FramedDirectionBasePtr& torqueOffsets, const Ice::Current& c)
 {
     // Ignore
 }
 
-void ForceTorqueUnitSimulation::setToNull(const Ice::Current &c)
+void ForceTorqueUnitSimulation::setToNull(const Ice::Current& c)
 {
     // Ignore
 }
diff --git a/source/RobotAPI/components/units/ForceTorqueUnitSimulation.h b/source/RobotAPI/components/units/ForceTorqueUnitSimulation.h
index c7594288e2b1a099d6711f17be936d0ab62e3d10..cc4505a6cf781a0d1f5cd5dbb4170ed6e4d0e1a7 100644
--- a/source/RobotAPI/components/units/ForceTorqueUnitSimulation.h
+++ b/source/RobotAPI/components/units/ForceTorqueUnitSimulation.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    RobotAPI::units
  * @author     Peter Kaiser (peter dot kaiser at kit dot edu)
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -26,8 +25,8 @@
 
 #include "ForceTorqueUnit.h"
 
-#include <Core/core/services/tasks/PeriodicTask.h>
-#include <Core/core/system/ImportExportComponent.h>
+#include <ArmarXCore/core/services/tasks/PeriodicTask.h>
+#include <ArmarXCore/core/system/ImportExportComponent.h>
 #include <RobotAPI/libraries/core/FramedPose.h>
 
 #include <IceUtil/Time.h>
@@ -41,7 +40,7 @@ namespace armarx
      * \brief
      */
     class ForceTorqueUnitSimulationPropertyDefinitions :
-            public ForceTorqueUnitPropertyDefinitions
+        public ForceTorqueUnitPropertyDefinitions
     {
     public:
         ForceTorqueUnitSimulationPropertyDefinitions(std::string prefix) :
@@ -78,7 +77,7 @@ namespace armarx
         /**
          * \warning Not implemented yet
          */
-        virtual void setOffset(const FramedDirectionBasePtr &forceOffsets, const FramedDirectionBasePtr &torqueOffsets, const Ice::Current& c = ::Ice::Current());
+        virtual void setOffset(const FramedDirectionBasePtr& forceOffsets, const FramedDirectionBasePtr& torqueOffsets, const Ice::Current& c = ::Ice::Current());
 
         /**
          * \warning Not implemented yet
diff --git a/source/RobotAPI/components/units/HandUnit.cpp b/source/RobotAPI/components/units/HandUnit.cpp
index 8c8eb50c02ac931bae337fe8dafcdeb0dc730ce5..b30f96136afd126e2f7b90e7b5ef4b0c4aae6b31 100644
--- a/source/RobotAPI/components/units/HandUnit.cpp
+++ b/source/RobotAPI/components/units/HandUnit.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,14 +16,14 @@
  * @package    ArmarXCore::units
  * @author     Manfred Kroehnert (Manfred dot Kroehnert at kit dot edu)
  * @date       2013
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 
 #include "HandUnit.h"
 
-#include <Core/core/system/ArmarXDataPath.h>
+#include <ArmarXCore/core/system/ArmarXDataPath.h>
 
 #include <VirtualRobot/VirtualRobot.h>
 #include <VirtualRobot/EndEffector/EndEffector.h>
@@ -51,37 +50,47 @@ void HandUnit::onInitComponent()
     {
         robot = VirtualRobot::RobotIO::loadRobot(endeffectorFile, VirtualRobot::RobotIO::eStructure);
     }
-    catch(VirtualRobot::VirtualRobotException& e)
+    catch (VirtualRobot::VirtualRobotException& e)
     {
         throw UserException(e.what());
     }
 
-    if(endeffectorName == "")
+    if (endeffectorName == "")
     {
         throw UserException("EndeffectorName not defined");
     }
-    if(!robot->hasEndEffector(endeffectorName))
+
+    if (!robot->hasEndEffector(endeffectorName))
     {
         throw UserException("Robot does not contain an endeffector with name: " + endeffectorName);
     }
+
     eef = robot->getEndEffector(endeffectorName);
     robotName = robot->getName();
+
     if (eef->getTcp())
+    {
         tcpName = robot->getEndEffector(endeffectorName)->getTcp()->getName();
+    }
     else
+    {
         throw UserException("Endeffector without TCP: " + endeffectorName);
+    }
 
     // get all joints
     std::vector<EndEffectorActorPtr> actors;
     eef->getActors(actors);
-    for (size_t i=0;i<actors.size();i++)
+
+    for (size_t i = 0; i < actors.size(); i++)
     {
         EndEffectorActorPtr a = actors[i];
         std::vector<EndEffectorActor::ActorDefinition> ads;// = a->getDefinition();
-        for (size_t j=0;j<ads.size();j++)
+
+        for (size_t j = 0; j < ads.size(); j++)
         {
             EndEffectorActor::ActorDefinition ad = ads[j];
-            if (ad.directionAndSpeed!=0 && ad.robotNode)
+
+            if (ad.directionAndSpeed != 0 && ad.robotNode)
             {
                 handJoints[ad.robotNode->getName()] = ad.directionAndSpeed;
             }
@@ -92,7 +101,8 @@ void HandUnit::onInitComponent()
 
     shapeNames = new SingleTypeVariantList(VariantType::String);
     std::vector<std::string>::const_iterator iter = endeffectorPreshapes.begin();
-    while(iter != endeffectorPreshapes.end())
+
+    while (iter != endeffectorPreshapes.end())
     {
         Variant currentPreshape;
         currentPreshape.setString(*iter);
@@ -139,34 +149,36 @@ SingleTypeVariantListBasePtr HandUnit::getShapeNames(const Ice::Current& c)
 PropertyDefinitionsPtr HandUnit::createPropertyDefinitions()
 {
     return PropertyDefinitionsPtr(new HandUnitPropertyDefinitions(
-                                           getConfigIdentifier()));
+                                      getConfigIdentifier()));
 }
 
 
-NameValueMap HandUnit::getShapeJointValues(const std::string &shapeName, const Ice::Current &)
+NameValueMap HandUnit::getShapeJointValues(const std::string& shapeName, const Ice::Current&)
 {
     EndEffectorPtr efp = robot->getEndEffector(getProperty<std::string>("EndeffectorName").getValue());
     RobotConfigPtr rc = efp->getPreshape(shapeName);
     return rc->getRobotNodeJointValueMap();
 }
 
-NameValueMap HandUnit::getCurrentJointValues(const Ice::Current &c)
+NameValueMap HandUnit::getCurrentJointValues(const Ice::Current& c)
 {
     NameValueMap result;
+
     for (auto j : handJoints)
     {
         result[j.first] = 0.0f;
     }
+
     return result;
 }
 
-void HandUnit::setObjectGrasped(const std::string &objectName, const Ice::Current &)
+void HandUnit::setObjectGrasped(const std::string& objectName, const Ice::Current&)
 {
-   ARMARX_INFO << "Object grasped " << objectName << flush;
-   graspedObject = objectName;
+    ARMARX_INFO << "Object grasped " << objectName << flush;
+    graspedObject = objectName;
 }
 
-void HandUnit::setObjectReleased(const std::string &objectName, const Ice::Current &)
+void HandUnit::setObjectReleased(const std::string& objectName, const Ice::Current&)
 {
     ARMARX_INFO << "Object released " << objectName << flush;
     graspedObject = "";
@@ -174,13 +186,13 @@ void HandUnit::setObjectReleased(const std::string &objectName, const Ice::Curre
 
 
 
-std::string armarx::HandUnit::getHandName(const Ice::Current &)
+std::string armarx::HandUnit::getHandName(const Ice::Current&)
 {
     return eef->getName();
 }
 
 
-void armarx::HandUnit::setJointAngles(const armarx::NameValueMap& targetJointAngles, const Ice::Current & c)
+void armarx::HandUnit::setJointAngles(const armarx::NameValueMap& targetJointAngles, const Ice::Current& c)
 {
 
 }
diff --git a/source/RobotAPI/components/units/HandUnit.h b/source/RobotAPI/components/units/HandUnit.h
index 3df2d52bc68e0cf2088f9e1445a8d7504931f65f..1fd2c51bfa6d13018024dae430a9346d0e58bb12 100644
--- a/source/RobotAPI/components/units/HandUnit.h
+++ b/source/RobotAPI/components/units/HandUnit.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    ArmarXCore::units
  * @author     Manfred Kroehnert (manfred dot kroehnert at kit dot edu)
  * @date       2013
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -28,9 +27,9 @@
 
 #include <RobotAPI/interface/units/HandUnitInterface.h>
 
-#include <Core/core/application/properties/Properties.h>
-#include <Core/core/system/ImportExportComponent.h>
-#include <Core/observers/variant/SingleTypeVariantList.h>
+#include <ArmarXCore/core/application/properties/Properties.h>
+#include <ArmarXCore/core/system/ImportExportComponent.h>
+#include <ArmarXCore/observers/variant/SingleTypeVariantList.h>
 
 
 
@@ -48,7 +47,7 @@ namespace armarx
      * \brief Defines all necessary properties for armarx::HandUnit
      */
     class HandUnitPropertyDefinitions:
-            public ComponentPropertyDefinitions
+        public ComponentPropertyDefinitions
     {
     public:
         HandUnitPropertyDefinitions(std::string prefix):
@@ -61,7 +60,7 @@ namespace armarx
 
 
     /**
-     * \class HandUnit
+     * @ingroup Component-HandUnit HandUnit
      * \brief Base unit for high-level access to robot hands.
      * \ingroup RobotAPI-SensorActorUnits
      *
@@ -69,6 +68,11 @@ namespace armarx
      * It uses the HandUnitListener Ice interface to report updates of its current state
      *
      */
+
+    /**
+     * @brief The HandUnit class
+     * @ingroup Component-HandUnit
+     */
     class HandUnit :
         virtual public HandUnitInterface,
         virtual public SensorActorUnit
@@ -120,12 +124,12 @@ namespace armarx
          */
         virtual SingleTypeVariantListBasePtr getShapeNames(const Ice::Current& c = ::Ice::Current());
 
-        NameValueMap getShapeJointValues(const std::string &shapeName, const Ice::Current & c = ::Ice::Current());
-        virtual NameValueMap getCurrentJointValues(const Ice::Current & c = ::Ice::Current());
+        NameValueMap getShapeJointValues(const std::string& shapeName, const Ice::Current& c = ::Ice::Current());
+        virtual NameValueMap getCurrentJointValues(const Ice::Current& c = ::Ice::Current());
 
-        void setObjectGrasped(const std::string& objectName, const Ice::Current &);
-        void setObjectReleased(const std::string& objectName, const Ice::Current &);
-        void setJointAngles(const NameValueMap& targetJointAngles, const Ice::Current &);
+        void setObjectGrasped(const std::string& objectName, const Ice::Current&);
+        void setObjectReleased(const std::string& objectName, const Ice::Current&);
+        void setJointAngles(const NameValueMap& targetJointAngles, const Ice::Current&);
 
         /**
          * \see armarx::PropertyUser::createPropertyDefinitions()
@@ -161,7 +165,7 @@ namespace armarx
 
         // HandUnitInterface interface
     public:
-        std::string getHandName(const Ice::Current &);
+        std::string getHandName(const Ice::Current&);
 
 
     };
diff --git a/source/RobotAPI/components/units/HandUnitSimulation.cpp b/source/RobotAPI/components/units/HandUnitSimulation.cpp
index 2b18416f7b6ac0f721f5b376520031ceaef2f8b4..96adc2d15d3ab7003a340ac74de95bd23356be9d 100644
--- a/source/RobotAPI/components/units/HandUnitSimulation.cpp
+++ b/source/RobotAPI/components/units/HandUnitSimulation.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    ArmarXCore::units
  * @author     David Schiebener (schiebener at kit dot edu)
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -57,7 +56,7 @@ void HandUnitSimulation::setShape(const std::string& shapeName, const Ice::Curre
 
 
 
-void armarx::HandUnitSimulation::setJointAngles(const NameValueMap& jointAngles, const Ice::Current &)
+void armarx::HandUnitSimulation::setJointAngles(const NameValueMap& jointAngles, const Ice::Current&)
 {
 
 }
diff --git a/source/RobotAPI/components/units/HandUnitSimulation.h b/source/RobotAPI/components/units/HandUnitSimulation.h
index 36a4d8a8359e500c21cc65bbb2f4c4369b6a328e..84fa0dd706d6dabda20f2d782747fa3f8b24ca29 100644
--- a/source/RobotAPI/components/units/HandUnitSimulation.h
+++ b/source/RobotAPI/components/units/HandUnitSimulation.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    ArmarXCore::units
  * @author     David Schiebener (schiebener at kit dot edu)
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -34,14 +33,14 @@ namespace armarx
      * \brief Defines all necessary properties for armarx::HandUnitSimulation
      */
     class HandUnitSimulationPropertyDefinitions:
-            public ComponentPropertyDefinitions
+        public ComponentPropertyDefinitions
     {
     public:
         HandUnitSimulationPropertyDefinitions(std::string prefix):
             ComponentPropertyDefinitions(prefix)
         {
-            defineRequiredProperty<std::string>("RobotFileName","VirtualRobot XML file in which the endeffector is is stored.");
-            defineRequiredProperty<std::string>("EndeffectorName","Name of the endeffector as stored in the XML file (will publish values on EndeffectorName + 'State')");
+            defineRequiredProperty<std::string>("RobotFileName", "VirtualRobot XML file in which the endeffector is is stored.");
+            defineRequiredProperty<std::string>("EndeffectorName", "Name of the endeffector as stored in the XML file (will publish values on EndeffectorName + 'State')");
         }
     };
 
diff --git a/source/RobotAPI/components/units/HapticObserver.cpp b/source/RobotAPI/components/units/HapticObserver.cpp
index 9bb402e9665847f305f0bac5bd318e298bf84c7a..569894080e054db4adcfd7e6c8639341dc21996a 100644
--- a/source/RobotAPI/components/units/HapticObserver.cpp
+++ b/source/RobotAPI/components/units/HapticObserver.cpp
@@ -1,15 +1,15 @@
 #include "HapticObserver.h"
 
-#include <Core/observers/checks/ConditionCheckUpdated.h>
-#include <Core/observers/checks/ConditionCheckEquals.h>
-#include <Core/observers/checks/ConditionCheckInRange.h>
-#include <Core/observers/checks/ConditionCheckLarger.h>
-#include <Core/observers/checks/ConditionCheckSmaller.h>
+#include <ArmarXCore/observers/checks/ConditionCheckUpdated.h>
+#include <ArmarXCore/observers/checks/ConditionCheckEquals.h>
+#include <ArmarXCore/observers/checks/ConditionCheckInRange.h>
+#include <ArmarXCore/observers/checks/ConditionCheckLarger.h>
+#include <ArmarXCore/observers/checks/ConditionCheckSmaller.h>
 #include <RobotAPI/libraries/core/checks/ConditionCheckMagnitudeChecks.h>
 
 #include <RobotAPI/libraries/core/RobotAPIObjectFactories.h>
 #include <Eigen/Dense>
-#include <Core/observers/variant/TimestampVariant.h>
+#include <ArmarXCore/observers/variant/TimestampVariant.h>
 
 using namespace armarx;
 
@@ -25,10 +25,14 @@ void HapticObserver::setTopicName(std::string topicName)
 
 void HapticObserver::onInitObserver()
 {
-    if(topicName.empty())
+    if (topicName.empty())
+    {
         usingTopic(getProperty<std::string>("HapticTopicName").getValue());
+    }
     else
+    {
         usingTopic(topicName);
+    }
 
     // register all checks
     offerConditionCheck("updated", new ConditionCheckUpdated());
@@ -57,7 +61,8 @@ void HapticObserver::reportSensorValues(const std::string& device, const std::st
     float max = eigenMatrix.maxCoeff();
     float mean = eigenMatrix.mean();
     std::string channelName = name;
-    if(!existsChannel(channelName))
+
+    if (!existsChannel(channelName))
     {
         offerChannel(channelName, "Haptic data");
         offerDataFieldWithDefault(channelName, "device", Variant(device), "Device of the tactile sensor");
@@ -78,6 +83,7 @@ void HapticObserver::reportSensorValues(const std::string& device, const std::st
         setDataField(channelName, "mean", Variant(mean));
         setDataField(channelName, "timestamp", timestampPtr);
     }
+
     /*if(statistics.count(device) > 0)
     {
         statistics.at(device).add(timestamp->timestamp);
diff --git a/source/RobotAPI/components/units/HapticObserver.h b/source/RobotAPI/components/units/HapticObserver.h
index dd9cb014c5580962c4b091a61b83b981ed09407b..160d1cf81192edb6db02cc1c6596c5a261b1ef10 100644
--- a/source/RobotAPI/components/units/HapticObserver.h
+++ b/source/RobotAPI/components/units/HapticObserver.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    ArmarXCore::units
  * @author     Peter Kaiser <peter dot kaiser at kit dot edu>
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -25,10 +24,10 @@
 #define _ARMARX_ROBOTAPI_HAPTIC_OBSERVER_H
 
 #include <RobotAPI/interface/units/HapticUnit.h>
-#include <Core/observers/Observer.h>
-#include <Core/util/variants/eigen3/MatrixVariant.h>
-#include <Core/util/variants/eigen3/Eigen3VariantObjectFactories.h>
-#include <Core/core/services/tasks/PeriodicTask.h>
+#include <ArmarXCore/observers/Observer.h>
+#include <ArmarXCore/util/variants/eigen3/MatrixVariant.h>
+#include <ArmarXCore/util/variants/eigen3/Eigen3VariantObjectFactories.h>
+#include <ArmarXCore/core/services/tasks/PeriodicTask.h>
 
 
 namespace armarx
@@ -38,7 +37,7 @@ namespace armarx
      * \brief
      */
     class HapticObserverPropertyDefinitions:
-            public ComponentPropertyDefinitions
+        public ComponentPropertyDefinitions
     {
     public:
         HapticObserverPropertyDefinitions(std::string prefix):
@@ -65,7 +64,8 @@ namespace armarx
         void add(long timestamp)
         {
             long delta = timestamp - lastTimestamp;
-            if(deltas.size() < count)
+
+            if (deltas.size() < count)
             {
                 deltas.push_back(delta);
             }
@@ -74,6 +74,7 @@ namespace armarx
                 deltas.at(pos) = delta;
                 pos = (pos + 1) % count;
             }
+
             lastTimestamp = timestamp;
         }
 
@@ -89,15 +90,18 @@ namespace armarx
 
         long average()
         {
-            if(deltas.size() == 0)
+            if (deltas.size() == 0)
             {
                 return 0;
             }
+
             long sum = 0;
-            for(std::vector<long>::iterator it = deltas.begin(); it != deltas.end(); ++it)
+
+            for (std::vector<long>::iterator it = deltas.begin(); it != deltas.end(); ++it)
             {
                 sum += *it;
             }
+
             return sum / deltas.size();
         }
 
@@ -117,8 +121,8 @@ namespace armarx
      * Available condition checks are: *updated*, *larger*, *equals* and *smaller*.
      */
     class HapticObserver :
-            virtual public Observer,
-            virtual public HapticUnitObserverInterface
+        virtual public Observer,
+        virtual public HapticUnitObserverInterface
     {
     public:
         HapticObserver();
@@ -126,7 +130,10 @@ namespace armarx
         void setTopicName(std::string topicName);
 
         // framework hooks
-        virtual std::string getDefaultName() const { return "HapticUnitObserver"; }
+        virtual std::string getDefaultName() const
+        {
+            return "HapticUnitObserver";
+        }
         void onInitObserver();
         void onConnectObserver();
         void onExitObserver();
diff --git a/source/RobotAPI/components/units/HapticUnit.cpp b/source/RobotAPI/components/units/HapticUnit.cpp
index aef0f4e890a05766782217b1ccdcc5b08caf6437..584b430430c5662c9e02cae02d8e4369b346b3c7 100644
--- a/source/RobotAPI/components/units/HapticUnit.cpp
+++ b/source/RobotAPI/components/units/HapticUnit.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    ArmarXCore::units
  * @author     Peter Kaiser <peter dot kaiser at kit dot edu>
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
diff --git a/source/RobotAPI/components/units/HapticUnit.h b/source/RobotAPI/components/units/HapticUnit.h
index 012825f072f4678855aa7aa078a5878c7af7eb19..d3daeb10a1cd26c227bad58336e1ff0d233158b7 100644
--- a/source/RobotAPI/components/units/HapticUnit.h
+++ b/source/RobotAPI/components/units/HapticUnit.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,16 +16,16 @@
  * @package    ArmarXCore::units
  * @author     Peter Kaiser <peter dot kaiser at kit dot edu>
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 #ifndef _ARMARX_COMPONENT_HAPTIC_UNIT_H
 #define _ARMARX_COMPONENT_HAPTIC_UNIT_H
 
-#include <Core/core/Component.h>
-#include <Core/core/application/properties/Properties.h>
-#include <Core/core/system/ImportExportComponent.h>
+#include <ArmarXCore/core/Component.h>
+#include <ArmarXCore/core/application/properties/Properties.h>
+#include <ArmarXCore/core/system/ImportExportComponent.h>
 #include "RobotAPI/components/units/SensorActorUnit.h"
 
 #include <RobotAPI/interface/units/HapticUnit.h>
@@ -41,38 +40,46 @@ namespace armarx
      */
     class HapticUnitPropertyDefinitions : public ComponentPropertyDefinitions
     {
-        public:
-            HapticUnitPropertyDefinitions(std::string prefix) :
-                ComponentPropertyDefinitions(prefix)
-            {
-                defineOptionalProperty<std::string>("HapticTopicName", "HapticValues", "Name of the Haptic Topic.");
-            }
+    public:
+        HapticUnitPropertyDefinitions(std::string prefix) :
+            ComponentPropertyDefinitions(prefix)
+        {
+            defineOptionalProperty<std::string>("HapticTopicName", "HapticValues", "Name of the Haptic Topic.");
+        }
     };
-    
+
     /**
-     * \class HapticUnit
+     * \defgroup Component-HapticUnit HapticUnit
      * \ingroup RobotAPI-SensorActorUnits
      * \brief Base unit for haptic sensors.
      */
+
+    /**
+     * @ingroup Component-HapticUnit
+     * @brief The HapticUnit class
+     */
     class HapticUnit :
         virtual public HapticUnitInterface,
         virtual public SensorActorUnit
     {
-        public:
-            virtual std::string getDefaultName() const { return "HapticUnit"; }
-            
-            virtual void onInitComponent();
-            virtual void onConnectComponent();
-            virtual void onExitComponent();
-            
-            virtual void onInitHapticUnit() = 0;
-            virtual void onStartHapticUnit() = 0;
-            virtual void onExitHapticUnit() = 0;
-            
-            virtual PropertyDefinitionsPtr createPropertyDefinitions();
-            
-        protected:
-            HapticUnitListenerPrx hapticTopicPrx;
+    public:
+        virtual std::string getDefaultName() const
+        {
+            return "HapticUnit";
+        }
+
+        virtual void onInitComponent();
+        virtual void onConnectComponent();
+        virtual void onExitComponent();
+
+        virtual void onInitHapticUnit() = 0;
+        virtual void onStartHapticUnit() = 0;
+        virtual void onExitHapticUnit() = 0;
+
+        virtual PropertyDefinitionsPtr createPropertyDefinitions();
+
+    protected:
+        HapticUnitListenerPrx hapticTopicPrx;
     };
 }
 
diff --git a/source/RobotAPI/components/units/HeadIKUnit.cpp b/source/RobotAPI/components/units/HeadIKUnit.cpp
index 86420ccb0189f575cb4442097243333cb47b3933..653a3fd7a27c418e6e9c8f01322c51ab7541da3f 100644
--- a/source/RobotAPI/components/units/HeadIKUnit.cpp
+++ b/source/RobotAPI/components/units/HeadIKUnit.cpp
@@ -1,7 +1,7 @@
 #include "HeadIKUnit.h"
 
 
-#include <Core/core/system/ArmarXDataPath.h>
+#include <ArmarXCore/core/system/ArmarXDataPath.h>
 
 #include <VirtualRobot/XML/RobotIO.h>
 #include <VirtualRobot/IK/GazeIK.h>
@@ -26,7 +26,7 @@ namespace armarx
 
         usingProxy(getProperty<std::string>("KinematicUnitName").getValue());
         usingProxy("RobotStateComponent");
-        usingTopic("RobotState");
+        usingTopic(getProperty<std::string>("RobotStateTopicName").getValue());
 
         cycleTime = getProperty<int>("CycleTime").getValue();
         offeringTopic("DebugDrawerUpdates");
@@ -53,7 +53,12 @@ namespace armarx
         //localRobot->setConfig(robotSnapshot->getConfig());
 
         requested = false;
-        if (execTask) execTask->stop();
+
+        if (execTask)
+        {
+            execTask->stop();
+        }
+
         execTask = new PeriodicTask<HeadIKUnit>(this, &HeadIKUnit::periodicExec, cycleTime, false, "HeadIKCalculator");
         execTask->setDelayWarningTolerance(300);
         execTask->start();
@@ -63,13 +68,19 @@ namespace armarx
     void HeadIKUnit::onDisconnectComponent()
     {
         release();
+
         //ScopedLock lock(accessMutex);
-        if(drawer)
+        if (drawer)
+        {
             drawer->removeSphereDebugLayerVisu("HeadViewTarget");
+        }
 
 
 
-        if (execTask) execTask->stop();
+        if (execTask)
+        {
+            execTask->stop();
+        }
     }
 
     void HeadIKUnit::onExitComponent()
@@ -78,12 +89,16 @@ namespace armarx
 
 
 
-    void HeadIKUnit::setCycleTime(Ice::Int milliseconds, const Ice::Current & c)
+    void HeadIKUnit::setCycleTime(Ice::Int milliseconds, const Ice::Current& c)
     {
         ScopedLock lock(accessMutex);
 
         cycleTime = milliseconds;
-        if (execTask) execTask->changeInterval(cycleTime);
+
+        if (execTask)
+        {
+            execTask->changeInterval(cycleTime);
+        }
     }
 
 
@@ -97,11 +112,12 @@ namespace armarx
         this->targetPosition->z = targetPosition->z;
         this->targetPosition->frame = targetPosition->frame;
         FramedPositionPtr globalTarget = FramedPositionPtr::dynamicCast(targetPosition)->toGlobal(robotStateComponentPrx->getSynchronizedRobot());
-        if(drawer)
+
+        if (drawer)
         {
             drawer->setSphereDebugLayerVisu("HeadViewTarget",
                                             globalTarget,
-                                            DrawColor{1,0,0,0.7},
+                                            DrawColor {1, 0, 0, 0.7},
                                             15);
 
 
@@ -115,30 +131,33 @@ namespace armarx
 
 
 
-    void HeadIKUnit::init(const Ice::Current & c)
+    void HeadIKUnit::init(const Ice::Current& c)
     {
     }
 
-    void HeadIKUnit::start(const Ice::Current & c)
+    void HeadIKUnit::start(const Ice::Current& c)
     {
     }
 
-    void HeadIKUnit::stop(const Ice::Current & c)
+    void HeadIKUnit::stop(const Ice::Current& c)
     {
     }
 
-    UnitExecutionState HeadIKUnit::getExecutionState(const Ice::Current & c)
+    UnitExecutionState HeadIKUnit::getExecutionState(const Ice::Current& c)
     {
         switch (getState())
         {
             case eManagedIceObjectStarted:
                 return eUnitStarted;
+
             case eManagedIceObjectInitialized:
             case eManagedIceObjectStarting:
                 return eUnitInitialized;
+
             case eManagedIceObjectExiting:
             case eManagedIceObjectExited:
                 return eUnitStopped;
+
             default:
                 return eUnitConstructed;
         }
@@ -147,13 +166,18 @@ namespace armarx
 
 
 
-    void HeadIKUnit::request(const Ice::Current & c)
+    void HeadIKUnit::request(const Ice::Current& c)
     {
         ScopedLock lock(accessMutex);
 
         requested = true;
         ARMARX_IMPORTANT << "Requesting HeadIKUnit";
-        if(execTask) execTask->stop();
+
+        if (execTask)
+        {
+            execTask->stop();
+        }
+
         execTask = new PeriodicTask<HeadIKUnit>(this, &HeadIKUnit::periodicExec, cycleTime, false, "TCPVelocityCalculator");
         execTask->start();
         ARMARX_IMPORTANT << "Requested HeadIKUnit";
@@ -162,15 +186,17 @@ namespace armarx
 
 
 
-    void HeadIKUnit::release(const Ice::Current & c)
+    void HeadIKUnit::release(const Ice::Current& c)
     {
         ScopedLock lock(accessMutex);
 
         ARMARX_INFO << "Releasing HeadIKUnit";
         requested = false;
 
-        if(drawer)
+        if (drawer)
+        {
             drawer->removeSphereDebugLayerVisu("HeadViewTarget");
+        }
 
         // why do we stop the kin unit?
         /*try
@@ -194,6 +220,7 @@ namespace armarx
 
         {
             ScopedTryLock lock(accessMutex);
+
             if (lock.owns_lock())
             {
                 doCalculation = requested && newTargetSet;
@@ -209,31 +236,37 @@ namespace armarx
         if (doCalculation)
         {
             ScopedLock lock(accessMutex);
-            RemoteRobot::synchronizeLocalClone(localRobot,robotStateComponentPrx);
+            RemoteRobot::synchronizeLocalClone(localRobot, robotStateComponentPrx);
             //VirtualRobot::RobotPtr robotSnapshot(new RemoteRobot(remoteRobotPrx));
             //localRobot->setConfig(robotSnapshot->getConfig());
 
             VirtualRobot::RobotNodeSetPtr kinematicChain = localRobot->getRobotNodeSet(robotNodeSetName);
             VirtualRobot::RobotNodePrismaticPtr virtualJoint;
-            for (unsigned int i=0; i<kinematicChain->getSize(); i++)
+
+            for (unsigned int i = 0; i < kinematicChain->getSize(); i++)
             {
                 if (kinematicChain->getNode(i)->getName().compare("VirtualCentralGaze") == 0)
                 {
                     virtualJoint = boost::dynamic_pointer_cast<VirtualRobot::RobotNodePrismatic>(kinematicChain->getNode(i));
                 }
             }
+
             ARMARX_DEBUG << deactivateSpam(5) << VAROUT(virtualJoint->getName()) << " " << VAROUT(kinematicChain->getName());
             VirtualRobot::GazeIK ikSolver(kinematicChain, virtualJoint);
             ikSolver.enableJointLimitAvoidance(true);
             ikSolver.setup(10, 30, 20);
-//            ikSolver.setVerbose(true);
+            //            ikSolver.setVerbose(true);
             auto globalPos = targetPosition->toGlobal(localRobot);
             ARMARX_DEBUG << "Calculating IK for target position " << globalPos->output();
             auto start = IceUtil::Time::now();
             bool solutionFound = ikSolver.solve(globalPos->toEigen());
-            auto duration = (IceUtil::Time::now()-start);
-            if(duration.toMilliSeconds() > 500)
+            auto duration = (IceUtil::Time::now() - start);
+
+            if (duration.toMilliSeconds() > 500)
+            {
                 ARMARX_INFO << "Calculating Gaze IK took " << duration.toMilliSeconds() << " ms";
+            }
+
             if (!solutionFound)
             {
                 ARMARX_WARNING << "IKSolver found no solution!";
@@ -242,18 +275,19 @@ namespace armarx
             {
                 ARMARX_DEBUG << "Solution found";
 
-                if(drawer && localRobot->hasRobotNode("Cameras"))
+                if (drawer && localRobot->hasRobotNode("Cameras"))
                 {
                     Vector3Ptr startPos = new Vector3(localRobot->getRobotNode("Cameras")->getGlobalPose());
                     drawer->setSphereDebugLayerVisu("HeadViewTarget",
                                                     startPos,
-                                                    DrawColor{0,1,1,0.2},
+                                                    DrawColor {0, 1, 1, 0.2},
                                                     17);
                 }
 
 
                 NameValueMap targetJointAngles;
                 NameControlModeMap controlModes;
+
                 for (int i = 0; i < (signed int)kinematicChain->getSize(); i++)
                 {
                     if (kinematicChain->getNode(i)->getName().compare("VirtualCentralGaze") != 0)
@@ -261,14 +295,17 @@ namespace armarx
                         targetJointAngles[kinematicChain->getNode(i)->getName()] = kinematicChain->getNode(i)->getJointValue();
                         controlModes[kinematicChain->getNode(i)->getName()] = ePositionControl;
                     }
+
                     ARMARX_DEBUG << kinematicChain->getNode(i)->getName() << ": " << kinematicChain->getNode(i)->getJointValue();
                 }
+
                 try
                 {
                     kinematicUnitPrx->switchControlMode(controlModes);
                     ARMARX_DEBUG << "setting new joint angles" << targetJointAngles;
                     kinematicUnitPrx->setJointAngles(targetJointAngles);
-                } catch (...)
+                }
+                catch (...)
                 {
                     ARMARX_IMPORTANT << "setJointAngles failed";
                 }
diff --git a/source/RobotAPI/components/units/HeadIKUnit.h b/source/RobotAPI/components/units/HeadIKUnit.h
index 143150b61e98879b4985a995b0572ebb999644c8..c9f137bb7781b59c860a76efee8629767cf934db 100644
--- a/source/RobotAPI/components/units/HeadIKUnit.h
+++ b/source/RobotAPI/components/units/HeadIKUnit.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::
 * @author     David Schiebener ( schiebener at kit dot edu)
 * @date       2014
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -25,8 +24,8 @@
 #define _ARMARX_HEADIKUNIT_H
 
 
-#include <Core/core/Component.h>
-#include <Core/core/services/tasks/PeriodicTask.h>
+#include <ArmarXCore/core/Component.h>
+#include <ArmarXCore/core/services/tasks/PeriodicTask.h>
 #include <RobotAPI/interface/visualization/DebugDrawerInterface.h>
 #include <RobotAPI/libraries/core/FramedPose.h>
 #include <RobotAPI/libraries/core/remoterobot/RemoteRobot.h>
@@ -41,22 +40,28 @@ namespace armarx
      * \brief
      */
     class HeadIKUnitPropertyDefinitions:
-            public ComponentPropertyDefinitions
+        public ComponentPropertyDefinitions
     {
     public:
         HeadIKUnitPropertyDefinitions(std::string prefix):
             ComponentPropertyDefinitions(prefix)
         {
-            defineRequiredProperty<std::string>("KinematicUnitName","Name of the KinematicUnit Proxy");
+            defineRequiredProperty<std::string>("KinematicUnitName", "Name of the KinematicUnit Proxy");
+            defineOptionalProperty<std::string>("RobotStateTopicName", "RobotState", "Name of the RobotComponent State topic.");
             defineOptionalProperty<int>("CycleTime", 30, "Cycle time of the tcp control in ms");
         }
     };
 
     /**
-     * \class HeadIKUnit
+     * \defgroup Component-HeadIKUnit HeadIKUnit
      * \ingroup RobotAPI-SensorActorUnits
      * \brief Unit for controlling a robot head via IK targets.
      */
+
+    /**
+     * @ingroup Component-HeadIKUnit
+     * @brief The HeadIKUnit class
+     */
     class HeadIKUnit : virtual public Component, virtual public HeadIKUnitInterface
     {
     public:
@@ -65,21 +70,24 @@ namespace armarx
         void onConnectComponent();
         void onDisconnectComponent();
         void onExitComponent();
-        std::string getDefaultName() const{ return "HeadIKUnit"; }
+        std::string getDefaultName() const
+        {
+            return "HeadIKUnit";
+        }
 
         // HeadIKUnitInterface interface
-        void setCycleTime(Ice::Int milliseconds, const Ice::Current &c = Ice::Current());
-        void setHeadTarget(const std::string& robotNodeSetName, const FramedPositionBasePtr &targetPosition, const Ice::Current &c = Ice::Current());
+        void setCycleTime(Ice::Int milliseconds, const Ice::Current& c = Ice::Current());
+        void setHeadTarget(const std::string& robotNodeSetName, const FramedPositionBasePtr& targetPosition, const Ice::Current& c = Ice::Current());
 
         // UnitExecutionManagementInterface interface
-        void init(const Ice::Current &c = Ice::Current());
-        void start(const Ice::Current &c = Ice::Current());
-        void stop(const Ice::Current &c = Ice::Current());
-        UnitExecutionState getExecutionState(const Ice::Current &c = Ice::Current());
+        void init(const Ice::Current& c = Ice::Current());
+        void start(const Ice::Current& c = Ice::Current());
+        void stop(const Ice::Current& c = Ice::Current());
+        UnitExecutionState getExecutionState(const Ice::Current& c = Ice::Current());
 
         // UnitResourceManagementInterface interface
-        void request(const Ice::Current &c = Ice::Current());
-        void release(const Ice::Current &c = Ice::Current());
+        void request(const Ice::Current& c = Ice::Current());
+        void release(const Ice::Current& c = Ice::Current());
 
         // PropertyUser interface
         PropertyDefinitionsPtr createPropertyDefinitions();
diff --git a/source/RobotAPI/components/units/InertialMeasurementUnit.cpp b/source/RobotAPI/components/units/InertialMeasurementUnit.cpp
index 672f856d35c99fa1c63b1e63c1981a98bf8c3154..d0f0b1d30096fba8673df04cb2d031c14bc57cfe 100644
--- a/source/RobotAPI/components/units/InertialMeasurementUnit.cpp
+++ b/source/RobotAPI/components/units/InertialMeasurementUnit.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    RobotAPI::ArmarXObjects::InertialMeasurementUnit
  * @author     Markus Grotz ( markus-grotz at web dot de )
  * @date       2015
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
diff --git a/source/RobotAPI/components/units/InertialMeasurementUnit.h b/source/RobotAPI/components/units/InertialMeasurementUnit.h
index 4cd2861f7fe30d61b7778f809f3261abd8e29bfc..9dec375d78f069a9cf5710e710bee06b1393e507 100644
--- a/source/RobotAPI/components/units/InertialMeasurementUnit.h
+++ b/source/RobotAPI/components/units/InertialMeasurementUnit.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    RobotAPI::ArmarXObjects::InertialMeasurementUnit
  * @author     Markus Grotz ( markus-grotz at web dot de )
  * @date       2015
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -27,7 +26,7 @@
 
 #include "SensorActorUnit.h"
 
-#include <Core/core/Component.h>
+#include <ArmarXCore/core/Component.h>
 #include <RobotAPI/interface/units/InertialMeasurementUnit.h>
 
 namespace armarx
diff --git a/source/RobotAPI/components/units/InertialMeasurementUnitObserver.cpp b/source/RobotAPI/components/units/InertialMeasurementUnitObserver.cpp
index 0499d45ff74207fcfec955dddaf7c22382b7525a..8feff3d67002613b2b5269b3671182a5aed60bc1 100644
--- a/source/RobotAPI/components/units/InertialMeasurementUnitObserver.cpp
+++ b/source/RobotAPI/components/units/InertialMeasurementUnitObserver.cpp
@@ -1,14 +1,14 @@
 #include "InertialMeasurementUnitObserver.h"
 
 
-#include <Core/observers/checks/ConditionCheckEquals.h>
-#include <Core/observers/checks/ConditionCheckLarger.h>
-#include <Core/observers/checks/ConditionCheckSmaller.h>
-#include <Core/observers/checks/ConditionCheckUpdated.h>
+#include <ArmarXCore/observers/checks/ConditionCheckEquals.h>
+#include <ArmarXCore/observers/checks/ConditionCheckLarger.h>
+#include <ArmarXCore/observers/checks/ConditionCheckSmaller.h>
+#include <ArmarXCore/observers/checks/ConditionCheckUpdated.h>
 
 #include <RobotAPI/libraries/core/Pose.h>
 
-#include <Core/observers/variant/TimestampVariant.h>
+#include <ArmarXCore/observers/variant/TimestampVariant.h>
 
 
 
@@ -41,7 +41,7 @@ void InertialMeasurementUnitObserver::onExitObserver()
     debugDrawerPrx->removeLineVisu("IMU", "acceleration");
 }
 
-void InertialMeasurementUnitObserver::reportSensorValues(const std::string &device, const std::string &name, const IMUData &values, const TimestampBasePtr &timestamp, const Ice::Current &c)
+void InertialMeasurementUnitObserver::reportSensorValues(const std::string& device, const std::string& name, const IMUData& values, const TimestampBasePtr& timestamp, const Ice::Current& c)
 {
     ScopedLock lock(dataMutex);
 
@@ -52,9 +52,10 @@ void InertialMeasurementUnitObserver::reportSensorValues(const std::string &devi
     Vector3Ptr magneticRotation = new Vector3(values.magneticRotation.at(0), values.magneticRotation.at(1), values.magneticRotation.at(2));
     QuaternionPtr orientationQuaternion =  new Quaternion(values.orientationQuaternion.at(0), values.orientationQuaternion.at(1), values.orientationQuaternion.at(2), values.orientationQuaternion.at(3));
 
-    if(!existsChannel(device))
+    if (!existsChannel(device))
     {
-        offerChannel(device, "IMU data");\
+        offerChannel(device, "IMU data");
+        \
         //todo remove
         offerDataFieldWithDefault(device, "name", Variant(name), "Name of the IMU sensor");
         offerDataFieldWithDefault(device, "acceleration", acceleration,  "acceleration values");
@@ -72,6 +73,7 @@ void InertialMeasurementUnitObserver::reportSensorValues(const std::string &devi
         setDataField(device, "orientationQuaternion", orientationQuaternion);
         setDataField(device, "timestamp", timestampPtr);
     }
+
     updateChannel(device);
 
     Eigen::Vector3f zero;
diff --git a/source/RobotAPI/components/units/InertialMeasurementUnitObserver.h b/source/RobotAPI/components/units/InertialMeasurementUnitObserver.h
index 291e4dcda27186bc28e6cad3cb622b4560e333d7..26bee065be5154cdc9bfb6ecd4f67dee3040efa2 100644
--- a/source/RobotAPI/components/units/InertialMeasurementUnitObserver.h
+++ b/source/RobotAPI/components/units/InertialMeasurementUnitObserver.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    RobotAPI::units
  * @author     David Schiebener <schiebener at kit dot edu>
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -25,7 +24,7 @@
 #define _ARMARX_ROBOTAPI_IMU_OBSERVER_H
 
 #include <RobotAPI/interface/units/InertialMeasurementUnit.h>
-#include <Core/observers/Observer.h>
+#include <ArmarXCore/observers/Observer.h>
 #include <RobotAPI/interface/visualization/DebugDrawerInterface.h>
 
 
@@ -36,7 +35,7 @@ namespace armarx
      * \brief
      */
     class InertialMeasurementUnitObserverPropertyDefinitions:
-            public ComponentPropertyDefinitions
+        public ComponentPropertyDefinitions
     {
     public:
         InertialMeasurementUnitObserverPropertyDefinitions(std::string prefix):
@@ -57,18 +56,21 @@ namespace armarx
      * Available condition checks are: *updated*, *larger*, *equals* and *smaller*.
      */
     class InertialMeasurementUnitObserver :
-            virtual public Observer,
-            virtual public InertialMeasurementUnitObserverInterface
+        virtual public Observer,
+        virtual public InertialMeasurementUnitObserverInterface
     {
     public:
-        InertialMeasurementUnitObserver(){}
+        InertialMeasurementUnitObserver() {}
 
-        virtual std::string getDefaultName() const { return "InertialMeasurementUnitObserver"; }
+        virtual std::string getDefaultName() const
+        {
+            return "InertialMeasurementUnitObserver";
+        }
         virtual void onInitObserver();
         virtual void onConnectObserver();
         virtual void onExitObserver();
 
-        void reportSensorValues(const std::string &device, const std::string &name, const IMUData &values, const TimestampBasePtr &timestamp, const Ice::Current &c = ::Ice::Current());
+        void reportSensorValues(const std::string& device, const std::string& name, const IMUData& values, const TimestampBasePtr& timestamp, const Ice::Current& c = ::Ice::Current());
 
         /**
          * @see PropertyUser::createPropertyDefinitions()
@@ -76,9 +78,9 @@ namespace armarx
         virtual PropertyDefinitionsPtr createPropertyDefinitions();
 
 
-      private:
-         Mutex dataMutex;
-         DebugDrawerInterfacePrx debugDrawerPrx;
+    private:
+        Mutex dataMutex;
+        DebugDrawerInterfacePrx debugDrawerPrx;
 
 
     };
diff --git a/source/RobotAPI/components/units/KinematicUnit.cpp b/source/RobotAPI/components/units/KinematicUnit.cpp
index b360f799b39e4cc34ade44cac5c3ed6c974ca8b0..d5c08b7a95a0dd28558f217e1ff5862c2c087854 100644
--- a/source/RobotAPI/components/units/KinematicUnit.cpp
+++ b/source/RobotAPI/components/units/KinematicUnit.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    ArmarXCore::units
  * @author     Christian Boege (boege at kit dot edu)
  * @date       2011
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -29,7 +28,8 @@
 #include <VirtualRobot/RobotNodeSet.h>
 #include <VirtualRobot/VirtualRobotException.h>
 #include <VirtualRobot/RuntimeEnvironment.h>
-#include <Core/core/system/ArmarXDataPath.h>
+#include <ArmarXCore/core/system/ArmarXDataPath.h>
+#include <ArmarXCore/core/system/cmake/CMakePackageFinder.h>
 
 using namespace armarx;
 
@@ -41,7 +41,22 @@ void KinematicUnit::onInitComponent()
     std::string robotFile = getProperty<std::string>("RobotFileName").getValue();
     robotNodeSetName = getProperty<std::string>("RobotNodeSetName").getValue();
 
-    if (!ArmarXDataPath::getAbsolutePath(robotFile,robotFile))
+    std::string project = getProperty<std::string>("RobotFileNameProject").getValue();
+    StringList includePaths;
+
+    if (!project.empty())
+    {
+        CMakePackageFinder finder(project);
+        StringList projectIncludePaths;
+        auto pathsString = finder.getDataDir();
+        boost::split(projectIncludePaths,
+                     pathsString,
+                     boost::is_any_of(";,"),
+                     boost::token_compress_on);
+        includePaths.insert(includePaths.end(), projectIncludePaths.begin(), projectIncludePaths.end());
+    }
+
+    if (!ArmarXDataPath::getAbsolutePath(robotFile, robotFile, includePaths))
     {
         throw UserException("Could not find robot file " + robotFile);
     }
@@ -51,11 +66,12 @@ void KinematicUnit::onInitComponent()
     {
         robot = VirtualRobot::RobotIO::loadRobot(robotFile, VirtualRobot::RobotIO::eStructure);
     }
-    catch(VirtualRobot::VirtualRobotException& e)
+    catch (VirtualRobot::VirtualRobotException& e)
     {
         throw UserException(e.what());
     }
-    if(robotNodeSetName == "")
+
+    if (robotNodeSetName == "")
     {
         throw UserException("RobotNodeSet not defined");
     }
@@ -111,5 +127,5 @@ void KinematicUnit::releaseKinematicUnit(const StringSequence& nodes, const Ice:
 PropertyDefinitionsPtr KinematicUnit::createPropertyDefinitions()
 {
     return PropertyDefinitionsPtr(new KinematicUnitPropertyDefinitions(
-                                           getConfigIdentifier()));
+                                      getConfigIdentifier()));
 }
diff --git a/source/RobotAPI/components/units/KinematicUnit.h b/source/RobotAPI/components/units/KinematicUnit.h
index c39ddfe0caf601c3ed5dff88285964837f9fe634..c3dd87e08a5b36e1c50c3bdcb14164b162aef89e 100644
--- a/source/RobotAPI/components/units/KinematicUnit.h
+++ b/source/RobotAPI/components/units/KinematicUnit.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    ArmarXCore::units
  * @author     Christian Boege (boege at kit dot edu)
  * @date       2011
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -26,9 +25,9 @@
 
 #include <RobotAPI/components/units/SensorActorUnit.h>
 
-#include <Core/core/Component.h>
-#include <Core/core/application/properties/Properties.h>
-#include <Core/core/system/ImportExportComponent.h>
+#include <ArmarXCore/core/Component.h>
+#include <ArmarXCore/core/application/properties/Properties.h>
+#include <ArmarXCore/core/system/ImportExportComponent.h>
 
 #include <RobotAPI/interface/units/KinematicUnitInterface.h>
 
@@ -42,20 +41,21 @@ namespace armarx
      * \brief
      */
     class KinematicUnitPropertyDefinitions:
-            public ComponentPropertyDefinitions
+        public ComponentPropertyDefinitions
     {
     public:
         KinematicUnitPropertyDefinitions(std::string prefix):
             ComponentPropertyDefinitions(prefix)
         {
-            defineRequiredProperty<std::string>("RobotNodeSetName","Robot node set name as defined in robot xml file, e.g. 'LeftArm'");
+            defineRequiredProperty<std::string>("RobotNodeSetName", "Robot node set name as defined in robot xml file, e.g. 'LeftArm'");
             defineRequiredProperty<std::string>("RobotFileName", "Robot file name, e.g. robot_model.xml");
+            defineOptionalProperty<std::string>("RobotFileNameProject", "", "Project in which the robot filename is located (if robot is loaded from an external project)");
         }
     };
 
 
     /**
-     * \class KinematicUnit
+     * \defgroup Component-KinematicUnit KinematicUnit
      * \ingroup RobotAPI-SensorActorUnits
      * \brief Base unit for kinematic sensors and actors.
      *
@@ -65,13 +65,21 @@ namespace armarx
      * The KinematicUnit retrieves its configuration from a VirtualRobot robot model. Within the model, the joints, the unit
      * controls are defined with a RobotNodeSet.
      */
+
+    /**
+     * @ingroup Component-KinematicUnit
+     * @brief The KinematicUnit class
+     */
     class KinematicUnit :
         virtual public KinematicUnitInterface,
         virtual public SensorActorUnit
     {
     public:
         // inherited from Component
-        virtual std::string getDefaultName() const { return "KinematicUnit"; }
+        virtual std::string getDefaultName() const
+        {
+            return "KinematicUnit";
+        }
 
         virtual void onInitComponent();
         virtual void onConnectComponent();
diff --git a/source/RobotAPI/components/units/KinematicUnitObserver.cpp b/source/RobotAPI/components/units/KinematicUnitObserver.cpp
index 30c9ce63f8025c1bf242d5a93cc6803c918aa258..19673d07830dfa863605cb1648c0f2b4902d30a0 100644
--- a/source/RobotAPI/components/units/KinematicUnitObserver.cpp
+++ b/source/RobotAPI/components/units/KinematicUnitObserver.cpp
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -23,20 +22,21 @@
 
 #include "KinematicUnitObserver.h"
 #include "KinematicUnit.h"
-#include <Core/observers/checks/ConditionCheckValid.h>
-#include <Core/observers/checks/ConditionCheckUpdated.h>
-#include <Core/observers/checks/ConditionCheckEquals.h>
-#include <Core/observers/checks/ConditionCheckInRange.h>
-#include <Core/observers/checks/ConditionCheckLarger.h>
-#include <Core/observers/checks/ConditionCheckSmaller.h>
-#include <Core/observers/variant/ChannelRef.h>
-#include <Core/core/system/ArmarXDataPath.h>
+#include <ArmarXCore/observers/checks/ConditionCheckValid.h>
+#include <ArmarXCore/observers/checks/ConditionCheckUpdated.h>
+#include <ArmarXCore/observers/checks/ConditionCheckEquals.h>
+#include <ArmarXCore/observers/checks/ConditionCheckInRange.h>
+#include <ArmarXCore/observers/checks/ConditionCheckLarger.h>
+#include <ArmarXCore/observers/checks/ConditionCheckSmaller.h>
+#include <ArmarXCore/observers/variant/ChannelRef.h>
+#include <ArmarXCore/core/system/ArmarXDataPath.h>
+#include <ArmarXCore/core/system/cmake/CMakePackageFinder.h>
 
 #include <VirtualRobot/VirtualRobot.h>
 #include <VirtualRobot/XML/RobotIO.h>
 #include <VirtualRobot/RobotNodeSet.h>
 #include <VirtualRobot/Nodes/RobotNode.h>
-#include <Core/observers/checks/ConditionCheckEqualsWithTolerance.h>
+#include <ArmarXCore/observers/checks/ConditionCheckEqualsWithTolerance.h>
 
 using namespace armarx;
 
@@ -64,30 +64,45 @@ void KinematicUnitObserver::onConnectObserver()
     // read names of kinematic chain elements belonging to this unit from XML and setup a map of all joints
     // the kinematic chain elements belonging to this unit are defined in a RobotNodeSet
     std::string robotFile = getProperty<std::string>("RobotFileName").getValue();
+    std::string project = getProperty<std::string>("RobotFileNameProject").getValue();
+    StringList includePaths;
 
+    if (!project.empty())
+    {
+        CMakePackageFinder finder(project);
+        StringList projectIncludePaths;
+        auto pathsString = finder.getDataDir();
+        boost::split(projectIncludePaths,
+                     pathsString,
+                     boost::is_any_of(";,"),
+                     boost::token_compress_on);
+        includePaths.insert(includePaths.end(), projectIncludePaths.begin(), projectIncludePaths.end());
+    }
 
-    if (!ArmarXDataPath::getAbsolutePath(robotFile,robotFile))
+    if (!ArmarXDataPath::getAbsolutePath(robotFile, robotFile, includePaths))
     {
         throw UserException("Could not find robot file " + robotFile);
     }
 
     VirtualRobot::RobotPtr robot = VirtualRobot::RobotIO::loadRobot(robotFile, VirtualRobot::RobotIO::eStructure);
-    if(robotNodeSetName == "")
+
+    if (robotNodeSetName == "")
     {
         throw UserException("RobotNodeSet not defined");
     }
+
     VirtualRobot::RobotNodeSetPtr robotNodeSetPtr = robot->getRobotNodeSet(robotNodeSetName);
 
     std::vector< VirtualRobot::RobotNodePtr > robotNodes;
     robotNodes = robotNodeSetPtr->getAllRobotNodes();
 
     // register all channels
-    offerChannel("jointangles","Joint values of the " + robotNodeSetName + " kinematic chain");
-    offerChannel("jointvelocities","Joint velocities of the " + robotNodeSetName + "kinematic chain");
-    offerChannel("jointtorques","Joint torques of the" + robotNodeSetName + " kinematic chain");
-    offerChannel("jointcurrents","Joint currents of the " + robotNodeSetName + " kinematic chain");
-    offerChannel("jointmotortemperatures","Joint motor temperatures of the " + robotNodeSetName + " kinematic chain");
-    offerChannel("jointcontrolmodes","Joint motor temperatures of the " + robotNodeSetName + " kinematic chain");
+    offerChannel("jointangles", "Joint values of the " + robotNodeSetName + " kinematic chain");
+    offerChannel("jointvelocities", "Joint velocities of the " + robotNodeSetName + "kinematic chain");
+    offerChannel("jointtorques", "Joint torques of the" + robotNodeSetName + " kinematic chain");
+    offerChannel("jointcurrents", "Joint currents of the " + robotNodeSetName + " kinematic chain");
+    offerChannel("jointmotortemperatures", "Joint motor temperatures of the " + robotNodeSetName + " kinematic chain");
+    offerChannel("jointcontrolmodes", "Joint motor temperatures of the " + robotNodeSetName + " kinematic chain");
 
 
     // register all data fields
@@ -102,6 +117,7 @@ void KinematicUnitObserver::onConnectObserver()
         offerDataField("jointcurrents", jointName, VariantType::Float, "Joint current of the " + jointName + "  joint");
         offerDataField("jointmotortemperatures", jointName, VariantType::Float, "Joint motor temperature of the " + jointName + "  joint");
     }
+
     updateChannel("jointcontrolmodes");
 }
 
@@ -112,18 +128,23 @@ void KinematicUnitObserver::onConnectObserver()
 // ********************************************************************
 void KinematicUnitObserver::reportControlModeChanged(const NameControlModeMap& jointModes, bool aValueChanged, const Ice::Current& c)
 {
-    try{
+    try
+    {
 
 
-        if(jointModes.size() == 0)
+        if (jointModes.size() == 0)
+        {
             return;
-        for(auto elem : jointModes)
+        }
+
+        for (auto elem : jointModes)
         {
             setDataFieldFlatCopy("jointcontrolmodes", elem.first, new Variant(ControlModeToString(elem.second)));
         }
+
         updateChannel("jointcontrolmodes");
     }
-    catch(...)
+    catch (...)
     {
         handleExceptions();
     }
@@ -131,18 +152,21 @@ void KinematicUnitObserver::reportControlModeChanged(const NameControlModeMap& j
 
 void KinematicUnitObserver::reportJointAngles(const NameValueMap& jointAngles,  bool aValueChanged, const Ice::Current& c)
 {
-    try{
+    try
+    {
 
 
-        if(jointAngles.size() == 0)
+        if (jointAngles.size() == 0)
+        {
             return;
+        }
 
         nameValueMapToDataFields("jointangles", jointAngles);
 
         updateChannel("jointangles");
 
     }
-    catch(...)
+    catch (...)
     {
         handleExceptions();
     }
@@ -151,13 +175,17 @@ void KinematicUnitObserver::reportJointAngles(const NameValueMap& jointAngles,
 
 void KinematicUnitObserver::reportJointVelocities(const NameValueMap& jointVelocities, bool aValueChanged, const Ice::Current& c)
 {
-    try{
-        if(jointVelocities.size() == 0)
+    try
+    {
+        if (jointVelocities.size() == 0)
+        {
             return;
+        }
+
         nameValueMapToDataFields("jointvelocities", jointVelocities);
         updateChannel("jointvelocities");
     }
-    catch(...)
+    catch (...)
     {
         handleExceptions();
     }
@@ -165,32 +193,40 @@ void KinematicUnitObserver::reportJointVelocities(const NameValueMap& jointVeloc
 
 void KinematicUnitObserver::reportJointTorques(const NameValueMap& jointTorques, bool aValueChanged, const Ice::Current& c)
 {
-    try{
-        if(jointTorques.size() == 0)
+    try
+    {
+        if (jointTorques.size() == 0)
+        {
             return;
+        }
+
         nameValueMapToDataFields("jointtorques", jointTorques);
         updateChannel("jointtorques");
     }
-    catch(...)
+    catch (...)
     {
         handleExceptions();
     }
 }
 
-void KinematicUnitObserver::reportJointAccelerations(const NameValueMap &jointAccelerations, bool aValueChanged, const Ice::Current &c)
+void KinematicUnitObserver::reportJointAccelerations(const NameValueMap& jointAccelerations, bool aValueChanged, const Ice::Current& c)
 {
 
 }
 
 void KinematicUnitObserver::reportJointCurrents(const NameValueMap& jointCurrents,  bool aValueChanged, const Ice::Current& c)
 {
-    try{
-        if(jointCurrents.size() == 0)
+    try
+    {
+        if (jointCurrents.size() == 0)
+        {
             return;
+        }
+
         nameValueMapToDataFields("jointcurrents", jointCurrents);
         updateChannel("jointcurrents");
     }
-    catch(...)
+    catch (...)
     {
         handleExceptions();
     }
@@ -198,30 +234,34 @@ void KinematicUnitObserver::reportJointCurrents(const NameValueMap& jointCurrent
 
 void KinematicUnitObserver::reportJointMotorTemperatures(const NameValueMap& jointMotorTemperatures, bool aValueChanged, const Ice::Current& c)
 {
-    try{
-        if(jointMotorTemperatures.size() == 0)
+    try
+    {
+        if (jointMotorTemperatures.size() == 0)
+        {
             return;
+        }
+
         nameValueMapToDataFields("jointmotortemperatures", jointMotorTemperatures);
         updateChannel("jointmotortemperatures");
     }
-    catch(...)
+    catch (...)
     {
         handleExceptions();
     }
 }
 
-void KinematicUnitObserver::reportJointStatuses(const NameStatusMap &jointStatuses, bool aValueChanged, const Ice::Current &c)
+void KinematicUnitObserver::reportJointStatuses(const NameStatusMap& jointStatuses, bool aValueChanged, const Ice::Current& c)
 {
 }
 
 // ********************************************************************
 // private methods
 // ********************************************************************
-void KinematicUnitObserver::nameValueMapToDataFields(const std::string &channelName, const NameValueMap& nameValueMap)
+void KinematicUnitObserver::nameValueMapToDataFields(const std::string& channelName, const NameValueMap& nameValueMap)
 {
     NameValueMap::const_iterator iter = nameValueMap.begin();
 
-    while(iter != nameValueMap.end())
+    while (iter != nameValueMap.end())
     {
         setDataFieldFlatCopy(channelName, iter->first, new Variant(iter->second));
         iter++;
diff --git a/source/RobotAPI/components/units/KinematicUnitObserver.h b/source/RobotAPI/components/units/KinematicUnitObserver.h
index 37e3637c9f65f77e9218b331b441348fc51af676..ecbc321b7be827e6c33bd460076c7c1cc925921a 100644
--- a/source/RobotAPI/components/units/KinematicUnitObserver.h
+++ b/source/RobotAPI/components/units/KinematicUnitObserver.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -24,14 +23,14 @@
 #ifndef _ARMARX_CORE_KINEMATIC_UNIT_OBSERVER_H
 #define _ARMARX_CORE_KINEMATIC_UNIT_OBSERVER_H
 
-#include <Core/core/system/ImportExport.h>
-#include <Core/core/Component.h>
-#include <Core/core/application/properties/Properties.h>
-#include <Core/interface/observers/VariantBase.h>
+#include <ArmarXCore/core/system/ImportExport.h>
+#include <ArmarXCore/core/Component.h>
+#include <ArmarXCore/core/application/properties/Properties.h>
+#include <ArmarXCore/interface/observers/VariantBase.h>
 #include <RobotAPI/interface/units/KinematicUnitInterface.h>
 #include <RobotAPI/interface/observers/KinematicUnitObserverInterface.h>
-#include <Core/observers/ConditionCheck.h>
-#include <Core/observers/Observer.h>
+#include <ArmarXCore/observers/ConditionCheck.h>
+#include <ArmarXCore/observers/Observer.h>
 
 #include <string>
 
@@ -40,19 +39,19 @@ namespace armarx
     ARMARX_CREATE_CHECK(KinematicUnitObserver, equals)
     ARMARX_CREATE_CHECK(KinematicUnitObserver, larger)
 
-   /**
-    * \class KinematicUnitObserver
-    * \ingroup RobotAPI-SensorActorUnits-observers
-    * \brief Observer monitoring kinematic sensor and actor values
-    *
-    * The KinematicUnitObserver allows to install conditions on all channel reported by the KinematicUnit.
-    * These include joint angles, velocities, torques and motor temperatures
-    *
-    * The KinematicUnitObserver retrieves its configuration from a VirtualRobot robot model. Within the model, the joints
-    * which are observer by the unit are define by a robotnodeset.
-    *
-    * Available condition checks are: *valid*, *updated*, *equals*, *inrange*, *approx*, *larger* and *smaller*.
-    */
+    /**
+     * \class KinematicUnitObserver
+     * \ingroup RobotAPI-SensorActorUnits-observers
+     * \brief Observer monitoring kinematic sensor and actor values
+     *
+     * The KinematicUnitObserver allows to install conditions on all channel reported by the KinematicUnit.
+     * These include joint angles, velocities, torques and motor temperatures
+     *
+     * The KinematicUnitObserver retrieves its configuration from a VirtualRobot robot model. Within the model, the joints
+     * which are observer by the unit are define by a robotnodeset.
+     *
+     * Available condition checks are: *valid*, *updated*, *equals*, *inrange*, *approx*, *larger* and *smaller*.
+     */
     class ARMARXCORE_IMPORT_EXPORT KinematicUnitObserver :
         virtual public Observer,
         virtual public KinematicUnitObserverInterface
@@ -85,40 +84,55 @@ namespace armarx
 
         static std::string ControlModeToString(ControlMode mode)
         {
-            switch(mode)
+            switch (mode)
             {
-            case eDisabled:
-                return "Disabled";
-            case ePositionControl:
-                return "PositionControl";
-            case eVelocityControl:
-                return "VelocityControl";
-            case eTorqueControl:
-                return "TorqueControl";
-            case ePositionVelocityControl:
-                return "PositionVelocityControl";
-            case eUnknown:
-            default:
-                return "Unknown";
+                case eDisabled:
+                    return "Disabled";
+
+                case ePositionControl:
+                    return "PositionControl";
+
+                case eVelocityControl:
+                    return "VelocityControl";
+
+                case eTorqueControl:
+                    return "TorqueControl";
+
+                case ePositionVelocityControl:
+                    return "PositionVelocityControl";
+
+                case eUnknown:
+                default:
+                    return "Unknown";
             }
 
         }
-        static ControlMode StringToControlMode(const std::string &mode)
+        static ControlMode StringToControlMode(const std::string& mode)
         {
-            if(mode == "Disabled")
+            if (mode == "Disabled")
+            {
                 return eDisabled;
+            }
 
-            if(mode == "PositionControl")
+            if (mode == "PositionControl")
+            {
                 return ePositionControl;
+            }
 
-            if(mode == "VelocityControl")
+            if (mode == "VelocityControl")
+            {
                 return eVelocityControl;
+            }
 
-            if(mode == "TorqueControl")
+            if (mode == "TorqueControl")
+            {
                 return eTorqueControl;
+            }
 
-            if(mode == "PositionVelocityControl")
+            if (mode == "PositionVelocityControl")
+            {
                 return ePositionVelocityControl;
+            }
 
             return eUnknown;
         }
@@ -128,35 +142,41 @@ namespace armarx
 
     private:
         std::string robotNodeSetName;
-};
-
+    };
 
 
 
 
-/**
-      @class KinematicUnitDatafieldCreator
-      @brief
-      @ingroup RobotAPI-SensorActorUnits-util
-     */
-class KinematicUnitDatafieldCreator
-{
-public:
-    KinematicUnitDatafieldCreator(const std::string &channelName): _channelName(channelName){}
 
     /**
-         * @brief Function to create a Channel Representation for a KinematicUnitObserver
-         * @param kinematicUnitOberserverName Name of the KinematicUnitObserver
-         * @param jointName Name of a joint of the robot like it is specified
-         * in the simox-robot-xml-file
-         * @return returns a ChannelRepresentationPtr
+          @class KinematicUnitDatafieldCreator
+          @brief
+          @ingroup RobotAPI-SensorActorUnits-util
          */
-    DataFieldIdentifier getDatafield(const std::string &kinematicUnitObserverName, const std::string &jointName) const
+    class KinematicUnitDatafieldCreator
+    {
+    public:
+        KinematicUnitDatafieldCreator(const std::string& channelName): _channelName(channelName) {}
+
+        /**
+             * @brief Function to create a Channel Representation for a KinematicUnitObserver
+             * @param kinematicUnitOberserverName Name of the KinematicUnitObserver
+             * @param jointName Name of a joint of the robot like it is specified
+             * in the simox-robot-xml-file
+             * @return returns a ChannelRepresentationPtr
+             */
+        DataFieldIdentifier getDatafield(const std::string& kinematicUnitObserverName, const std::string& jointName) const
         {
-            if(kinematicUnitObserverName.empty())
+            if (kinematicUnitObserverName.empty())
+            {
                 throw LocalException("kinematicUnitObserverName must not be empty!");
-            if(jointName.empty())
+            }
+
+            if (jointName.empty())
+            {
                 throw LocalException("jointName must not be empty!");
+            }
+
             return DataFieldIdentifier(kinematicUnitObserverName, _channelName, jointName);
         }
 
@@ -165,9 +185,11 @@ public:
     };
 
 
-    namespace channels{
+    namespace channels
+    {
 
-        namespace KinematicUnitObserver{
+        namespace KinematicUnitObserver
+        {
             const KinematicUnitDatafieldCreator jointAngles("jointAngles");
             const KinematicUnitDatafieldCreator jointVelocities("jointVelocities");
             const KinematicUnitDatafieldCreator jointTorques("jointTorques");
diff --git a/source/RobotAPI/components/units/KinematicUnitSimulation.cpp b/source/RobotAPI/components/units/KinematicUnitSimulation.cpp
index b81e735542abce076bbac03a5641e54419eee40c..411fb9bf187fca618596e97e4cf4c2ed29213320 100644
--- a/source/RobotAPI/components/units/KinematicUnitSimulation.cpp
+++ b/source/RobotAPI/components/units/KinematicUnitSimulation.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    ArmarXCore::units
  * @author     Christian Boege (boege at kit dot edu)
  * @date       2011
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -30,7 +29,7 @@
 #include <VirtualRobot/Nodes/RobotNode.h>
 #include <VirtualRobot/VirtualRobotException.h>
 #include <VirtualRobot/RuntimeEnvironment.h>
-#include <Core/core/system/ArmarXDataPath.h>
+#include <ArmarXCore/core/system/ArmarXDataPath.h>
 
 #include <algorithm>
 
@@ -42,8 +41,9 @@ void KinematicUnitSimulation::onInitKinematicUnit()
     for (std::vector<VirtualRobot::RobotNodePtr>::iterator it = robotNodes.begin(); it != robotNodes.end(); it++)
     {
         std::string jointName = (*it)->getName();
-        jointInfos[jointName].limitLo =  (*it)->getJointLimitLo();
-        jointInfos[jointName].limitHi =  (*it)->getJointLimitHi();
+        jointInfos[jointName].limitLo = (*it)->getJointLimitLo();
+        jointInfos[jointName].limitHi = (*it)->getJointLimitHi();
+
         if ((*it)->isRotationalJoint())
         {
             if (jointInfos[jointName].limitHi - jointInfos[jointName].limitLo >= float(M_PI * 2))
@@ -51,12 +51,14 @@ void KinematicUnitSimulation::onInitKinematicUnit()
                 jointInfos[jointName].reset();
             }
         }
+
         ARMARX_VERBOSE << jointName << " with limits: lo: " << jointInfos[jointName].limitLo << " hi: " << jointInfos[jointName].limitHi;
     }
 
     {
         // duplicate the loop because of locking
         boost::mutex::scoped_lock lock(jointStatesMutex);
+
         // initialize JoinStates
         for (std::vector<VirtualRobot::RobotNodePtr>::iterator it = robotNodes.begin(); it != robotNodes.end(); it++)
         {
@@ -65,8 +67,9 @@ void KinematicUnitSimulation::onInitKinematicUnit()
             jointStates[jointName].init();
         }
     }
+
     noise = getProperty<float>("Noise").getValue() / 180.f * M_PI;
-    distribution = std::normal_distribution<double>(0,noise);
+    distribution = std::normal_distribution<double>(0, noise);
     intervalMs = getProperty<int>("IntervalMs").getValue();
     ARMARX_VERBOSE << "Starting kinematic unit simulation with " << intervalMs << " ms interval";
     simulationTask = new PeriodicTask<KinematicUnitSimulation>(this, &KinematicUnitSimulation::simulationFunction, intervalMs, false, "KinematicUnitSimulation");
@@ -99,12 +102,14 @@ void KinematicUnitSimulation::simulationFunction()
 
     {
         boost::mutex::scoped_lock lock(jointStatesMutex);
-        for ( KinematicUnitSimulationJointStates::iterator it = jointStates.begin(); it!=jointStates.end(); it++ )
+
+        for (KinematicUnitSimulationJointStates::iterator it = jointStates.begin(); it != jointStates.end(); it++)
         {
 
             float newAngle = 0.0f;
+
             // calculate joint positions if joint is in velocity control mode
-            if ( it->second.controlMode == eVelocityControl )
+            if (it->second.controlMode == eVelocityControl)
             {
                 double change = (it->second.velocity * timeDeltaInSeconds);
 
@@ -112,13 +117,13 @@ void KinematicUnitSimulation::simulationFunction()
                 change += randomNoiseValue;
                 newAngle = it->second.angle + change;
             }
-            else if(it->second.controlMode == ePositionControl)
+            else if (it->second.controlMode == ePositionControl)
             {
                 newAngle = it->second.angle;
             }
 
             // constrain the angle
-            KinematicUnitSimulationJointInfo & jointInfo = jointInfos[it->first];
+            KinematicUnitSimulationJointInfo& jointInfo = jointInfos[it->first];
             float maxAngle = (jointInfo.hasLimits()) ? jointInfo.limitHi : 2.0 * M_PI;
             float minAngle = (jointInfo.hasLimits()) ? jointInfo.limitLo : -2.0 * M_PI;
             newAngle = std::max<float>(newAngle, minAngle);
@@ -126,20 +131,22 @@ void KinematicUnitSimulation::simulationFunction()
 
             // Check if joint existed before
             KinematicUnitSimulationJointStates::iterator itPrev = previousJointStates.find(it->first);
-            if(itPrev == previousJointStates.end())
+
+            if (itPrev == previousJointStates.end())
             {
                 aPosValueChanged = aVelValueChanged = true;
             }
 
             // check if the angle has changed
-            if(fabs(previousJointStates[it->first].angle - newAngle) > 0.00000001 )
+            if (fabs(previousJointStates[it->first].angle - newAngle) > 0.00000001)
             {
                 aPosValueChanged = true;
                 // set the new joint angle locally for the next simulation iteration
                 it->second.angle = newAngle;
             }
+
             // check if velocities have changed
-            if(fabs(previousJointStates[it->first].velocity - it->second.velocity) > 0.00000001 )
+            if (fabs(previousJointStates[it->first].velocity - it->second.velocity) > 0.00000001)
             {
                 aVelValueChanged = true;
             }
@@ -148,6 +155,7 @@ void KinematicUnitSimulation::simulationFunction()
             actualJointAngles[it->first] = newAngle;
             actualJointVelocities[it->first] = it->second.velocity;
         }
+
         previousJointStates = jointStates;
     }
 
@@ -161,7 +169,8 @@ void KinematicUnitSimulation::switchControlMode(const NameControlModeMap& target
     NameControlModeMap changedControlModes;
     {
         boost::mutex::scoped_lock lock(jointStatesMutex);
-        for ( NameControlModeMap::const_iterator it = targetJointModes.begin(); it!=targetJointModes.end(); it++ )
+
+        for (NameControlModeMap::const_iterator it = targetJointModes.begin(); it != targetJointModes.end(); it++)
         {
             // target values
             std::string targetJointName = it->first;
@@ -170,15 +179,20 @@ void KinematicUnitSimulation::switchControlMode(const NameControlModeMap& target
             KinematicUnitSimulationJointStates::iterator iterJoints = jointStates.find(targetJointName);
 
             // check whether there is a joint with this name and set joint angle
-            if(iterJoints != jointStates.end())
+            if (iterJoints != jointStates.end())
             {
-                if(iterJoints->second.controlMode != targetControlMode)
+                if (iterJoints->second.controlMode != targetControlMode)
+                {
                     aValueChanged = true;
+                }
+
                 iterJoints->second.controlMode = targetControlMode;
                 changedControlModes.insert(*it);
             }
             else
+            {
                 ARMARX_WARNING << "Could not find joint with name " << targetJointName;
+            }
         }
     }
     // only report control modes which have been changed
@@ -193,7 +207,8 @@ void KinematicUnitSimulation::setJointAngles(const NameValueMap& targetJointAngl
     // name value maps for reporting
     NameValueMap actualJointAngles;
     bool aValueChanged = false;
-    for ( NameValueMap::const_iterator it = targetJointAngles.begin(); it!=targetJointAngles.end(); it++ )
+
+    for (NameValueMap::const_iterator it = targetJointAngles.begin(); it != targetJointAngles.end(); it++)
     {
         // target values
         std::string targetJointName = it->first;
@@ -201,23 +216,33 @@ void KinematicUnitSimulation::setJointAngles(const NameValueMap& targetJointAngl
 
         // check whether there is a joint with this name and set joint angle
         KinematicUnitSimulationJointStates::iterator iterJoints = jointStates.find(targetJointName);
-        if(iterJoints != jointStates.end())
+
+        if (iterJoints != jointStates.end())
         {
-            if (fabs(iterJoints->second.angle - targetJointAngle)>0)
+            if (fabs(iterJoints->second.angle - targetJointAngle) > 0)
+            {
                 aValueChanged = true;
+            }
+
             if (jointInfos[targetJointName].hasLimits())
             {
                 targetJointAngle = std::max<float>(targetJointAngle, jointInfos[targetJointName].limitLo);
                 targetJointAngle = std::min<float>(targetJointAngle, jointInfos[targetJointName].limitHi);
             }
+
             iterJoints->second.angle = targetJointAngle;
             actualJointAngles[targetJointName] = iterJoints->second.angle;
         }
         else
+        {
             ARMARX_WARNING  << deactivateSpam(1) << "Joint '" << targetJointName << "' not found!";
+        }
     }
+
     if (aValueChanged)
+    {
         listenerPrx->reportJointAngles(actualJointAngles, aValueChanged);
+    }
 }
 
 void KinematicUnitSimulation::setJointVelocities(const NameValueMap& targetJointVelocities, const Ice::Current& c)
@@ -225,24 +250,32 @@ void KinematicUnitSimulation::setJointVelocities(const NameValueMap& targetJoint
     boost::mutex::scoped_lock lock(jointStatesMutex);
     NameValueMap actualJointVelocities;
     bool aValueChanged = false;
-    for ( NameValueMap::const_iterator it = targetJointVelocities.begin(); it!=targetJointVelocities.end(); it++ )
+
+    for (NameValueMap::const_iterator it = targetJointVelocities.begin(); it != targetJointVelocities.end(); it++)
     {
         // target values
         std::string targetJointName = it->first;
         float targetJointVelocity = it->second;
 
         KinematicUnitSimulationJointStates::iterator iterJoints = jointStates.find(targetJointName);
+
         // check whether there is a joint with this name and set joint angle
-        if(iterJoints != jointStates.end())
+        if (iterJoints != jointStates.end())
         {
             if (fabs(iterJoints->second.velocity - targetJointVelocity) > 0)
+            {
                 aValueChanged = true;
+            }
+
             iterJoints->second.velocity = targetJointVelocity;
             actualJointVelocities[targetJointName] = iterJoints->second.velocity;
         }
     }
+
     if (aValueChanged)
+    {
         listenerPrx->reportJointVelocities(actualJointVelocities, aValueChanged);
+    }
 }
 
 void KinematicUnitSimulation::setJointTorques(const NameValueMap& targetJointTorques, const Ice::Current& c)
@@ -250,33 +283,43 @@ void KinematicUnitSimulation::setJointTorques(const NameValueMap& targetJointTor
     boost::mutex::scoped_lock lock(jointStatesMutex);
     NameValueMap actualJointTorques;
     bool aValueChanged = false;
-    for ( NameValueMap::const_iterator it = targetJointTorques.begin(); it!=targetJointTorques.end(); it++ )
+
+    for (NameValueMap::const_iterator it = targetJointTorques.begin(); it != targetJointTorques.end(); it++)
     {
         // target values
         std::string targetJointName = it->first;
         float targetJointTorque = it->second;
 
         KinematicUnitSimulationJointStates::iterator iterJoints = jointStates.find(targetJointName);
+
         // check whether there is a joint with this name and set joint angle
-        if(iterJoints != jointStates.end())
+        if (iterJoints != jointStates.end())
         {
             if (fabs(iterJoints->second.torque - targetJointTorque) > 0)
+            {
                 aValueChanged = true;
+            }
+
             iterJoints->second.torque = targetJointTorque;
             actualJointTorques[targetJointName] = iterJoints->second.torque;
         }
     }
+
     if (aValueChanged)
+    {
         listenerPrx->reportJointTorques(actualJointTorques, aValueChanged);
+    }
 }
 
 NameControlModeMap KinematicUnitSimulation::getControlModes(const Ice::Current& c)
 {
     NameControlModeMap result;
-    for ( KinematicUnitSimulationJointStates::iterator it = jointStates.begin(); it!=jointStates.end(); it++ )
+
+    for (KinematicUnitSimulationJointStates::iterator it = jointStates.begin(); it != jointStates.end(); it++)
     {
         result[it->first] = it->second.controlMode;
     }
+
     return result;
 }
 
@@ -288,14 +331,16 @@ void KinematicUnitSimulation::setJointDecelerations(const NameValueMap& targetJo
 {
 }
 
-void KinematicUnitSimulation::stop(const Ice::Current &c)
+void KinematicUnitSimulation::stop(const Ice::Current& c)
 {
 
     boost::mutex::scoped_lock lock(jointStatesMutex);
-    for ( KinematicUnitSimulationJointStates::iterator it = jointStates.begin(); it!=jointStates.end(); it++ )
+
+    for (KinematicUnitSimulationJointStates::iterator it = jointStates.begin(); it != jointStates.end(); it++)
     {
         it->second.velocity = 0;
     }
+
     SensorActorUnit::stop(c);
 }
 
@@ -317,6 +362,7 @@ void KinematicUnitSimulation::requestJoints(const StringSequence& joints, const
     ARMARX_INFO << flush;
     // if one of the joints belongs to this unit, lock access to this unit for other components except for the requesting one
     KinematicUnitSimulationJointStates::const_iterator it = std::find_first_of(jointStates.begin(), jointStates.end(), joints.begin(), joints.end(), mapEntryEqualsString);
+
     if (jointStates.end() != it)
     {
         KinematicUnit::request(c);
@@ -328,6 +374,7 @@ void KinematicUnitSimulation::releaseJoints(const StringSequence& joints, const
     ARMARX_INFO << flush;
     // if one of the joints belongs to this unit, unlock access
     KinematicUnitSimulationJointStates::const_iterator it = std::find_first_of(jointStates.begin(), jointStates.end(), joints.begin(), joints.end(), mapEntryEqualsString);
+
     if (jointStates.end() != it)
     {
         KinematicUnit::release(c);
diff --git a/source/RobotAPI/components/units/KinematicUnitSimulation.h b/source/RobotAPI/components/units/KinematicUnitSimulation.h
index a0464e610c5bd6550bfb7b73704298855136b53b..236bda6325f8101369929f5b595ccfdd04b90198 100644
--- a/source/RobotAPI/components/units/KinematicUnitSimulation.h
+++ b/source/RobotAPI/components/units/KinematicUnitSimulation.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    ArmarXCore::units
  * @author     Christian Boege (boege dot at kit dot edu)
  * @date       2011
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -26,8 +25,8 @@
 
 #include "KinematicUnit.h"
 
-#include <Core/core/services/tasks/PeriodicTask.h>
-#include <Core/core/system/ImportExportComponent.h>
+#include <ArmarXCore/core/services/tasks/PeriodicTask.h>
+#include <ArmarXCore/core/system/ImportExportComponent.h>
 #include <random>
 
 #include <IceUtil/Time.h>
@@ -103,7 +102,7 @@ namespace armarx
      * \brief
      */
     class KinematicUnitSimulationPropertyDefinitions :
-            public KinematicUnitPropertyDefinitions
+        public KinematicUnitPropertyDefinitions
     {
     public:
         KinematicUnitSimulationPropertyDefinitions(std::string prefix) :
@@ -124,7 +123,10 @@ namespace armarx
     {
     public:
         // inherited from Component
-        virtual std::string getDefaultName() const { return "KinematicUnitSimulation"; }
+        virtual std::string getDefaultName() const
+        {
+            return "KinematicUnitSimulation";
+        }
 
         virtual void onInitKinematicUnit();
         virtual void onStartKinematicUnit();
@@ -152,7 +154,7 @@ namespace armarx
          */
         virtual void setJointDecelerations(const NameValueMap& targetJointDecelerations, const Ice::Current& c = ::Ice::Current());
 
-        void stop(const Ice::Current &c = Ice::Current());
+        void stop(const Ice::Current& c = Ice::Current());
 
         /**
          * \see PropertyUser::createPropertyDefinitions()
diff --git a/source/RobotAPI/components/units/PlatformUnit.cpp b/source/RobotAPI/components/units/PlatformUnit.cpp
index 7e0273357c3aa8010006abdfc910ff77c809f330..7a0e6c3e8b8096fd6a8f74f666612a9a3fa66b84 100644
--- a/source/RobotAPI/components/units/PlatformUnit.cpp
+++ b/source/RobotAPI/components/units/PlatformUnit.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    ArmarXCore::units
  * @author     Manfred Kroehnert (Manfred dot Kroehnert at kit dot edu)
  * @date       2013
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -63,7 +62,7 @@ void PlatformUnit::onExitComponent()
 }
 
 
-void PlatformUnit::moveTo(Ice::Float targetPlatformPositionX, Ice::Float targetPlatformPositionY, Ice::Float targetPlatformRotation, Ice::Float positionalAccuracy, Ice::Float orientationalAccuracy, const Ice::Current &c)
+void PlatformUnit::moveTo(Ice::Float targetPlatformPositionX, Ice::Float targetPlatformPositionY, Ice::Float targetPlatformRotation, Ice::Float positionalAccuracy, Ice::Float orientationalAccuracy, const Ice::Current& c)
 {
 }
 
@@ -71,5 +70,5 @@ void PlatformUnit::moveTo(Ice::Float targetPlatformPositionX, Ice::Float targetP
 PropertyDefinitionsPtr PlatformUnit::createPropertyDefinitions()
 {
     return PropertyDefinitionsPtr(new PlatformUnitPropertyDefinitions(
-                                           getConfigIdentifier()));
+                                      getConfigIdentifier()));
 }
diff --git a/source/RobotAPI/components/units/PlatformUnit.h b/source/RobotAPI/components/units/PlatformUnit.h
index 6252fe48e75e14493bbf3db9306134d78c2e508c..3b49d038d9ac02503d4857394b8bb7faa6e72a63 100644
--- a/source/RobotAPI/components/units/PlatformUnit.h
+++ b/source/RobotAPI/components/units/PlatformUnit.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    ArmarXCore::units
  * @author     Manfred Kroehnert (Manfred dot Kroehnert at kit dot edu)
  * @date       2013
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -26,8 +25,8 @@
 
 #include <RobotAPI/components/units/SensorActorUnit.h>
 
-#include <Core/core/application/properties/Properties.h>
-#include <Core/core/system/ImportExportComponent.h>
+#include <ArmarXCore/core/application/properties/Properties.h>
+#include <ArmarXCore/core/system/ImportExportComponent.h>
 
 #include <RobotAPI/interface/units/PlatformUnitInterface.h>
 
@@ -40,7 +39,7 @@ namespace armarx
      * \brief Defines all necessary properties for armarx::PlatformUnit
      */
     class PlatformUnitPropertyDefinitions:
-            public ComponentPropertyDefinitions
+        public ComponentPropertyDefinitions
     {
     public:
         PlatformUnitPropertyDefinitions(std::string prefix):
@@ -52,7 +51,7 @@ namespace armarx
 
 
     /**
-     * \class PlatformUnit
+     * \defgroup Component-PlatformUnit PlatformUnit
      * \ingroup RobotAPI-SensorActorUnits
      * \brief Base unit for high-level access to robot platforms.
      *
@@ -60,6 +59,11 @@ namespace armarx
      * An instance of a PlatformUnit provides means to set target positions.
      * It uses the PlatformUnitListener Ice interface to report updates of its current state.
      */
+
+    /**
+     * @ingroup Component-PlatformUnit
+     * @brief The PlatformUnit class
+     */
     class PlatformUnit :
         virtual public PlatformUnitInterface,
         virtual public SensorActorUnit
@@ -102,7 +106,7 @@ namespace armarx
         virtual void moveTo(Ice::Float targetPlatformPositionX, Ice::Float targetPlatformPositionY, Ice::Float targetPlatformRotation,
                             Ice::Float positionalAccuracy, Ice::Float orientationalAccuracy, const Ice::Current& c = ::Ice::Current());
 
-        void stopPlatform(const Ice::Current &c = Ice::Current()){}
+        void stopPlatform(const Ice::Current& c = Ice::Current()) {}
         /**
          * \see armarx::PropertyUser::createPropertyDefinitions()
          */
diff --git a/source/RobotAPI/components/units/PlatformUnitObserver.cpp b/source/RobotAPI/components/units/PlatformUnitObserver.cpp
index c0a6930a752a298460e0c3c9006fb23403331060..01c6bfd20e173a4ad2893ebd99782958d47d7898 100644
--- a/source/RobotAPI/components/units/PlatformUnitObserver.cpp
+++ b/source/RobotAPI/components/units/PlatformUnitObserver.cpp
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -25,13 +24,13 @@
 
 #include "PlatformUnit.h"
 
-#include <Core/observers/checks/ConditionCheckUpdated.h>
-#include <Core/observers/checks/ConditionCheckEquals.h>
-#include <Core/observers/checks/ConditionCheckInRange.h>
-#include <Core/observers/checks/ConditionCheckLarger.h>
-#include <Core/observers/checks/ConditionCheckSmaller.h>
-#include <Core/observers/checks/ConditionCheckValid.h>
-#include <Core/observers/checks/ConditionCheckEqualsWithTolerance.h>
+#include <ArmarXCore/observers/checks/ConditionCheckUpdated.h>
+#include <ArmarXCore/observers/checks/ConditionCheckEquals.h>
+#include <ArmarXCore/observers/checks/ConditionCheckInRange.h>
+#include <ArmarXCore/observers/checks/ConditionCheckLarger.h>
+#include <ArmarXCore/observers/checks/ConditionCheckSmaller.h>
+#include <ArmarXCore/observers/checks/ConditionCheckValid.h>
+#include <ArmarXCore/observers/checks/ConditionCheckEqualsWithTolerance.h>
 
 
 using namespace armarx;
@@ -112,5 +111,5 @@ void PlatformUnitObserver::nameValueMapToDataFields(std::string channelName, ::I
 PropertyDefinitionsPtr PlatformUnitObserver::createPropertyDefinitions()
 {
     return PropertyDefinitionsPtr(new PlatformUnitPropertyDefinitions(
-                                           getConfigIdentifier()));
+                                      getConfigIdentifier()));
 }
diff --git a/source/RobotAPI/components/units/PlatformUnitObserver.h b/source/RobotAPI/components/units/PlatformUnitObserver.h
index d07da91a4a16875949df07b272b90c8f065df2a3..5589e366c3d49e004e83fce534fe842b0c7117b4 100644
--- a/source/RobotAPI/components/units/PlatformUnitObserver.h
+++ b/source/RobotAPI/components/units/PlatformUnitObserver.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -24,15 +23,15 @@
 #ifndef _ARMARX_CORE_KINEMATIC_UNIT_OBSERVER_H
 #define _ARMARX_CORE_KINEMATIC_UNIT_OBSERVER_H
 
-#include <Core/core/system/ImportExport.h>
-#include <Core/core/Component.h>
+#include <ArmarXCore/core/system/ImportExport.h>
+#include <ArmarXCore/core/Component.h>
 
 #include <RobotAPI/interface/observers/PlatformUnitObserverInterface.h>
-#include <Core/interface/observers/VariantBase.h>
+#include <ArmarXCore/interface/observers/VariantBase.h>
 
-#include <Core/observers/ConditionCheck.h>
-#include <Core/observers/Observer.h>
-#include <Core/observers/ObserverObjectFactories.h>
+#include <ArmarXCore/observers/ConditionCheck.h>
+#include <ArmarXCore/observers/Observer.h>
+#include <ArmarXCore/observers/ObserverObjectFactories.h>
 
 #include <string>
 
@@ -42,19 +41,19 @@ namespace armarx
     ARMARX_CREATE_CHECK(PlatformUnitObserver, larger)
     ARMARX_CREATE_CHECK(PlatformUnitObserver, inrange)
 
-   /**
-    * \class PlatformUnitObserver
-    * \ingroup RobotAPI-SensorActorUnits-observers
-    * \brief Observer monitoring platform-related sensor values.
-    *
-    * The PlatformUnitObserver allows the installation of conditions on all channel reported by the PlatformUnit.
-    * These include current and target position.
-    *
-    * The PlatformUnitObserver retrieves its platform configuration via properties.
-    * The name must exist in the used Simox robot model file.
-    *
-    * Available condition checks are: *valid*, *updated*, *equals*, *inrange*, *approx*, *larger* and *smaller*.
-    */
+    /**
+     * \class PlatformUnitObserver
+     * \ingroup RobotAPI-SensorActorUnits-observers
+     * \brief Observer monitoring platform-related sensor values.
+     *
+     * The PlatformUnitObserver allows the installation of conditions on all channel reported by the PlatformUnit.
+     * These include current and target position.
+     *
+     * The PlatformUnitObserver retrieves its platform configuration via properties.
+     * The name must exist in the used Simox robot model file.
+     *
+     * Available condition checks are: *valid*, *updated*, *equals*, *inrange*, *approx*, *larger* and *smaller*.
+     */
     class ARMARXCORE_IMPORT_EXPORT PlatformUnitObserver :
         virtual public Observer,
         virtual public PlatformUnitObserverInterface
@@ -94,7 +93,7 @@ namespace armarx
     class PlatformUnitDatafieldCreator
     {
     public:
-        PlatformUnitDatafieldCreator(const std::string &channelName) :
+        PlatformUnitDatafieldCreator(const std::string& channelName) :
             channelName(channelName)
         {}
 
@@ -107,10 +106,16 @@ namespace armarx
          */
         DataFieldIdentifier getDatafield(const std::string& platformUnitObserverName, const std::string& platformName) const
         {
-            if(platformUnitObserverName.empty())
+            if (platformUnitObserverName.empty())
+            {
                 throw LocalException("kinematicUnitObserverName must not be empty!");
-            if(platformName.empty())
+            }
+
+            if (platformName.empty())
+            {
                 throw LocalException("jointName must not be empty!");
+            }
+
             return DataFieldIdentifier(platformUnitObserverName, channelName, platformName);
         }
 
diff --git a/source/RobotAPI/components/units/PlatformUnitSimulation.cpp b/source/RobotAPI/components/units/PlatformUnitSimulation.cpp
index 44c57e54a17ec4cefa57370407425351995ed97c..382a28c0a801c6fb13700d6b57fa6cee309f4f35 100644
--- a/source/RobotAPI/components/units/PlatformUnitSimulation.cpp
+++ b/source/RobotAPI/components/units/PlatformUnitSimulation.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    ArmarXCore::units
  * @author     Christian Boege (boege at kit dot edu)
  * @date       2011
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -54,15 +53,19 @@ void PlatformUnitSimulation::onStartPlatformUnit()
 
 void PlatformUnitSimulation::onStopPlatformUnit()
 {
-    if(simulationTask)
+    if (simulationTask)
+    {
         simulationTask->stop();
+    }
 }
 
 
 void PlatformUnitSimulation::onExitPlatformUnit()
 {
-    if(simulationTask)
+    if (simulationTask)
+    {
         simulationTask->stop();
+    }
 }
 
 
@@ -75,29 +78,41 @@ void PlatformUnitSimulation::simulationFunction()
     {
         ScopedLock lock(currentPoseMutex);
         float diff = fabs(targetPositionX - currentPositionX);
+
         if (diff > positionalAccuracy)
         {
             int sign = copysignf(1.0f, (targetPositionX - currentPositionX));
             currentPositionX += sign * std::min<float>(linearVelocity * timeDeltaInSeconds, diff);
             vel[0] = linearVelocity;
         }
+
         diff = fabs(targetPositionY - currentPositionY);
+
         if (diff > positionalAccuracy)
         {
             int sign = copysignf(1.0f, (targetPositionY - currentPositionY));
             currentPositionY +=  sign * std::min<float>(linearVelocity * timeDeltaInSeconds, diff);
             vel[1] = linearVelocity;
         }
+
         diff = fabs(targetRotation - currentRotation);
+
         if (diff > orientationalAccuracy)
         {
             int sign = copysignf(1.0f, (targetRotation - currentRotation));
             currentRotation += sign * std::min<float>(angularVelocity * timeDeltaInSeconds, diff);
+
             // stay between +/- M_2_PI
-            if(currentRotation > 2 * M_PI)
+            if (currentRotation > 2 * M_PI)
+            {
                 currentRotation -= 2 * M_PI;
-            if(currentRotation < -2 * M_PI)
+            }
+
+            if (currentRotation < -2 * M_PI)
+            {
                 currentRotation += 2 * M_PI;
+            }
+
             vel[2] = angularVelocity;
 
         }
@@ -127,12 +142,12 @@ PropertyDefinitionsPtr PlatformUnitSimulation::createPropertyDefinitions()
 }
 
 
-void armarx::PlatformUnitSimulation::move(float targetPlatformVelocityX, float targetPlatformVelocityY, float targetPlatformVelocityRotation, const Ice::Current &c)
+void armarx::PlatformUnitSimulation::move(float targetPlatformVelocityX, float targetPlatformVelocityY, float targetPlatformVelocityRotation, const Ice::Current& c)
 {
     throw LocalException("NYI");
 }
 
-void PlatformUnitSimulation::moveRelative(float targetPlatformOffsetX, float targetPlatformOffsetY, float targetPlatformOffsetRotation, float positionalAccuracy, float orientationalAccuracy, const Ice::Current &c)
+void PlatformUnitSimulation::moveRelative(float targetPlatformOffsetX, float targetPlatformOffsetY, float targetPlatformOffsetRotation, float positionalAccuracy, float orientationalAccuracy, const Ice::Current& c)
 {
     float targetPositionX, targetPositionY, targetRotation;
     {
@@ -144,7 +159,7 @@ void PlatformUnitSimulation::moveRelative(float targetPlatformOffsetX, float tar
     moveTo(targetPositionX, targetPositionY, targetRotation, positionalAccuracy, orientationalAccuracy);
 }
 
-void PlatformUnitSimulation::setMaxVelocities(float positionalVelocity, float orientaionalVelocity, const Ice::Current &c)
+void PlatformUnitSimulation::setMaxVelocities(float positionalVelocity, float orientaionalVelocity, const Ice::Current& c)
 {
     ScopedLock lock(currentPoseMutex);
     linearVelocity = positionalVelocity;
diff --git a/source/RobotAPI/components/units/PlatformUnitSimulation.h b/source/RobotAPI/components/units/PlatformUnitSimulation.h
index dfd0e18ab04cfa3ae59a2ac94a05b524e3a42a1b..0e9bb1fc683262e4117b7fae14d1a83ce9ec4a87 100644
--- a/source/RobotAPI/components/units/PlatformUnitSimulation.h
+++ b/source/RobotAPI/components/units/PlatformUnitSimulation.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    ArmarXCore::units
  * @author     Christian Boege (boege dot at kit dot edu)
  * @date       2011
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -26,8 +25,8 @@
 
 #include "PlatformUnit.h"
 
-#include <Core/core/services/tasks/PeriodicTask.h>
-#include <Core/core/system/ImportExportComponent.h>
+#include <ArmarXCore/core/services/tasks/PeriodicTask.h>
+#include <ArmarXCore/core/system/ImportExportComponent.h>
 
 #include <IceUtil/Time.h>
 
@@ -40,7 +39,7 @@ namespace armarx
      * \brief
      */
     class PlatformUnitSimulationPropertyDefinitions :
-            public PlatformUnitPropertyDefinitions
+        public PlatformUnitPropertyDefinitions
     {
     public:
         PlatformUnitSimulationPropertyDefinitions(std::string prefix) :
@@ -84,10 +83,10 @@ namespace armarx
         /**
          * \warning Not yet implemented!
          */
-        void move(float targetPlatformVelocityX, float targetPlatformVelocityY, float targetPlatformVelocityRotation, const Ice::Current &c = Ice::Current());
+        void move(float targetPlatformVelocityX, float targetPlatformVelocityY, float targetPlatformVelocityRotation, const Ice::Current& c = Ice::Current());
 
-        void moveRelative(float targetPlatformOffsetX, float targetPlatformOffsetY, float targetPlatformOffsetRotation, float positionalAccuracy, float orientationalAccuracy, const Ice::Current &c = Ice::Current());
-        void setMaxVelocities(float positionalVelocity, float orientaionalVelocity, const Ice::Current &c = Ice::Current());
+        void moveRelative(float targetPlatformOffsetX, float targetPlatformOffsetY, float targetPlatformOffsetRotation, float positionalAccuracy, float orientationalAccuracy, const Ice::Current& c = Ice::Current());
+        void setMaxVelocities(float positionalVelocity, float orientaionalVelocity, const Ice::Current& c = Ice::Current());
 
         /**
          * \see PropertyUser::createPropertyDefinitions()
diff --git a/source/RobotAPI/components/units/SensorActorUnit.cpp b/source/RobotAPI/components/units/SensorActorUnit.cpp
index eb4b644573b690bcf204244d665ec21f149e8cf4..c716b3f708759d67825dd565a1d2d14979a0825e 100644
--- a/source/RobotAPI/components/units/SensorActorUnit.cpp
+++ b/source/RobotAPI/components/units/SensorActorUnit.cpp
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -40,71 +39,77 @@ SensorActorUnit::~SensorActorUnit()
 
 void SensorActorUnit::init(const Ice::Current& c)
 {
-	std::string currentName = c.adapter->getName();
-	Ice::Identity currentId = c.adapter->getCommunicator()->stringToIdentity(currentName);
-	if(ownerId == currentId)
-	{
+    std::string currentName = c.adapter->getName();
+    Ice::Identity currentId = c.adapter->getCommunicator()->stringToIdentity(currentName);
+
+    if (ownerId == currentId)
+    {
         CALLINFO
-    	if(executionState == eUnitConstructed)
-    	{
-        	executionState = eUnitInitialized;
-        	onInit();
-    	}
-    	else
-		{
-        	ARMARX_LOG << armarx::eWARN << "Unit " << getName() << " is already initialized." << armarx::flush;
-		}
-	}
+
+        if (executionState == eUnitConstructed)
+        {
+            executionState = eUnitInitialized;
+            onInit();
+        }
+        else
+        {
+            ARMARX_LOG << armarx::eWARN << "Unit " << getName() << " is already initialized." << armarx::flush;
+        }
+    }
     else
-	{
+    {
         ARMARX_LOG << armarx::eWARN << "Unit " << getName() << " can not be initialized while unrequested." << armarx::flush;
-	}
+    }
 }
 
 void SensorActorUnit::start(const Ice::Current& c)
 {
-	std::string currentName = c.adapter->getName();
-	Ice::Identity currentId = c.adapter->getCommunicator()->stringToIdentity(currentName);
-	if(ownerId == currentId)
-	{
+    std::string currentName = c.adapter->getName();
+    Ice::Identity currentId = c.adapter->getCommunicator()->stringToIdentity(currentName);
+
+    if (ownerId == currentId)
+    {
         CALLINFO
-    	if( (executionState == eUnitInitialized ) || (executionState == eUnitStopped) )
-    	{
+
+        if ((executionState == eUnitInitialized) || (executionState == eUnitStopped))
+        {
             executionState = eUnitStarted;
             onStart();
-    	}
-    	else
-		{
-        	ARMARX_LOG << armarx::eWARN << "Unit " << getName() << " could not be started." << armarx::flush;
-    	}
-	}
+        }
+        else
+        {
+            ARMARX_LOG << armarx::eWARN << "Unit " << getName() << " could not be started." << armarx::flush;
+        }
+    }
     else
-	{
+    {
         ARMARX_LOG << armarx::eWARN << "Unit " << getName() << " can not be started while unrequested." << armarx::flush;
-	}
+    }
 }
 
 void SensorActorUnit::stop(const Ice::Current& c)
 {
-	std::string currentName = c.adapter->getName();
-	Ice::Identity currentId = c.adapter->getCommunicator()->stringToIdentity(currentName);
-	if(ownerId == currentId)
-	{
+    std::string currentName = c.adapter->getName();
+    Ice::Identity currentId = c.adapter->getCommunicator()->stringToIdentity(currentName);
+
+    if (ownerId == currentId)
+    {
         CALLINFO
-	    if(executionState == eUnitStarted)
-    	{
-    	    executionState = eUnitStopped;
-    	    onStop();
-    	}
-    	else
-		{
-        	ARMARX_LOG << armarx::eWARN << "Unit " << getName() << " could not be stopped." << armarx::flush;
-		}
-	}
+
+        if (executionState == eUnitStarted)
+        {
+            executionState = eUnitStopped;
+            onStop();
+        }
+        else
+        {
+            ARMARX_LOG << armarx::eWARN << "Unit " << getName() << " could not be stopped." << armarx::flush;
+        }
+    }
     else
-	{
+    {
         ARMARX_LOG << armarx::eWARN << "Unit " << getName() << " can not be stopped while unrequested. " << armarx::flush;
-	}
+    }
 }
 
 UnitExecutionState SensorActorUnit::getExecutionState(const Ice::Current& c)
@@ -117,8 +122,9 @@ UnitExecutionState SensorActorUnit::getExecutionState(const Ice::Current& c)
 void SensorActorUnit::request(const Ice::Current& c)
 {
     CALLINFO
+
     // try to lock unit
-    if(!unitMutex.try_lock())
+    if (!unitMutex.try_lock())
     {
         ARMARX_LOG << armarx::eERROR << "Trying to request already owned unit " << getName() << "\n" << armarx::flush;
         throw ResourceUnavailableException("Trying to request already owned unit");
@@ -128,7 +134,7 @@ void SensorActorUnit::request(const Ice::Current& c)
     std::string ownerName = c.adapter->getName();
     ownerId = c.adapter->getCommunicator()->stringToIdentity(ownerName);
 
-    ARMARX_INFO << "unit requested by "<< ownerName << flush;
+    ARMARX_INFO << "unit requested by " << ownerName << flush;
 }
 
 void SensorActorUnit::release(const Ice::Current& c)
@@ -138,7 +144,7 @@ void SensorActorUnit::release(const Ice::Current& c)
     std::string callerName = c.adapter->getName();
     Ice::Identity callerId = c.adapter->getCommunicator()->stringToIdentity(callerName);
 
-    if(!(ownerId == callerId))
+    if (!(ownerId == callerId))
     {
         ARMARX_LOG << armarx::eERROR << "Trying to release unit owned by another component" << armarx::flush;
         throw ResourceNotOwnedException("Trying to release unit owned by another component");
diff --git a/source/RobotAPI/components/units/SensorActorUnit.h b/source/RobotAPI/components/units/SensorActorUnit.h
index 7180ec22424c9417620b862540acdfa9bf790b6c..db78c6f821ff6b51336a79c10f7387c53eaca2af 100644
--- a/source/RobotAPI/components/units/SensorActorUnit.h
+++ b/source/RobotAPI/components/units/SensorActorUnit.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -24,9 +23,9 @@
 #ifndef SENSOR_ACTOR_UNIT_H
 #define SENSOR_ACTOR_UNIT_H
 
-#include <Core/core/system/ImportExport.h>
-#include <Core/core/Component.h>
-#include <Core/core/exceptions/Exception.h>
+#include <ArmarXCore/core/system/ImportExport.h>
+#include <ArmarXCore/core/Component.h>
+#include <ArmarXCore/core/exceptions/Exception.h>
 #include <RobotAPI/interface/units/UnitInterface.h>
 
 
@@ -44,91 +43,91 @@ namespace armarx
         virtual public SensorActorUnitInterface,
         virtual public Component
     {
-        public:
-            /**
-            * Constructs a SensorActorUnit.
-            */
-            SensorActorUnit();
-            /**
-            * Destructor of SensorActorUnit.
-            */
-            virtual ~SensorActorUnit();
+    public:
+        /**
+        * Constructs a SensorActorUnit.
+        */
+        SensorActorUnit();
+        /**
+        * Destructor of SensorActorUnit.
+        */
+        virtual ~SensorActorUnit();
 
-            /**
-            * Set execution state to eInitialized.
-            *
-            * Assures that init is called only once and the calls subclass method onInit().
-            *
-            * \param c Ice context provided by the Ice framework
-            */
-            virtual void init(const Ice::Current& c = ::Ice::Current());
+        /**
+        * Set execution state to eInitialized.
+        *
+        * Assures that init is called only once and the calls subclass method onInit().
+        *
+        * \param c Ice context provided by the Ice framework
+        */
+        virtual void init(const Ice::Current& c = ::Ice::Current());
 
-            /**
-            * Set execution state to eStarted
-            *
-            * Start streaming of sensory data and acceptance of control data.
-            *
-            * Start can be called if the unit is initialized and not started yet (stopped).
-            * Calls subclass method inStart().
-            *
-            * \param c Ice context provided by the Ice framework
-            */
-            virtual void start(const Ice::Current& c = ::Ice::Current());
+        /**
+        * Set execution state to eStarted
+        *
+        * Start streaming of sensory data and acceptance of control data.
+        *
+        * Start can be called if the unit is initialized and not started yet (stopped).
+        * Calls subclass method inStart().
+        *
+        * \param c Ice context provided by the Ice framework
+        */
+        virtual void start(const Ice::Current& c = ::Ice::Current());
 
-            /**
-            * Set execution state to eStopped
-            *
-            * Stop streaming of sensory data and acceptance of control data.
-            *
-            * Stop can be called if the unit is started.
-            * Calls subclass method onStop()
-            *
-            * \param c Ice context provided by the Ice framework
-            */
-            virtual void stop(const Ice::Current& c = ::Ice::Current());
+        /**
+        * Set execution state to eStopped
+        *
+        * Stop streaming of sensory data and acceptance of control data.
+        *
+        * Stop can be called if the unit is started.
+        * Calls subclass method onStop()
+        *
+        * \param c Ice context provided by the Ice framework
+        */
+        virtual void stop(const Ice::Current& c = ::Ice::Current());
 
-            /**
-            * Retrieve current execution state
-            *
-            * \param c Ice context provided by the Ice framework
-            * \return current execution state
-            */
-            UnitExecutionState getExecutionState(const Ice::Current& c = ::Ice::Current());
+        /**
+        * Retrieve current execution state
+        *
+        * \param c Ice context provided by the Ice framework
+        * \return current execution state
+        */
+        UnitExecutionState getExecutionState(const Ice::Current& c = ::Ice::Current());
 
-            /**
-            * Request exclusive access to current unit. Throws ResourceUnavailableException on error.
-            *
-            * \param c Ice context provided by the Ice framework
-            */
-            virtual void request(const Ice::Current& c = ::Ice::Current());
+        /**
+        * Request exclusive access to current unit. Throws ResourceUnavailableException on error.
+        *
+        * \param c Ice context provided by the Ice framework
+        */
+        virtual void request(const Ice::Current& c = ::Ice::Current());
 
-            /**
-            * Release exclusive access to current unit. Throws ResourceUnavailableException on error.
-            *
-            * \param c Ice context provided by the Ice framework
-            */
-            virtual void release(const Ice::Current& c = ::Ice::Current());
+        /**
+        * Release exclusive access to current unit. Throws ResourceUnavailableException on error.
+        *
+        * \param c Ice context provided by the Ice framework
+        */
+        virtual void release(const Ice::Current& c = ::Ice::Current());
 
-        protected:
-            void onExitComponent();
-            /**
-            * callback onInit for subclass hook. See init().
-            */
-            virtual void onInit() {};
+    protected:
+        void onExitComponent();
+        /**
+        * callback onInit for subclass hook. See init().
+        */
+        virtual void onInit() {};
 
-            /**
-            * callback onStart for subclass hook. See start().
-            */
-            virtual void onStart() {};
+        /**
+        * callback onStart for subclass hook. See start().
+        */
+        virtual void onStart() {};
 
-            /**
-            * callback onStop for subclass hook. See stop().
-            */
-            virtual void onStop() {};
+        /**
+        * callback onStop for subclass hook. See stop().
+        */
+        virtual void onStop() {};
 
-            boost::mutex unitMutex;
-            Ice::Identity ownerId;
-            UnitExecutionState  executionState;
+        boost::mutex unitMutex;
+        Ice::Identity ownerId;
+        UnitExecutionState  executionState;
     };
 }
 
diff --git a/source/RobotAPI/components/units/TCPControlUnit.cpp b/source/RobotAPI/components/units/TCPControlUnit.cpp
index 07ebe712c319827c8bc4e2d46f731937124c3f73..8ddedde1f105cd85d190fe028c57bded83d8b8ad 100644
--- a/source/RobotAPI/components/units/TCPControlUnit.cpp
+++ b/source/RobotAPI/components/units/TCPControlUnit.cpp
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::
 * @author     Mirko Waechter ( mirko.waechter at kit dot edu)
 * @date       2013
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -26,9 +25,9 @@
 
 #include <boost/unordered_map.hpp>
 
-#include <Core/core/exceptions/local/ExpressionException.h>
+#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 
-#include <Core/core/system/ArmarXDataPath.h>
+#include <ArmarXCore/core/system/ArmarXDataPath.h>
 #include <VirtualRobot/RobotConfig.h>
 #include <VirtualRobot/XML/RobotIO.h>
 
@@ -43,7 +42,7 @@ namespace armarx
 {
 
     TCPControlUnit::TCPControlUnit() :
-        maxJointVelocity(30.f/180*3.141),
+        maxJointVelocity(30.f / 180 * 3.141),
         cycleTime(30),
         requested(false),
         calculationRunning(false)
@@ -58,7 +57,7 @@ namespace armarx
         usingProxy("RobotStateComponent");
         usingProxy("DebugObserver");
         offeringTopic(topicName);
-        usingTopic("RobotState");
+        usingTopic(getProperty<std::string>("RobotStateTopicName").getValue());
 
         cycleTime = getProperty<int>("CycleTime").getValue();
         maxJointVelocity = getProperty<float>("MaxJointVelocity").getValue();
@@ -81,15 +80,19 @@ namespace armarx
         localReportRobot = localRobot->clone(localRobot->getName());
 
         std::string nodesetsString = getProperty<std::string>("TCPsToReport").getValue();
-        if(!nodesetsString.empty())
+
+        if (!nodesetsString.empty())
         {
-            if(nodesetsString=="*")
+            if (nodesetsString == "*")
             {
                 auto nodesets = localReportRobot->getRobotNodeSets();
-                for(RobotNodeSetPtr& set : nodesets)
+
+                for (RobotNodeSetPtr& set : nodesets)
                 {
-                    if(set->getTCP())
+                    if (set->getTCP())
+                    {
                         nodesToReport.push_back(set->getTCP());
+                    }
                 }
             }
             else
@@ -99,19 +102,26 @@ namespace armarx
                              nodesetsString,
                              boost::is_any_of(","),
                              boost::token_compress_on);
-                for(auto& name : nodesetNames)
+
+                for (auto& name : nodesetNames)
                 {
                     auto node = localReportRobot->getRobotNode(name);
-                    if(node)
+
+                    if (node)
+                    {
                         nodesToReport.push_back(node);
+                    }
                     else
+                    {
                         ARMARX_ERROR << "Could not find node set with name: " << name;
+                    }
                 }
             }
         }
 
         std::vector<RobotNodePtr> nodes = localRobot->getRobotNodes();
-        for(unsigned int i=0; i < nodes.size(); i++)
+
+        for (unsigned int i = 0; i < nodes.size(); i++)
         {
             ARMARX_VERBOSE << nodes.at(i)->getName();
         }
@@ -121,8 +131,12 @@ namespace armarx
         listener = getTopic<TCPControlUnitListenerPrx>(topicName);
 
         requested = false;
-        if(execTask)
+
+        if (execTask)
+        {
             execTask->stop();
+        }
+
         execTask = new PeriodicTask<TCPControlUnit>(this, &TCPControlUnit::periodicExec, cycleTime, false, "TCPVelocityCalculator");
         execTask->start();
         execTask->setDelayWarningTolerance(100);
@@ -136,13 +150,15 @@ namespace armarx
         {
             release();
         }
-        catch(std::exception&e)
+        catch (std::exception& e)
         {
             ARMARX_WARNING << "Releasing TCP Unit failed";
         }
 
-        if(execTask)
+        if (execTask)
+        {
             execTask->stop();
+        }
     }
 
     void TCPControlUnit::onExitComponent()
@@ -151,30 +167,39 @@ namespace armarx
 
 
 
-    void TCPControlUnit::setCycleTime(Ice::Int milliseconds, const Ice::Current & c)
+    void TCPControlUnit::setCycleTime(Ice::Int milliseconds, const Ice::Current& c)
     {
         ScopedLock lock(taskMutex);
         cycleTime = milliseconds;
-        if(execTask)
+
+        if (execTask)
+        {
             execTask->changeInterval(cycleTime);
+        }
     }
 
-    void TCPControlUnit::setTCPVelocity(const std::string &nodeSetName, const std::string &tcpName, const FramedDirectionBasePtr &translationVelocity, const FramedDirectionBasePtr &orientationVelocityRPY, const Ice::Current &c)
+    void TCPControlUnit::setTCPVelocity(const std::string& nodeSetName, const std::string& tcpName, const FramedDirectionBasePtr& translationVelocity, const FramedDirectionBasePtr& orientationVelocityRPY, const Ice::Current& c)
     {
         ScopedLock lock(dataMutex);
         ARMARX_CHECK_EXPRESSION_W_HINT(jointExistenceCheckRobot->hasRobotNodeSet(nodeSetName), "The robot does not have the node set: " + nodeSetName);
 
 
-        if(translationVelocity)
+        if (translationVelocity)
+        {
             ARMARX_DEBUG << "Setting new Velocity for " << nodeSetName << " in frame " << translationVelocity->frame << ":\n" << FramedDirectionPtr::dynamicCast(translationVelocity)->toEigen();
-        if(orientationVelocityRPY)
+        }
+
+        if (orientationVelocityRPY)
+        {
             ARMARX_DEBUG << "Orientation Velo in frame " << orientationVelocityRPY->frame << ": \n" << FramedDirectionPtr::dynamicCast(orientationVelocityRPY)->toEigen();
+        }
 
         TCPVelocityData data;
         data.nodeSetName = nodeSetName;
         data.translationVelocity = FramedDirectionPtr::dynamicCast(translationVelocity);
         data.orientationVelocity = FramedDirectionPtr::dynamicCast(orientationVelocityRPY);
-        if(tcpName.empty())
+
+        if (tcpName.empty())
         {
             data.tcpName = jointExistenceCheckRobot->getRobotNodeSet(nodeSetName)->getTCP()->getName();
         }
@@ -184,50 +209,60 @@ namespace armarx
 
             data.tcpName = tcpName;
         }
+
         tcpVelocitiesMap[data.tcpName] = data;
         lastCommandTime = IceUtil::Time::now();
     }
 
 
-    void TCPControlUnit::init(const Ice::Current & c)
+    void TCPControlUnit::init(const Ice::Current& c)
     {
     }
 
-    void TCPControlUnit::start(const Ice::Current & c)
+    void TCPControlUnit::start(const Ice::Current& c)
     {
     }
 
-    void TCPControlUnit::stop(const Ice::Current & c)
+    void TCPControlUnit::stop(const Ice::Current& c)
     {
     }
 
-    UnitExecutionState TCPControlUnit::getExecutionState(const Ice::Current & c)
+    UnitExecutionState TCPControlUnit::getExecutionState(const Ice::Current& c)
     {
         switch (getState())
         {
             case eManagedIceObjectStarted:
                 return eUnitStarted;
+
             case eManagedIceObjectInitialized:
             case eManagedIceObjectStarting:
                 return eUnitInitialized;
+
             case eManagedIceObjectExiting:
             case eManagedIceObjectExited:
                 return eUnitStopped;
+
             default:
                 return eUnitConstructed;
         }
     }
 
-    void TCPControlUnit::request(const Ice::Current & c)
+    void TCPControlUnit::request(const Ice::Current& c)
     {
         ARMARX_IMPORTANT << "Requesting TCPControlUnit";
         ScopedLock lock(dataMutex);
         requested = true;
-        if(execTask)
+
+        if (execTask)
         {
-            while (calculationRunning) IceUtil::ThreadControl::yield();
+            while (calculationRunning)
+            {
+                IceUtil::ThreadControl::yield();
+            }
+
             execTask->stop();
         }
+
         lastCommandTime = IceUtil::Time::now();
         execTask = new PeriodicTask<TCPControlUnit>(this, &TCPControlUnit::periodicExec, cycleTime, false, "TCPVelocityCalculator");
         execTask->start();
@@ -235,11 +270,16 @@ namespace armarx
         ARMARX_IMPORTANT << "Requested TCPControlUnit";
     }
 
-    void TCPControlUnit::release(const Ice::Current & c)
+    void TCPControlUnit::release(const Ice::Current& c)
     {
         ARMARX_IMPORTANT << "Releasing TCPControlUnit";
         ScopedLock lock(dataMutex);
-        while (calculationRunning) IceUtil::ThreadControl::yield();
+
+        while (calculationRunning)
+        {
+            IceUtil::ThreadControl::yield();
+        }
+
         tcpVelocitiesMap.clear();
         localTcpVelocitiesMap.clear();
         requested = false;
@@ -258,21 +298,23 @@ namespace armarx
             {
                 localTcpVelocitiesMap.clear();
                 TCPVelocityDataMap::iterator it = tcpVelocitiesMap.begin();
-                for(; it != tcpVelocitiesMap.end(); it++)
+
+                for (; it != tcpVelocitiesMap.end(); it++)
                 {
                     localTcpVelocitiesMap[it->first] = it->second;
                 }
 
                 localDIKMap.clear();
                 DIKMap::iterator itDIK = dIKMap.begin();
-                for(; itDIK != dIKMap.end(); itDIK++)
+
+                for (; itDIK != dIKMap.end(); itDIK++)
                 {
                     localDIKMap[itDIK->first] = itDIK->second;
                 }
 
                 //ARMARX_DEBUG << "RN TCP R pose1:" << localRobot->getRobotNode("TCP R")->getGlobalPose();
 
-                RemoteRobot::synchronizeLocalClone(localRobot,robotStateComponentPrx);
+                RemoteRobot::synchronizeLocalClone(localRobot, robotStateComponentPrx);
                 //ARMARX_DEBUG << "RN TCP R pose2:" << localRobot->getRobotNode("TCP R")->getGlobalPose();
             }
         }
@@ -288,7 +330,7 @@ namespace armarx
             //                release();                          <---- this is a potential deadlock
             //            }
             //            else
-                calcAndSetVelocities();
+            calcAndSetVelocities();
         }
 
         calculationRunning = false;
@@ -299,14 +341,19 @@ namespace armarx
     void TCPControlUnit::calcAndSetVelocities()
     {
         TCPVelocityDataMap::iterator it = localTcpVelocitiesMap.begin();
-        for(; it != localTcpVelocitiesMap.end(); it++)
+
+        for (; it != localTcpVelocitiesMap.end(); it++)
         {
             const TCPVelocityData& data = it->second;
             RobotNodeSetPtr nodeSet = localRobot->getRobotNodeSet(data.nodeSetName);
-//            std::string refFrame = nodeSet->getTCP()->getName();
+            //            std::string refFrame = nodeSet->getTCP()->getName();
             DIKMap::iterator itDIK = localDIKMap.find(data.nodeSetName);
-            if(itDIK == localDIKMap.end())
+
+            if (itDIK == localDIKMap.end())
+            {
                 localDIKMap[data.nodeSetName].reset(new EDifferentialIK(nodeSet, localRobot->getRootNode(), VirtualRobot::JacobiProvider::eSVDDamped));
+            }
+
             EDifferentialIKPtr dIk = boost::dynamic_pointer_cast<EDifferentialIK>(localDIKMap[data.nodeSetName]);
             dIk->clearGoals();
         }
@@ -314,25 +361,31 @@ namespace armarx
         using namespace Eigen;
 
         it = localTcpVelocitiesMap.begin();
-        for(; it != localTcpVelocitiesMap.end(); it++)
+
+        for (; it != localTcpVelocitiesMap.end(); it++)
         {
 
             TCPVelocityData& data = it->second;
-//            RobotNodeSetPtr nodeSet = localRobot->getRobotNodeSet(data.nodeSetName);
+            //            RobotNodeSetPtr nodeSet = localRobot->getRobotNodeSet(data.nodeSetName);
             std::string refFrame = localRobot->getRootNode()->getName();
             IKSolver::CartesianSelection mode;
-            if(data.translationVelocity && data.orientationVelocity)
+
+            if (data.translationVelocity && data.orientationVelocity)
             {
                 mode = IKSolver::All;
-//                ARMARX_DEBUG << deactivateSpam(4) << "FullMode";
+                //                ARMARX_DEBUG << deactivateSpam(4) << "FullMode";
             }
-            else if(data.translationVelocity && !data.orientationVelocity)
+            else if (data.translationVelocity && !data.orientationVelocity)
+            {
                 mode = IKSolver::Position;
-            else if(!data.translationVelocity && data.orientationVelocity)
+            }
+            else if (!data.translationVelocity && data.orientationVelocity)
+            {
                 mode = IKSolver::Orientation;
+            }
             else
             {
-//                ARMARX_VERBOSE << deactivateSpam(2) << "No mode feasible for " << data.nodeSetName << " - skipping";
+                //                ARMARX_VERBOSE << deactivateSpam(2) << "No mode feasible for " << data.nodeSetName << " - skipping";
                 continue;
             }
 
@@ -340,76 +393,91 @@ namespace armarx
             Eigen::Matrix4f m;
             m.setIdentity();
 
-            if(data.orientationVelocity)
+            if (data.orientationVelocity)
             {
                 Eigen::Matrix3f rotInOriginalFrame, rotInRefFrame;
-                rotInOriginalFrame =  Eigen::AngleAxisf(data.orientationVelocity->z*cycleTime*0.001, Eigen::Vector3f::UnitZ())
-                                    * Eigen::AngleAxisf(data.orientationVelocity->y*cycleTime*0.001, Eigen::Vector3f::UnitY())
-                                    * Eigen::AngleAxisf(data.orientationVelocity->x*cycleTime*0.001, Eigen::Vector3f::UnitX());
+                rotInOriginalFrame =  Eigen::AngleAxisf(data.orientationVelocity->z * cycleTime * 0.001, Eigen::Vector3f::UnitZ())
+                                      * Eigen::AngleAxisf(data.orientationVelocity->y * cycleTime * 0.001, Eigen::Vector3f::UnitY())
+                                      * Eigen::AngleAxisf(data.orientationVelocity->x * cycleTime * 0.001, Eigen::Vector3f::UnitX());
+
                 if (data.orientationVelocity->frame != refFrame)
                 {
                     Eigen::Matrix4f trafoOriginalFrameToGlobal = Eigen::Matrix4f::Identity();
-                    if (data.orientationVelocity->frame != GlobalFrame) trafoOriginalFrameToGlobal = localRobot->getRobotNode(data.orientationVelocity->frame)->getGlobalPose();
+
+                    if (data.orientationVelocity->frame != GlobalFrame)
+                    {
+                        trafoOriginalFrameToGlobal = localRobot->getRobotNode(data.orientationVelocity->frame)->getGlobalPose();
+                    }
+
                     Eigen::Matrix4f trafoRefFrameToGlobal = Eigen::Matrix4f::Identity();
-                    if (refFrame != GlobalFrame) trafoRefFrameToGlobal = localRobot->getRobotNode(refFrame)->getGlobalPose();
+
+                    if (refFrame != GlobalFrame)
+                    {
+                        trafoRefFrameToGlobal = localRobot->getRobotNode(refFrame)->getGlobalPose();
+                    }
+
                     Eigen::Matrix4f trafoOriginalToRef = trafoRefFrameToGlobal.inverse() * trafoOriginalFrameToGlobal;
-                    rotInRefFrame = trafoOriginalToRef.block<3,3>(0,0) * rotInOriginalFrame * trafoOriginalToRef.block<3,3>(0,0).inverse();
+                    rotInRefFrame = trafoOriginalToRef.block<3, 3>(0, 0) * rotInOriginalFrame * trafoOriginalToRef.block<3, 3>(0, 0).inverse();
                 }
                 else
                 {
                     rotInRefFrame = rotInOriginalFrame;
                 }
-                m.block(0,0,3,3) = rotInRefFrame * (tcpNode->getGlobalPose().block(0,0,3,3) );
+
+                m.block(0, 0, 3, 3) = rotInRefFrame * (tcpNode->getGlobalPose().block(0, 0, 3, 3));
             }
 
-//            ARMARX_VERBOSE << deactivateSpam(1) << "Delta Mat: \n" << m;
+            //            ARMARX_VERBOSE << deactivateSpam(1) << "Delta Mat: \n" << m;
 
 
-//            m =  m * tcpNode->getGlobalPose();
+            //            m =  m * tcpNode->getGlobalPose();
 
-            if(data.translationVelocity)
+            if (data.translationVelocity)
             {
                 data.translationVelocity = FramedDirection::ChangeFrame(localRobot, *data.translationVelocity, refFrame);
                 ARMARX_INFO << deactivateSpam(1) << "Translation in " << refFrame << ": " << data.translationVelocity->toEigen();
-                m.block(0,3,3,1) = tcpNode->getGlobalPose().block(0,3,3,1) + data.translationVelocity->toEigen()*cycleTime*0.001;
+                m.block(0, 3, 3, 1) = tcpNode->getGlobalPose().block(0, 3, 3, 1) + data.translationVelocity->toEigen() * cycleTime * 0.001;
             }
 
 
             DifferentialIKPtr dIK = localDIKMap[data.nodeSetName];
-            if(!dIK)
+
+            if (!dIK)
             {
                 ARMARX_WARNING << deactivateSpam(1) << "DiffIK is NULL for robot node set: " << data.nodeSetName;
                 continue;
             }
-//            ARMARX_VERBOSE << deactivateSpam(1) << "Old Pos: \n" << tcpNode->getGlobalPose();
-//            ARMARX_VERBOSE << deactivateSpam(1) << "New Goal: \n" << m;
-//            if(tcpNode != nodeSet->getTCP())
-//            {
-//                mode = IKSolver::Z;
-//                Eigen::VectorXf weight(1);
-//                weight << 0.2;
-//                boost::shared_dynamic_cast<EDifferentialIK>(dIK)->setGoal(m, tcpNode,mode, 0.001, 0.001/180.0f*3.14159, weight);
-//            }
-//            else
-                dIK->setGoal(m, tcpNode,mode, 0.001, 0.001/180.0f*3.14159);
-
-//            ARMARX_VERBOSE << deactivateSpam(1) << "Delta to Goal: " << dIK->getDeltaToGoal(tcpNode);
+
+            //            ARMARX_VERBOSE << deactivateSpam(1) << "Old Pos: \n" << tcpNode->getGlobalPose();
+            //            ARMARX_VERBOSE << deactivateSpam(1) << "New Goal: \n" << m;
+            //            if(tcpNode != nodeSet->getTCP())
+            //            {
+            //                mode = IKSolver::Z;
+            //                Eigen::VectorXf weight(1);
+            //                weight << 0.2;
+            //                boost::shared_dynamic_cast<EDifferentialIK>(dIK)->setGoal(m, tcpNode,mode, 0.001, 0.001/180.0f*3.14159, weight);
+            //            }
+            //            else
+            dIK->setGoal(m, tcpNode, mode, 0.001, 0.001 / 180.0f * 3.14159);
+
+            //            ARMARX_VERBOSE << deactivateSpam(1) << "Delta to Goal: " << dIK->getDeltaToGoal(tcpNode);
         }
 
 
         NameValueMap targetVelocities;
         NameControlModeMap controlModes;
         DIKMap::iterator itDIK = localDIKMap.begin();
-        for(; itDIK != localDIKMap.end(); itDIK++)
+
+        for (; itDIK != localDIKMap.end(); itDIK++)
         {
             RobotNodeSetPtr robotNodeSet = localRobot->getRobotNodeSet(itDIK->first);
 
             EDifferentialIKPtr dIK = boost::dynamic_pointer_cast<EDifferentialIK>(itDIK->second);
-//            ARMARX_VERBOSE << deactivateSpam(1) << "Old Pos: \n" << robotNodeSet->getTCP()->getGlobalPose();
-//            dIK->setVerbose(true);
+            //            ARMARX_VERBOSE << deactivateSpam(1) << "Old Pos: \n" << robotNodeSet->getTCP()->getGlobalPose();
+            //            dIK->setVerbose(true);
             Eigen::VectorXf jointDelta;
             dIK->computeSteps(jointDelta, 0.8f, 0.001, 1, &EDifferentialIK::computeStep); // 1.0, 0.00001, 50
-//            ARMARX_VERBOSE << deactivateSpam(1) << "New Goal: \n" << robotNodeSet->getTCP()->getGlobalPose();
+            //            ARMARX_VERBOSE << deactivateSpam(1) << "New Goal: \n" << robotNodeSet->getTCP()->getGlobalPose();
 
             MatrixXf fullJac = dIK->calcFullJacobian();
             MatrixXf fullJacInv = dIK->computePseudoInverseJacobianMatrix(fullJac);
@@ -436,24 +504,25 @@ namespace armarx
 
             if (jointLimitCompensation(0) == jointLimitCompensation(0))
             {
-                if (jointLimitCompensation.norm() > maxJointLimitCompensationRatio*jointDelta.norm())
+                if (jointLimitCompensation.norm() > maxJointLimitCompensationRatio * jointDelta.norm())
                 {
-                    jointLimitCompensation = maxJointLimitCompensationRatio*jointDelta.norm()/jointLimitCompensation.norm() * jointLimitCompensation;
+                    jointLimitCompensation = maxJointLimitCompensationRatio * jointDelta.norm() / jointLimitCompensation.norm() * jointLimitCompensation;
                 }
+
                 jointDelta += jointLimitCompensation;
             }
 
-            jointDelta /=(cycleTime*0.001);
+            jointDelta /= (cycleTime * 0.001);
 
             jointDelta = applyMaxJointVelocity(jointDelta, maxJointVelocity);
 
-//            Eigen::Vector3f currentTCPPosition = robotNodeSet->getTCP()->getGlobalPose().block(0,3,3,1);
-//            const Eigen::Matrix4f mat = robotNodeSet->getTCP()->getGlobalPose() * lastTCPPose.inverse();
-//            const Eigen::Matrix3f rot = currentPose.block(0,0,3,3) * lastPose->toEigen().block(0,0,3,3).inverse();
-//            Eigen::Vector3f rpy;
-//            VirtualRobot::MathTools::eigen4f2rpy(mat, rpy);
-//            ARMARX_DEBUG << deactivateSpam(2) << "Current TCP Position: \n" << currentTCPPosition;
-//            ARMARX_VERBOSE  << deactivateSpam(2)<< "ActualTCPVelocity: " << (rpy/(0.001*cycleTime));
+            //            Eigen::Vector3f currentTCPPosition = robotNodeSet->getTCP()->getGlobalPose().block(0,3,3,1);
+            //            const Eigen::Matrix4f mat = robotNodeSet->getTCP()->getGlobalPose() * lastTCPPose.inverse();
+            //            const Eigen::Matrix3f rot = currentPose.block(0,0,3,3) * lastPose->toEigen().block(0,0,3,3).inverse();
+            //            Eigen::Vector3f rpy;
+            //            VirtualRobot::MathTools::eigen4f2rpy(mat, rpy);
+            //            ARMARX_DEBUG << deactivateSpam(2) << "Current TCP Position: \n" << currentTCPPosition;
+            //            ARMARX_VERBOSE  << deactivateSpam(2)<< "ActualTCPVelocity: " << (rpy/(0.001*cycleTime));
             lastTCPPose = robotNodeSet->getTCP()->getGlobalPose();
 
             // build name value map
@@ -461,10 +530,14 @@ namespace armarx
             const std::vector< VirtualRobot::RobotNodePtr > nodes =  robotNodeSet->getAllRobotNodes();
             std::vector< VirtualRobot::RobotNodePtr >::const_iterator iter = nodes.begin();
             int i = 0;
+
             while (iter != nodes.end() && i < jointDelta.rows())
             {
-                if(targetVelocities.find((*iter)->getName()) != targetVelocities.end())
+                if (targetVelocities.find((*iter)->getName()) != targetVelocities.end())
+                {
                     ARMARX_WARNING << deactivateSpam(2) << (*iter)->getName() << " is set from two joint delta calculations - overwriting first value";
+                }
+
                 targetVelocities.insert(std::make_pair((*iter)->getName(), jointDelta(i)));
 
                 controlModes.insert(std::make_pair((*iter)->getName(), eVelocityControl));
@@ -480,29 +553,35 @@ namespace armarx
 
 
 
-    void TCPControlUnit::ContinuousAngles(const Eigen::AngleAxisf& oldAngle, Eigen::AngleAxisf& newAngle, double & offset)
+    void TCPControlUnit::ContinuousAngles(const Eigen::AngleAxisf& oldAngle, Eigen::AngleAxisf& newAngle, double& offset)
     {
-    //    if(oldAngle.axis().isApprox(newAngle.axis()*-1))
+        //    if(oldAngle.axis().isApprox(newAngle.axis()*-1))
         const Eigen::Vector3f& v1 = oldAngle.axis();
         const Eigen::Vector3f& v2 = newAngle.axis();
-        const Eigen::Vector3f& v2i = newAngle.axis()*-1;
+        const Eigen::Vector3f& v2i = newAngle.axis() * -1;
         double angle = acos(v1.dot(v2) / (v1.norm() * v2.norm()));
         double angleInv = acos(v1.dot(v2i) / (v1.norm() * v2i.norm()));
-//        std::cout << "angle1: " << angle << std::endl;
-//        std::cout << "angleInv: " << angleInv << std::endl;
+        //        std::cout << "angle1: " << angle << std::endl;
+        //        std::cout << "angleInv: " << angleInv << std::endl;
+
+        //        Eigen::AngleAxisd result;
+        if (angle > angleInv)
+        {
+            //            ARMARX_IMPORTANT_S << "inversion needed" << std::endl;
+            newAngle = Eigen::AngleAxisf(2.0 * M_PI - newAngle.angle(), newAngle.axis() * -1);
+        }
+
+        //        else newAngle = newAngle;
 
-//        Eigen::AngleAxisd result;
-        if(angle > angleInv)
+        if (fabs(newAngle.angle() + offset - oldAngle.angle()) > fabs(newAngle.angle() + offset - (oldAngle.angle() + M_PI * 2)))
+        {
+            offset -= M_PI * 2;
+        }
+        else if (fabs(newAngle.angle() + offset - oldAngle.angle()) > fabs((newAngle.angle() + M_PI * 2 + offset) - oldAngle.angle()))
         {
-//            ARMARX_IMPORTANT_S << "inversion needed" << std::endl;
-            newAngle = Eigen::AngleAxisf(2.0*M_PI - newAngle.angle(), newAngle.axis()*-1);
+            offset += M_PI * 2;
         }
-//        else newAngle = newAngle;
 
-        if(fabs(newAngle.angle()+offset - oldAngle.angle()) > fabs(newAngle.angle()+offset - (oldAngle.angle() + M_PI*2)) )
-            offset -= M_PI*2;
-        else if(fabs(newAngle.angle()+offset - oldAngle.angle()) > fabs((newAngle.angle()+M_PI*2+offset) - oldAngle.angle()) )
-            offset += M_PI*2;
         newAngle.angle() += offset;
     }
 
@@ -511,12 +590,13 @@ namespace armarx
     {
         std::vector< VirtualRobot::RobotNodePtr > nodes = robotNodeSet->getAllRobotNodes();
         Eigen::VectorXf actualJointValues(nodes.size());
-        if(desiredJointValues.rows() == 0)
+
+        if (desiredJointValues.rows() == 0)
         {
 
             desiredJointValues.resize(nodes.size());
 
-            for(unsigned int i=0; i < nodes.size(); i++)
+            for (unsigned int i = 0; i < nodes.size(); i++)
             {
                 VirtualRobot::RobotNodePtr node = nodes.at(i);
                 desiredJointValues(i) = (node->getJointLimitHigh() - node->getJointLimitLow()) * 0.5f + node->getJointLimitLow();
@@ -524,23 +604,26 @@ namespace armarx
 
 
         }
-//        ARMARX_IMPORTANT << deactivateSpam(true, 0.5) << "desiredJointValues: "  << desiredJointValues;
+
+        //        ARMARX_IMPORTANT << deactivateSpam(true, 0.5) << "desiredJointValues: "  << desiredJointValues;
         Eigen::VectorXf jointCompensationDeltas(desiredJointValues.rows());
-        for(unsigned int i = 0; i < desiredJointValues.rows(); i++)
+
+        for (unsigned int i = 0; i < desiredJointValues.rows(); i++)
         {
             VirtualRobot::RobotNodePtr node = nodes.at(i);
             actualJointValues(i) = node->getJointValue();
-            jointCompensationDeltas(i) = (node->getJointValue() -  desiredJointValues(i) ) / (node->getJointLimitHigh() - node->getJointLimitLow());
-            jointCompensationDeltas(i) = -pow(jointCompensationDeltas(i), 3)*pow(nodes.size()-i,2);
+            jointCompensationDeltas(i) = (node->getJointValue() -  desiredJointValues(i)) / (node->getJointLimitHigh() - node->getJointLimitLow());
+            jointCompensationDeltas(i) = -pow(jointCompensationDeltas(i), 3) * pow(nodes.size() - i, 2);
         }
-//        ARMARX_IMPORTANT << deactivateSpam(true, 0.5) << "actualJointValues: "  << actualJointValues;
 
-        return CalcNullspaceJointDeltas(jointCompensationDeltas,jacobian, jacobianInverse);
+        //        ARMARX_IMPORTANT << deactivateSpam(true, 0.5) << "actualJointValues: "  << actualJointValues;
+
+        return CalcNullspaceJointDeltas(jointCompensationDeltas, jacobian, jacobianInverse);
     }
 
     Eigen::VectorXf TCPControlUnit::CalcNullspaceJointDeltas(const Eigen::VectorXf& desiredJointDeltas, const Eigen::MatrixXf& jacobian, const Eigen::MatrixXf& jacobianInverse)
     {
-        Eigen::MatrixXf I(jacobianInverse.rows(),jacobian.cols());
+        Eigen::MatrixXf I(jacobianInverse.rows(), jacobian.cols());
         I.setIdentity();
 
         Eigen::MatrixXf nullspaceProjection = I - jacobianInverse * jacobian;
@@ -553,18 +636,21 @@ namespace armarx
     {
         double currentMaxJointVel = std::numeric_limits<double>::min();
         unsigned int rows = jointVelocity.rows();
-        for(unsigned int i=0; i < rows; i++)
+
+        for (unsigned int i = 0; i < rows; i++)
         {
             currentMaxJointVel = std::max(fabs(jointVelocity(i)), currentMaxJointVel);
         }
 
-        if(currentMaxJointVel > maxJointVelocity)
+        if (currentMaxJointVel > maxJointVelocity)
         {
             ARMARX_IMPORTANT << deactivateSpam(1) << "max joint velocity too high: " << currentMaxJointVel << " allowed: " << maxJointVelocity;
-            return jointVelocity * (maxJointVelocity/currentMaxJointVel);
+            return jointVelocity * (maxJointVelocity / currentMaxJointVel);
         }
         else
+        {
             return jointVelocity;
+        }
 
     }
 
@@ -584,27 +670,36 @@ namespace armarx
 
     Eigen::MatrixXf EDifferentialIK::calcFullJacobian()
     {
-        if (nRows==0) this->setNRows();
+        if (nRows == 0)
+        {
+            this->setNRows();
+        }
+
         size_t nDoF = nodes.size();
 
         using namespace Eigen;
-        MatrixXf Jacobian(nRows,nDoF);
+        MatrixXf Jacobian(nRows, nDoF);
+
+        size_t index = 0;
 
-        size_t index=0;
-        for (size_t i=0; i<tcp_set.size();i++)
+        for (size_t i = 0; i < tcp_set.size(); i++)
         {
             SceneObjectPtr tcp = tcp_set[i];
-            if (this->targets.find(tcp)!=this->targets.end())
+
+            if (this->targets.find(tcp) != this->targets.end())
             {
                 IKSolver::CartesianSelection mode = this->modes[tcp];
-                MatrixXf partJacobian = this->getJacobianMatrix(tcp,mode);
-                Jacobian.block(index,0,partJacobian.rows(),nDoF) = partJacobian;
+                MatrixXf partJacobian = this->getJacobianMatrix(tcp, mode);
+                Jacobian.block(index, 0, partJacobian.rows(), nDoF) = partJacobian;
             }
             else
-                VR_ERROR << "Internal error?!" << endl; // Error
+            {
+                VR_ERROR << "Internal error?!" << endl;    // Error
+            }
 
 
         }
+
         return Jacobian;
     }
 
@@ -623,14 +718,16 @@ namespace armarx
         this->coordSystem = coordSystem;
     }
 
-    void EDifferentialIK::setGoal(const Matrix4f &goal, RobotNodePtr tcp, IKSolver::CartesianSelection mode, float tolerancePosition, float toleranceRotation, VectorXf tcpWeight)
+    void EDifferentialIK::setGoal(const Matrix4f& goal, RobotNodePtr tcp, IKSolver::CartesianSelection mode, float tolerancePosition, float toleranceRotation, VectorXf tcpWeight)
     {
-        if(mode <=  IKSolver::Z)
+        if (mode <=  IKSolver::Z)
             ARMARX_CHECK_EXPRESSION_W_HINT(tcpWeight.rows() == 1, "The tcpWeight vector must be of size 1")
-        else if(mode <=  IKSolver::Orientation)
-            ARMARX_CHECK_EXPRESSION_W_HINT(tcpWeight.rows() == 3, "The tcpWeight vector must be of size 3")
-        else if(mode ==  IKSolver::All)
-            ARMARX_CHECK_EXPRESSION_W_HINT(tcpWeight.rows() == 6, "The tcpWeight vector must be of size 6");
+            else if (mode <=  IKSolver::Orientation)
+                ARMARX_CHECK_EXPRESSION_W_HINT(tcpWeight.rows() == 3, "The tcpWeight vector must be of size 3")
+                else if (mode ==  IKSolver::All)
+                {
+                    ARMARX_CHECK_EXPRESSION_W_HINT(tcpWeight.rows() == 6, "The tcpWeight vector must be of size 6");
+                }
 
         tcpWeights[tcp] = tcpWeight;
         DifferentialIK::setGoal(goal, tcp, mode, tolerancePosition, toleranceRotation);
@@ -647,19 +744,19 @@ namespace armarx
         return computeSteps(jointDelta, stepSize, mininumChange, maxNStep, &DifferentialIK::computeStep);
     }
 
-//    void EDifferentialIK::setTCPWeights(Eigen::VectorXf tcpWeights)
-//    {
-//        this->tcpWeights = tcpWeights;
-//    }
+    //    void EDifferentialIK::setTCPWeights(Eigen::VectorXf tcpWeights)
+    //    {
+    //        this->tcpWeights = tcpWeights;
+    //    }
 
-    bool EDifferentialIK::computeSteps(VectorXf &resultJointDelta, float stepSize, float mininumChange, int maxNStep, ComputeFunction computeFunction)
+    bool EDifferentialIK::computeSteps(VectorXf& resultJointDelta, float stepSize, float mininumChange, int maxNStep, ComputeFunction computeFunction)
     {
         VR_ASSERT(rns);
         VR_ASSERT(nodes.size() == rns->getSize());
         //std::vector<RobotNodePtr> rn = this->nodes;
         RobotPtr robot = rns->getRobot();
         VR_ASSERT(robot);
-        std::vector<float> jv(nodes.size(),0.0f);
+        std::vector<float> jv(nodes.size(), 0.0f);
         std::vector<float> jvBest = rns->getJointValues();
         int step = 0;
         checkTolerances();
@@ -669,76 +766,89 @@ namespace armarx
         VectorXf oldJointValues;
         rns->getJointValues(oldJointValues);
         VectorXf tempDOFWeights = dofWeights;
-//        VectorXf dThetaSum(nodes.size());
+        //        VectorXf dThetaSum(nodes.size());
         resultJointDelta.resize(nodes.size());
         resultJointDelta.setZero();
+
         do
         {
             VectorXf dTheta = (this->*computeFunction)(stepSize);
-            if(adjustDOFWeightsToJointLimits(dTheta))
+
+            if (adjustDOFWeightsToJointLimits(dTheta))
+            {
                 dTheta = computeStep(stepSize);
+            }
 
 
 
-            for (unsigned int i=0; i<nodes.size();i++)
+            for (unsigned int i = 0; i < nodes.size(); i++)
             {
                 ARMARX_DEBUG << VAROUT(nodes[i]->getJointValue()) << VAROUT(dTheta[i]);
                 jv[i] = (nodes[i]->getJointValue() + dTheta[i]);
+
                 if (boost::math::isnan(jv[i]) || boost::math::isinf(jv[i]))
                 {
                     ARMARX_WARNING_S << "Aborting, invalid joint value (nan)" << endl;
                     dofWeights = tempDOFWeights;
                     return false;
                 }
+
                 //nodes[i]->setJointValue(nodes[i]->getJointValue() + dTheta[i]);
             }
 
-            robot->setJointValues(rns,jv);
+            robot->setJointValues(rns, jv);
 
             VectorXf newJointValues;
             rns->getJointValues(newJointValues);
             resultJointDelta = newJointValues - oldJointValues;
 
 
-//            ARMARX_DEBUG << "joint angle deltas:\n" << dThetaSum;
+            //            ARMARX_DEBUG << "joint angle deltas:\n" << dThetaSum;
 
             // check tolerances
             if (checkTolerances())
             {
                 if (verbose)
+                {
                     ARMARX_INFO << deactivateSpam(1) << "Tolerances ok, loop:" << step << endl;
+                }
+
                 break;
             }
+
             float d = dTheta.norm();
             float posDist = getMeanErrorPosition();
             float oriErr = getErrorRotation(rns->getTCP());
-            if (dTheta.norm()<mininumChange)
+
+            if (dTheta.norm() < mininumChange)
             {
-//                if (verbose)
-                    ARMARX_INFO << deactivateSpam(1) << "Could not improve result any more (dTheta.norm()=" << d << "), loop:" << step << " Resulting error: pos " << posDist << " orientation: " << oriErr << endl;
+                //                if (verbose)
+                ARMARX_INFO << deactivateSpam(1) << "Could not improve result any more (dTheta.norm()=" << d << "), loop:" << step << " Resulting error: pos " << posDist << " orientation: " << oriErr << endl;
                 break;
             }
 
-            if (checkImprovement && posDist>lastDist)
+            if (checkImprovement && posDist > lastDist)
             {
-//                if (verbose)
-                    ARMARX_INFO << deactivateSpam(1) << "Could not improve result any more (current position error=" << posDist << ", last loop's error:" << lastDist << "), loop:" << step << endl;
-                robot->setJointValues(rns,jvBest);
+                //                if (verbose)
+                ARMARX_INFO << deactivateSpam(1) << "Could not improve result any more (current position error=" << posDist << ", last loop's error:" << lastDist << "), loop:" << step << endl;
+                robot->setJointValues(rns, jvBest);
                 break;
             }
+
             jvBest = jv;
             lastDist = posDist;
             step++;
 
             jointDeltaIterations.push_back(std::make_pair(getWeightedError(), resultJointDelta));
         }
-        while (step<maxNStep);
+        while (step < maxNStep);
 
 
         float bestJVError = std::numeric_limits<float>::max();
-        for(unsigned int i=0; i < jointDeltaIterations.size(); i++)
+
+        for (unsigned int i = 0; i < jointDeltaIterations.size(); i++)
         {
-            if(jointDeltaIterations.at(i).first < bestJVError)
+            if (jointDeltaIterations.at(i).first < bestJVError)
             {
                 bestJVError = jointDeltaIterations.at(i).first;
                 resultJointDelta = jointDeltaIterations.at(i).second;
@@ -747,15 +857,16 @@ namespace armarx
             }
         }
 
-        robot->setJointValues(rns,oldJointValues + resultJointDelta);
+        robot->setJointValues(rns, oldJointValues + resultJointDelta);
 
-//        ARMARX_DEBUG << "best try: " <<  bestIndex << " with error: " << bestJVError;
-//        rns->setJointValues(oldJointValues);
-//        Matrix4f oldPose = rns->getTCP()->getGlobalPose();
-//        rns->setJointValues(oldJointValues+dThetaSum);
-//        Matrix4f newPose = rns->getTCP()->getGlobalPose();
-//        ARMARX_IMPORTANT << "tcp delta:\n" << newPose.block(0,3,3,1) - oldPose.block(0,3,3,1);
+        //        ARMARX_DEBUG << "best try: " <<  bestIndex << " with error: " << bestJVError;
+        //        rns->setJointValues(oldJointValues);
+        //        Matrix4f oldPose = rns->getTCP()->getGlobalPose();
+        //        rns->setJointValues(oldJointValues+dThetaSum);
+        //        Matrix4f newPose = rns->getTCP()->getGlobalPose();
+        //        ARMARX_IMPORTANT << "tcp delta:\n" << newPose.block(0,3,3,1) - oldPose.block(0,3,3,1);
         dofWeights = tempDOFWeights;
+
         if (step >=  maxNStep && verbose)
         {
             ARMARX_INFO << deactivateSpam(1) << "IK failed, loop:" << step << endl;
@@ -767,58 +878,70 @@ namespace armarx
         return true;
     }
 
-    VectorXf EDifferentialIK::computeStep(float stepSize )
+    VectorXf EDifferentialIK::computeStep(float stepSize)
     {
 
-        if (nRows==0) this->setNRows();
+        if (nRows == 0)
+        {
+            this->setNRows();
+        }
+
         size_t nDoF = nodes.size();
 
-        MatrixXf Jacobian(nRows,nDoF);
+        MatrixXf Jacobian(nRows, nDoF);
         VectorXf error(nRows);
-        size_t index=0;
-        for (size_t i=0; i<tcp_set.size();i++)
+        size_t index = 0;
+
+        for (size_t i = 0; i < tcp_set.size(); i++)
         {
             SceneObjectPtr tcp = tcp_set[i];
-            if (this->targets.find(tcp)!=this->targets.end())
+
+            if (this->targets.find(tcp) != this->targets.end())
             {
                 Eigen::VectorXf delta = getDeltaToGoal(tcp);
                 //ARMARX_DEBUG << VAROUT(delta);
                 IKSolver::CartesianSelection mode = this->modes[tcp];
-                MatrixXf partJacobian = this->getJacobianMatrix(tcp,mode);
+                MatrixXf partJacobian = this->getJacobianMatrix(tcp, mode);
                 //ARMARX_DEBUG << VAROUT(partJacobian);
 
-                Jacobian.block(index,0,partJacobian.rows(),nDoF) = partJacobian;
+                Jacobian.block(index, 0, partJacobian.rows(), nDoF) = partJacobian;
                 Vector3f position = delta.head(3);
-                position *=stepSize;
+                position *= stepSize;
+
                 if (mode & IKSolver::X)
                 {
                     error(index) = position(0);
                     index++;
                 }
+
                 if (mode & IKSolver::Y)
                 {
                     error(index) = position(1);
                     index++;
                 }
+
                 if (mode & IKSolver::Z)
                 {
                     error(index) = position(2);
                     index++;
                 }
+
                 if (mode & IKSolver::Orientation)
                 {
-                    error.segment(index,3) = delta.tail(3)*stepSize;
-                    index+=3;
+                    error.segment(index, 3) = delta.tail(3) * stepSize;
+                    index += 3;
                 }
 
             }
             else
-                VR_ERROR << "Internal error?!" << endl; // Error
+            {
+                VR_ERROR << "Internal error?!" << endl;    // Error
+            }
 
 
         }
 
-//        applyDOFWeightsToJacobian(Jacobian);
+        //        applyDOFWeightsToJacobian(Jacobian);
         ARMARX_DEBUG << VAROUT(Jacobian);
         MatrixXf pseudo = computePseudoInverseJacobianMatrix(Jacobian);
         ARMARX_DEBUG << VAROUT(pseudo);
@@ -827,72 +950,91 @@ namespace armarx
     }
 
 
-    VectorXf EDifferentialIK::computeStepIndependently(float stepSize )
+    VectorXf EDifferentialIK::computeStepIndependently(float stepSize)
     {
-        if (nRows==0) this->setNRows();
+        if (nRows == 0)
+        {
+            this->setNRows();
+        }
+
         size_t nDoF = nodes.size();
 
         std::map<float,  MatrixXf> partJacobians;
 
         VectorXf thetaSum(nDoF);
         thetaSum.setZero();
-        size_t index=0;
-        for (size_t i=0; i<tcp_set.size();i++)
+        size_t index = 0;
+
+        for (size_t i = 0; i < tcp_set.size(); i++)
         {
             SceneObjectPtr tcp = tcp_set[i];
-            if (this->targets.find(tcp)!=this->targets.end())
+
+            if (this->targets.find(tcp) != this->targets.end())
             {
                 Eigen::VectorXf delta = getDeltaToGoal(tcp);
                 IKSolver::CartesianSelection mode = this->modes[tcp];
-                MatrixXf partJacobian = this->getJacobianMatrix(tcp,mode);
+                MatrixXf partJacobian = this->getJacobianMatrix(tcp, mode);
 
                 // apply tcp weights
-//                applyTCPWeights(tcp, partJacobian);
+                //                applyTCPWeights(tcp, partJacobian);
                 int tcpDOF = 0;
-                if(mode <=  IKSolver::Z)
+
+                if (mode <=  IKSolver::Z)
+                {
                     tcpDOF = 1;
-                else if(mode <=  IKSolver::Orientation)
+                }
+                else if (mode <=  IKSolver::Orientation)
+                {
                     tcpDOF = 3;
-                else if(mode ==  IKSolver::All)
+                }
+                else if (mode ==  IKSolver::All)
+                {
                     tcpDOF = 6;
+                }
+
                 index = 0;
                 VectorXf partError(tcpDOF);
                 Vector3f position = delta.head(3);
-//                ARMARX_DEBUG << tcp->getName() << "'s error: " << position << " weighted error: " << position*stepSize;
-                position *=stepSize;
+                //                ARMARX_DEBUG << tcp->getName() << "'s error: " << position << " weighted error: " << position*stepSize;
+                position *= stepSize;
+
                 if (mode & IKSolver::X)
                 {
                     partError(index) = position(0);
                     index++;
                 }
+
                 if (mode & IKSolver::Y)
                 {
                     partError(index) = position(1);
                     index++;
                 }
+
                 if (mode & IKSolver::Z)
                 {
                     partError(index) = position(2);
                     index++;
                 }
+
                 if (mode & IKSolver::Orientation)
                 {
-                    partError.segment(index,3) = delta.tail(3)*stepSize;
-                    index+=3;
+                    partError.segment(index, 3) = delta.tail(3) * stepSize;
+                    index += 3;
                 }
 
 
                 ARMARX_DEBUG <<  deactivateSpam(0.05) << "step size adjusted error to goal:\n" << partError;
 
                 applyDOFWeightsToJacobian(partJacobian);
-//                ARMARX_DEBUG <<  "Jac:\n" << partJacobian;
+                //                ARMARX_DEBUG <<  "Jac:\n" << partJacobian;
 
 
                 MatrixXf pseudo = computePseudoInverseJacobianMatrix(partJacobian);
 
                 Eigen::VectorXf tcpWeightVec;
                 std::map<VirtualRobot:: SceneObjectPtr, Eigen::VectorXf>::iterator it = tcpWeights.find(tcp);
-                if(it != tcpWeights.end())
+
+                if (it != tcpWeights.end())
                 {
                     tcpWeightVec = it->second;
                 }
@@ -900,40 +1042,51 @@ namespace armarx
                 {
                     IKSolver::CartesianSelection mode = modes[tcp_set.at(i)];
                     int size = 1;
-                    if(mode <=  IKSolver::Z)
+
+                    if (mode <=  IKSolver::Z)
+                    {
                         size = 1;
-                    else if(mode <=  IKSolver::Orientation)
+                    }
+                    else if (mode <=  IKSolver::Orientation)
+                    {
                         size = 3;
-                    else if(mode ==  IKSolver::All)
+                    }
+                    else if (mode ==  IKSolver::All)
+                    {
                         size = 6;
+                    }
 
                     Eigen::VectorXf tmptcpWeightVec(size);
                     tmptcpWeightVec.setOnes();
-                    tcpWeightVec= tmptcpWeightVec;
+                    tcpWeightVec = tmptcpWeightVec;
 
                 }
 
 
-                if(pseudo.cols() == tcpWeightVec.rows())
+                if (pseudo.cols() == tcpWeightVec.rows())
                 {
 
                     Eigen::MatrixXf weightMat(tcpWeightVec.rows(), tcpWeightVec.rows());
                     weightMat.setIdentity();
                     weightMat.diagonal() = tcpWeightVec;
-        //            ARMARX_DEBUG << /*deactivateSpam(1) <<*/ "tcpWeightVec:\n" << tcpWeightVec;
-        //            ARMARX_DEBUG << /*deactivateSpam(1) << */"InvJac Before:\n" << invJacobian;
+                    //            ARMARX_DEBUG << /*deactivateSpam(1) <<*/ "tcpWeightVec:\n" << tcpWeightVec;
+                    //            ARMARX_DEBUG << /*deactivateSpam(1) << */"InvJac Before:\n" << invJacobian;
                     pseudo =  pseudo * weightMat;
-//                    ARMARX_DEBUG << /*deactivateSpam(1) <<*/ "InvJac after:\n" << pseudo;
+                    //                    ARMARX_DEBUG << /*deactivateSpam(1) <<*/ "InvJac after:\n" << pseudo;
                 }
                 else
+                {
                     ARMARX_WARNING << deactivateSpam(3) << "Wrong dimension of tcp weights: " << tcpWeightVec.rows() << ", but should be: " << pseudo.cols();
+                }
 
 
                 thetaSum += pseudo * partError;
 
             }
             else
-                VR_ERROR << "Internal error?!" << endl; // Error
+            {
+                VR_ERROR << "Internal error?!" << endl;    // Error
+            }
 
 
         }
@@ -947,28 +1100,33 @@ namespace armarx
         rns->getJointValues(jointValuesBefore);
         Eigen::VectorXf resultJointDelta;
         Eigen::VectorXf jointDeltaAlternative;
-        bool result = computeSteps(resultJointDelta, stepSize,minChange, maxSteps);
+        bool result = computeSteps(resultJointDelta, stepSize, minChange, maxSteps);
         float error = getWeightedError();
-        if(useAlternativeOnFail && error > 5)
-            result = computeSteps(jointDeltaAlternative,stepSize,minChange, maxSteps, &EDifferentialIK::computeStepIndependently);
-        if(getWeightedError() < error)
+
+        if (useAlternativeOnFail && error > 5)
+        {
+            result = computeSteps(jointDeltaAlternative, stepSize, minChange, maxSteps, &EDifferentialIK::computeStepIndependently);
+        }
+
+        if (getWeightedError() < error)
         {
             resultJointDelta = jointDeltaAlternative;
         }
+
         return result;
     }
 
-    void EDifferentialIK::applyDOFWeightsToJacobian(MatrixXf &Jacobian)
+    void EDifferentialIK::applyDOFWeightsToJacobian(MatrixXf& Jacobian)
     {
-        if(dofWeights.rows() == Jacobian.cols())
+        if (dofWeights.rows() == Jacobian.cols())
         {
             Eigen::MatrixXf weightMat(dofWeights.rows(), dofWeights.rows());
             weightMat.setIdentity();
             weightMat.diagonal() = dofWeights;
-//            ARMARX_DEBUG << deactivateSpam(1) << "Jac before:\n" << Jacobian;
-//            ARMARX_DEBUG << deactivateSpam(1) << "Weights:\n" << weightMat;
+            //            ARMARX_DEBUG << deactivateSpam(1) << "Jac before:\n" << Jacobian;
+            //            ARMARX_DEBUG << deactivateSpam(1) << "Weights:\n" << weightMat;
             Jacobian = Jacobian * weightMat;
-//            ARMARX_DEBUG << deactivateSpam(1) << "Jac after:\n" << Jacobian;
+            //            ARMARX_DEBUG << deactivateSpam(1) << "Jac after:\n" << Jacobian;
 
         }
     }
@@ -977,10 +1135,12 @@ namespace armarx
     {
 
         std::map<VirtualRobot:: SceneObjectPtr, Eigen::VectorXf>::iterator it = tcpWeights.find(tcp);
-        if(it != tcpWeights.end())
+
+        if (it != tcpWeights.end())
         {
             Eigen::VectorXf& tcpWeightVec = it->second;
-            if(partJacobian.rows() == tcpWeightVec.rows())
+
+            if (partJacobian.rows() == tcpWeightVec.rows())
             {
 
                 Eigen::MatrixXf weightMat(tcpWeightVec.rows(), tcpWeightVec.rows());
@@ -991,39 +1151,58 @@ namespace armarx
                 ARMARX_DEBUG << deactivateSpam(1) << "Jac after: " << partJacobian;
             }
             else
+            {
                 ARMARX_WARNING << deactivateSpam(3) << "Wrong dimension of tcp weights: " << tcpWeightVec.rows() << ", but should be: " << partJacobian.rows();
+            }
         }
     }
 
     void EDifferentialIK::applyTCPWeights(MatrixXf& invJacobian)
     {
-        if(tcpWeightVec.rows() == 0)
-            for (size_t i=0; i<tcp_set.size();i++)
+        if (tcpWeightVec.rows() == 0)
+            for (size_t i = 0; i < tcp_set.size(); i++)
             {
                 std::map<VirtualRobot:: SceneObjectPtr, Eigen::VectorXf>::iterator it = tcpWeights.find(tcp_set.at(i));
-                if(it != tcpWeights.end())
+
+                if (it != tcpWeights.end())
                 {
                     Eigen::VectorXf& tmptcpWeightVec = it->second;
                     Eigen::VectorXf oldVec = tcpWeightVec;
-                    tcpWeightVec.resize(tcpWeightVec.rows()+tmptcpWeightVec.rows());
-                    if(oldVec.rows()>0)
+                    tcpWeightVec.resize(tcpWeightVec.rows() + tmptcpWeightVec.rows());
+
+                    if (oldVec.rows() > 0)
+                    {
                         tcpWeightVec.head(oldVec.rows()) = oldVec;
+                    }
+
                     tcpWeightVec.tail(tmptcpWeightVec.rows()) = tmptcpWeightVec;
                 }
                 else
                 {
                     IKSolver::CartesianSelection mode = modes[tcp_set.at(i)];
                     int size = 1;
-                    if(mode <=  IKSolver::Z)
+
+                    if (mode <=  IKSolver::Z)
+                    {
                         size = 1;
-                    else if(mode <=  IKSolver::Orientation)
+                    }
+                    else if (mode <=  IKSolver::Orientation)
+                    {
                         size = 3;
-                    else if(mode ==  IKSolver::All)
+                    }
+                    else if (mode ==  IKSolver::All)
+                    {
                         size = 6;
+                    }
+
                     Eigen::VectorXf oldVec = tcpWeightVec;
-                    tcpWeightVec.resize(tcpWeightVec.rows()+size);
-                    if(oldVec.rows()>0)
+                    tcpWeightVec.resize(tcpWeightVec.rows() + size);
+
+                    if (oldVec.rows() > 0)
+                    {
                         tcpWeightVec.head(oldVec.rows()) = oldVec;
+                    }
+
                     Eigen::VectorXf tmptcpWeightVec(size);
                     tmptcpWeightVec.setOnes();
                     tcpWeightVec.tail(size) = tmptcpWeightVec;
@@ -1031,72 +1210,91 @@ namespace armarx
                 }
             }
 
-        if(invJacobian.cols() == tcpWeightVec.rows())
+        if (invJacobian.cols() == tcpWeightVec.rows())
         {
 
             Eigen::MatrixXf weightMat(tcpWeightVec.rows(), tcpWeightVec.rows());
             weightMat.setIdentity();
             weightMat.diagonal() = tcpWeightVec;
-//            ARMARX_DEBUG << /*deactivateSpam(1) <<*/ "tcpWeightVec:\n" << tcpWeightVec;
-//            ARMARX_DEBUG << /*deactivateSpam(1) << */"InvJac Before:\n" << invJacobian;
+            //            ARMARX_DEBUG << /*deactivateSpam(1) <<*/ "tcpWeightVec:\n" << tcpWeightVec;
+            //            ARMARX_DEBUG << /*deactivateSpam(1) << */"InvJac Before:\n" << invJacobian;
             invJacobian =  invJacobian * weightMat;
             ARMARX_DEBUG << /*deactivateSpam(1) <<*/ "InvJac after:\n" << invJacobian;
         }
         else
+        {
             ARMARX_WARNING << deactivateSpam(3) << "Wrong dimension of tcp weights: " << tcpWeightVec.rows() << ", but should be: " << invJacobian.cols();
+        }
 
     }
 
     float EDifferentialIK::getWeightedError()
     {
         float result = 0.0f;
-        float positionOrientationRatio = 3.f/180.f*M_PI;
-        for (size_t i=0; i<tcp_set.size();i++){
+        float positionOrientationRatio = 3.f / 180.f * M_PI;
+
+        for (size_t i = 0; i < tcp_set.size(); i++)
+        {
             SceneObjectPtr tcp = tcp_set[i];
-            result += getWeightedErrorPosition(tcp) + getErrorRotation(tcp)*positionOrientationRatio;
+            result += getWeightedErrorPosition(tcp) + getErrorRotation(tcp) * positionOrientationRatio;
         }
+
         return result;
     }
 
     float EDifferentialIK::getWeightedErrorPosition(SceneObjectPtr tcp)
     {
         if (modes[tcp] == IKSolver::Orientation)
-            return 0.0f; // ignoring position
+        {
+            return 0.0f;    // ignoring position
+        }
 
         if (!tcp)
+        {
             tcp = getDefaultTCP();
-        Vector3f position = targets[tcp].block(0,3,3,1) - tcp->getGlobalPose().block(0,3,3,1);
+        }
+
+        Vector3f position = targets[tcp].block(0, 3, 3, 1) - tcp->getGlobalPose().block(0, 3, 3, 1);
         //cout << "Error Position <" << tcp->getName() << ">: " << position.norm() << endl;
         //cout << boost::format("Error Position < %1% >: %2%") % tcp->getName() % position.norm()  << std::endl;
         float result = 0.0f;
         Eigen::VectorXf tcpWeight(3);
-        if(tcpWeights.find(tcp) != tcpWeights.end())
+
+        if (tcpWeights.find(tcp) != tcpWeights.end())
+        {
             tcpWeight = tcpWeights.find(tcp)->second;
+        }
         else
+        {
             tcpWeight.setOnes();
+        }
+
         int weightIndex = 0;
+
         if (modes[tcp] & IKSolver::X)
         {
-//            ARMARX_DEBUG << "error x: " << position(0)*tcpWeight(weightIndex);
+            //            ARMARX_DEBUG << "error x: " << position(0)*tcpWeight(weightIndex);
             result += position(0) * position(0) * tcpWeight(weightIndex++);
         }
+
         if (modes[tcp] & IKSolver::Y)
         {
-//            ARMARX_DEBUG << "error y: " << position(1)*tcpWeight(weightIndex);
+            //            ARMARX_DEBUG << "error y: " << position(1)*tcpWeight(weightIndex);
             result += position(1) * position(1) * tcpWeight(weightIndex++);
         }
+
         if (modes[tcp] & IKSolver::Z)
         {
-//            ARMARX_DEBUG << "error z: " << position(2)*tcpWeight(weightIndex);
+            //            ARMARX_DEBUG << "error z: " << position(2)*tcpWeight(weightIndex);
             result += position(2) * position(2) * tcpWeight(weightIndex++);
         }
 
         return sqrtf(result);
     }
 
-    bool EDifferentialIK::adjustDOFWeightsToJointLimits(const VectorXf &plannedJointDeltas)
+    bool EDifferentialIK::adjustDOFWeightsToJointLimits(const VectorXf& plannedJointDeltas)
     {
-        if(dofWeights.rows() != plannedJointDeltas.rows())
+        if (dofWeights.rows() != plannedJointDeltas.rows())
         {
             dofWeights.resize(plannedJointDeltas.rows());
             dofWeights.setOnes();
@@ -1104,16 +1302,19 @@ namespace armarx
         }
 
         bool result = false;
-        for (unsigned int i=0; i<nodes.size();i++)
+
+        for (unsigned int i = 0; i < nodes.size(); i++)
         {
-            float angle = nodes[i]->getJointValue() + plannedJointDeltas[i]*0.1;
-            if(angle > nodes[i]->getJointLimitHi() || angle < nodes[i]->getJointLimitLo())
+            float angle = nodes[i]->getJointValue() + plannedJointDeltas[i] * 0.1;
+
+            if (angle > nodes[i]->getJointLimitHi() || angle < nodes[i]->getJointLimitLo())
             {
                 ARMARX_VERBOSE << deactivateSpam(3) << nodes[i]->getName() << " joint deactivated because of joint limit";
                 dofWeights(i) = 0;
                 result = true;
             }
         }
+
         return result;
 
     }
@@ -1124,104 +1325,120 @@ namespace armarx
 
 
 
-void armarx::TCPControlUnit::reportControlModeChanged(const NameControlModeMap &, bool, const Ice::Current &)
+void armarx::TCPControlUnit::reportControlModeChanged(const NameControlModeMap&, bool, const Ice::Current&)
 {
 }
 
-void armarx::TCPControlUnit::reportJointAngles(const NameValueMap &jointAngles, bool, const Ice::Current &)
+void armarx::TCPControlUnit::reportJointAngles(const NameValueMap& jointAngles, bool, const Ice::Current&)
 {
     ScopedLock lock(reportMutex);
     FramedPoseBaseMap tcpPoses;
     std::string rootFrame =  localReportRobot->getRootNode()->getName();
     localReportRobot->setJointValues(jointAngles);
+
     //IceUtil::Time start = IceUtil::Time::now();
-    for(unsigned int i=0; i < nodesToReport.size(); i++)
+    for (unsigned int i = 0; i < nodesToReport.size(); i++)
     {
         RobotNodePtr& node = nodesToReport.at(i);
-        const std::string &tcpName  = node->getName();
-        const Eigen::Matrix4f &currentPose = node->getPoseInRootFrame();
+        const std::string& tcpName  = node->getName();
+        const Eigen::Matrix4f& currentPose = node->getPoseInRootFrame();
         tcpPoses[tcpName] = new FramedPose(currentPose, rootFrame, localReportRobot->getName());
 
     }
-//    ARMARX_DEBUG << deactivateSpam(5) << "TCP Pose Calc took: " << ( IceUtil::Time::now() - start).toMilliSecondsDouble();
+
+    //    ARMARX_DEBUG << deactivateSpam(5) << "TCP Pose Calc took: " << ( IceUtil::Time::now() - start).toMilliSecondsDouble();
     listener->reportTCPPose(tcpPoses);
 }
 
-void armarx::TCPControlUnit::reportJointVelocities(const NameValueMap &jointVel, bool, const Ice::Current &)
+void armarx::TCPControlUnit::reportJointVelocities(const NameValueMap& jointVel, bool, const Ice::Current&)
 {
-    if((IceUtil::Time::now()-lastTopicReportTime).toMilliSeconds() < cycleTime )
+    if ((IceUtil::Time::now() - lastTopicReportTime).toMilliSeconds() < cycleTime)
+    {
         return;
+    }
+
     lastTopicReportTime = IceUtil::Time::now();
     ScopedLock lock(reportMutex);
-    if(!localVelReportRobot)
+
+    if (!localVelReportRobot)
+    {
         localVelReportRobot = localReportRobot->clone(localReportRobot->getName());
-//    ARMARX_DEBUG << jointVel;    FramedPoseBaseMap tcpPoses;
+    }
+
+    //    ARMARX_DEBUG << jointVel;    FramedPoseBaseMap tcpPoses;
     FramedDirectionMap tcpTranslationVelocities;
     FramedDirectionMap tcpOrientationVelocities;
     std::string rootFrame =  localReportRobot->getRootNode()->getName();
     NameValueMap tempJointAngles = localReportRobot->getConfig()->getRobotNodeJointValueMap();
     FramedPoseBaseMap tcpPoses;
-    for(unsigned int i=0; i < nodesToReport.size(); i++)
+
+    for (unsigned int i = 0; i < nodesToReport.size(); i++)
     {
         RobotNodePtr node = nodesToReport.at(i);
-        const std::string &tcpName  = node->getName();
-        const Eigen::Matrix4f &currentPose = node->getPoseInRootFrame();
+        const std::string& tcpName  = node->getName();
+        const Eigen::Matrix4f& currentPose = node->getPoseInRootFrame();
         tcpPoses[tcpName] = new FramedPose(currentPose, rootFrame, localReportRobot->getName());
 
     }
 
     double tDelta = 0.001;
-    for(NameValueMap::iterator it = tempJointAngles.begin(); it != tempJointAngles.end(); it++)
+
+    for (NameValueMap::iterator it = tempJointAngles.begin(); it != tempJointAngles.end(); it++)
     {
         NameValueMap::const_iterator itSrc = jointVel.find(it->first);
-        if(itSrc != jointVel.end())
+
+        if (itSrc != jointVel.end())
+        {
             it->second += itSrc->second * tDelta;
+        }
     }
 
     localVelReportRobot->setJointValues(tempJointAngles);
+
     //IceUtil::Time start = IceUtil::Time::now();
-    for(unsigned int i=0; i < nodesToReport.size(); i++)
+    for (unsigned int i = 0; i < nodesToReport.size(); i++)
     {
         RobotNodePtr node = localVelReportRobot->getRobotNode(nodesToReport.at(i)->getName());
-        const std::string &tcpName  = node->getName();
-        const Eigen::Matrix4f &currentPose = node->getPoseInRootFrame();
+        const std::string& tcpName  = node->getName();
+        const Eigen::Matrix4f& currentPose = node->getPoseInRootFrame();
 
 
         FramedPosePtr lastPose = FramedPosePtr::dynamicCast(tcpPoses[tcpName]);
 
-        tcpTranslationVelocities[tcpName] = new FramedDirection((currentPose.block(0,3,3,1) - lastPose->toEigen().block(0,3,3,1))/tDelta, rootFrame, localReportRobot->getName());
+        tcpTranslationVelocities[tcpName] = new FramedDirection((currentPose.block(0, 3, 3, 1) - lastPose->toEigen().block(0, 3, 3, 1)) / tDelta, rootFrame, localReportRobot->getName());
 
         const Eigen::Matrix4f mat = currentPose * lastPose->toEigen().inverse();
-//        const Eigen::Matrix3f rot = currentPose.block(0,0,3,3) * lastPose->toEigen().block(0,0,3,3).inverse();
+        //        const Eigen::Matrix3f rot = currentPose.block(0,0,3,3) * lastPose->toEigen().block(0,0,3,3).inverse();
         Eigen::Vector3f rpy;
         VirtualRobot::MathTools::eigen4f2rpy(mat, rpy);
-//        Eigen::AngleAxisf orient(rot.block<3,3>(0,0));
+        //        Eigen::AngleAxisf orient(rot.block<3,3>(0,0));
 
-        tcpOrientationVelocities[tcpName] = new FramedDirection(rpy/tDelta, rootFrame, localReportRobot->getName());
+        tcpOrientationVelocities[tcpName] = new FramedDirection(rpy / tDelta, rootFrame, localReportRobot->getName());
 
 
     }
-//    ARMARX_DEBUG << deactivateSpam(5) << "TCP Pose Vel Calc took: " << ( IceUtil::Time::now() - start).toMilliSecondsDouble();
+
+    //    ARMARX_DEBUG << deactivateSpam(5) << "TCP Pose Vel Calc took: " << ( IceUtil::Time::now() - start).toMilliSecondsDouble();
     listener->reportTCPVelocities(tcpTranslationVelocities, tcpOrientationVelocities);
 }
 
-void armarx::TCPControlUnit::reportJointTorques(const NameValueMap &, bool, const Ice::Current &)
+void armarx::TCPControlUnit::reportJointTorques(const NameValueMap&, bool, const Ice::Current&)
 {
 }
 
-void armarx::TCPControlUnit::reportJointAccelerations(const armarx::NameValueMap &jointAccelerations, bool aValueChanged, const Ice::Current &c)
+void armarx::TCPControlUnit::reportJointAccelerations(const armarx::NameValueMap& jointAccelerations, bool aValueChanged, const Ice::Current& c)
 {
 
 }
 
-void armarx::TCPControlUnit::reportJointCurrents(const NameValueMap &, bool, const Ice::Current &)
+void armarx::TCPControlUnit::reportJointCurrents(const NameValueMap&, bool, const Ice::Current&)
 {
 }
 
-void armarx::TCPControlUnit::reportJointMotorTemperatures(const NameValueMap &, bool, const Ice::Current &)
+void armarx::TCPControlUnit::reportJointMotorTemperatures(const NameValueMap&, bool, const Ice::Current&)
 {
 }
 
-void armarx::TCPControlUnit::reportJointStatuses(const NameStatusMap &, bool, const Ice::Current &)
+void armarx::TCPControlUnit::reportJointStatuses(const NameStatusMap&, bool, const Ice::Current&)
 {
 }
diff --git a/source/RobotAPI/components/units/TCPControlUnit.h b/source/RobotAPI/components/units/TCPControlUnit.h
index 24ce0d04a82ee3cf2de97e8d71950c23c0bc92f3..31ddf540cc143fb5ad18dd90d268ccbf242481af 100644
--- a/source/RobotAPI/components/units/TCPControlUnit.h
+++ b/source/RobotAPI/components/units/TCPControlUnit.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::
 * @author     Mirko Waechter (mirko.waechter at kit dot edu)
 * @date       2013
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -26,12 +25,12 @@
 
 #include <RobotAPI/interface/units/TCPControlUnit.h>
 #include <RobotAPI/libraries/core/FramedPose.h>
-#include <Core/core/services/tasks/PeriodicTask.h>
-#include <Core/core/Component.h>
+#include <ArmarXCore/core/services/tasks/PeriodicTask.h>
+#include <ArmarXCore/core/Component.h>
 
 #include <VirtualRobot/IK/DifferentialIK.h>
 #include <RobotAPI/libraries/core/remoterobot/RemoteRobot.h>
-#include <Core/interface/observers/ObserverInterface.h>
+#include <ArmarXCore/interface/observers/ObserverInterface.h>
 
 namespace armarx
 {
@@ -40,14 +39,15 @@ namespace armarx
      * \brief
      */
     class TCPControlUnitPropertyDefinitions:
-            public ComponentPropertyDefinitions
+        public ComponentPropertyDefinitions
     {
     public:
         TCPControlUnitPropertyDefinitions(std::string prefix):
             ComponentPropertyDefinitions(prefix)
         {
-            defineRequiredProperty<std::string>("KinematicUnitName","Name of the KinematicUnit Proxy");
-            defineOptionalProperty<float>("MaxJointVelocity",30.f/180*3.141, "Maximal joint velocity in rad/sec");
+            defineRequiredProperty<std::string>("KinematicUnitName", "Name of the KinematicUnit Proxy");
+            defineOptionalProperty<std::string>("RobotStateTopicName", "RobotState", "Name of the RobotComponent State topic.");
+            defineOptionalProperty<float>("MaxJointVelocity", 30.f / 180 * 3.141, "Maximal joint velocity in rad/sec");
             defineRequiredProperty<std::string>("RobotFileName", "Robot file name, e.g. robot_model.xml");
             defineOptionalProperty<int>("CycleTime", 30, "Cycle time of the tcp control in ms");
             defineOptionalProperty<float>("MaximumCommandDelay", 20000, "Delay after which the TCP Control unit releases itself if no new velocity have been set.");
@@ -58,7 +58,7 @@ namespace armarx
     };
 
     /**
-     * \class TCPControlUnit
+     * \defgroup Component-TCPControlUnit TCPControlUnit
      * \ingroup RobotAPI-SensorActorUnits
      * \brief Unit for controlling a tool center point (TCP).
      *
@@ -75,9 +75,14 @@ namespace armarx
      *
      * \note After usage release() **must** be called to stop the recalcuation and setting of joint velocities.
      */
+
+    /**
+     * @ingroup Component-TCPControlUnit
+     * @brief The TCPControlUnit class
+     */
     class TCPControlUnit :
-            virtual public Component,
-            virtual public TCPControlUnitInterface
+        virtual public Component,
+        virtual public TCPControlUnitInterface
     {
     public:
         TCPControlUnit();
@@ -89,7 +94,7 @@ namespace armarx
          * \param milliseconds New cycle time.
          * \param c Ice Context, leave blank.
          */
-        void setCycleTime(Ice::Int milliseconds, const Ice::Current &c = Ice::Current());
+        void setCycleTime(Ice::Int milliseconds, const Ice::Current& c = Ice::Current());
 
         /**
          * \brief Sets the cartesian velocity of a node in a nodeset for translation and/or orientation.
@@ -106,32 +111,32 @@ namespace armarx
          *
          * \see request(), release()
          */
-        void setTCPVelocity(const std::string &nodeSetName, const std::string &tcpName, const::armarx::FramedDirectionBasePtr &translationVelocity, const::armarx::FramedDirectionBasePtr &orientationVelocityRPY, const Ice::Current &c = Ice::Current());
+        void setTCPVelocity(const std::string& nodeSetName, const std::string& tcpName, const::armarx::FramedDirectionBasePtr& translationVelocity, const::armarx::FramedDirectionBasePtr& orientationVelocityRPY, const Ice::Current& c = Ice::Current());
 
         // UnitExecutionManagementInterface interface
         /**
          * \brief Does not do anything at the moment.
          * \param c
          */
-        void init(const Ice::Current &c = Ice::Current());
+        void init(const Ice::Current& c = Ice::Current());
         /**
          * \brief Does not do anything at the moment.
          * \param c
          */
-        void start(const Ice::Current &c = Ice::Current());
+        void start(const Ice::Current& c = Ice::Current());
         /**
          * \brief Does not do anything at the moment.
          * \param c
          */
-        void stop(const Ice::Current &c = Ice::Current());
-        UnitExecutionState getExecutionState(const Ice::Current &c = Ice::Current());
+        void stop(const Ice::Current& c = Ice::Current());
+        UnitExecutionState getExecutionState(const Ice::Current& c = Ice::Current());
 
         // UnitResourceManagementInterface interface
         /**
          * \brief Triggers the calculation loop for using cartesian velocity. Call once before/after setting a tcp velocity with SetTCPVelocity.
          * \param c Ice Context, leave blank.
          */
-        void request(const Ice::Current &c = Ice::Current());
+        void request(const Ice::Current& c = Ice::Current());
 
         /**
          * \brief Releases and stops the recalculation and updating of joint velocities.
@@ -139,7 +144,7 @@ namespace armarx
          * all node set will be deleted in this function.
          * \param c Ice Context, leave blank.
          */
-        void release(const Ice::Current &c = Ice::Current());
+        void release(const Ice::Current& c = Ice::Current());
 
     protected:
 
@@ -147,20 +152,23 @@ namespace armarx
         void onConnectComponent();
         void onDisconnectComponent();
         void onExitComponent();
-        std::string getDefaultName() const{return "TCPControlUnit";}
+        std::string getDefaultName() const
+        {
+            return "TCPControlUnit";
+        }
 
         // PropertyUser interface
         PropertyDefinitionsPtr createPropertyDefinitions();
 
-        static Eigen::VectorXf CalcNullspaceJointDeltas(const Eigen::VectorXf &desiredJointDeltas, const Eigen::MatrixXf &jacobian, const Eigen::MatrixXf &jacobianInverse);
-        static Eigen::VectorXf CalcJointLimitAvoidanceDeltas(VirtualRobot::RobotNodeSetPtr robotNodeSet, const Eigen::MatrixXf &jacobian, const Eigen::MatrixXf &jacobianInverse, Eigen::VectorXf desiredJointValues = Eigen::VectorXf());
+        static Eigen::VectorXf CalcNullspaceJointDeltas(const Eigen::VectorXf& desiredJointDeltas, const Eigen::MatrixXf& jacobian, const Eigen::MatrixXf& jacobianInverse);
+        static Eigen::VectorXf CalcJointLimitAvoidanceDeltas(VirtualRobot::RobotNodeSetPtr robotNodeSet, const Eigen::MatrixXf& jacobian, const Eigen::MatrixXf& jacobianInverse, Eigen::VectorXf desiredJointValues = Eigen::VectorXf());
         void calcAndSetVelocities();
     private:
-        static void ContinuousAngles(const Eigen::AngleAxisf &oldAngle, Eigen::AngleAxisf &newAngle, double & offset);
+        static void ContinuousAngles(const Eigen::AngleAxisf& oldAngle, Eigen::AngleAxisf& newAngle, double& offset);
         void periodicExec();
         void periodicReport();
         Eigen::VectorXf calcJointVelocities(VirtualRobot::RobotNodeSetPtr robotNodeSet, Eigen::VectorXf tcpDelta, VirtualRobot::RobotNodePtr refFrame, VirtualRobot::IKSolver::CartesianSelection mode);
-        Eigen::VectorXf applyMaxJointVelocity(const Eigen::VectorXf &jointVelocity, float maxJointVelocity);
+        Eigen::VectorXf applyMaxJointVelocity(const Eigen::VectorXf& jointVelocity, float maxJointVelocity);
 
         float maxJointVelocity;
         int cycleTime;
@@ -216,48 +224,54 @@ namespace armarx
 
         // KinematicUnitListener interface
     protected:
-        void reportControlModeChanged(const NameControlModeMap &, bool, const Ice::Current &);
-        void reportJointAngles(const NameValueMap &jointAngles, bool, const Ice::Current &);
-        void reportJointVelocities(const NameValueMap &jointVel, bool, const Ice::Current &);
-        void reportJointTorques(const NameValueMap &, bool, const Ice::Current &);
+        void reportControlModeChanged(const NameControlModeMap&, bool, const Ice::Current&);
+        void reportJointAngles(const NameValueMap& jointAngles, bool, const Ice::Current&);
+        void reportJointVelocities(const NameValueMap& jointVel, bool, const Ice::Current&);
+        void reportJointTorques(const NameValueMap&, bool, const Ice::Current&);
         void reportJointAccelerations(const NameValueMap& jointAccelerations, bool aValueChanged, const Ice::Current& c);
-        void reportJointCurrents(const NameValueMap &, bool, const Ice::Current &);
-        void reportJointMotorTemperatures(const NameValueMap &, bool, const Ice::Current &);
-        void reportJointStatuses(const NameStatusMap &, bool, const Ice::Current &);
+        void reportJointCurrents(const NameValueMap&, bool, const Ice::Current&);
+        void reportJointMotorTemperatures(const NameValueMap&, bool, const Ice::Current&);
+        void reportJointStatuses(const NameStatusMap&, bool, const Ice::Current&);
 
     };
 
     class EDifferentialIK : public VirtualRobot::DifferentialIK, virtual public Logging
     {
     public:
-        typedef Eigen::VectorXf (EDifferentialIK::*ComputeFunction)(float);
+        typedef Eigen::VectorXf(EDifferentialIK::*ComputeFunction)(float);
 
-        EDifferentialIK(VirtualRobot::RobotNodeSetPtr rns,VirtualRobot:: RobotNodePtr coordSystem = VirtualRobot::RobotNodePtr(), VirtualRobot::JacobiProvider::InverseJacobiMethod invJacMethod = eSVD);
+        EDifferentialIK(VirtualRobot::RobotNodeSetPtr rns, VirtualRobot:: RobotNodePtr coordSystem = VirtualRobot::RobotNodePtr(), VirtualRobot::JacobiProvider::InverseJacobiMethod invJacMethod = eSVD);
 
-        VirtualRobot::RobotNodePtr getRefFrame(){return coordSystem;}
-        int getJacobianRows(){ return nRows;}
+        VirtualRobot::RobotNodePtr getRefFrame()
+        {
+            return coordSystem;
+        }
+        int getJacobianRows()
+        {
+            return nRows;
+        }
 
         Eigen::MatrixXf calcFullJacobian();
 
         void clearGoals();
         void setRefFrame(VirtualRobot::RobotNodePtr coordSystem);
 
-        void setGoal(const Eigen::Matrix4f &goal, VirtualRobot::RobotNodePtr tcp, VirtualRobot::IKSolver::CartesianSelection mode, float tolerancePosition, float toleranceRotation, Eigen::VectorXf tcpWeight);
+        void setGoal(const Eigen::Matrix4f& goal, VirtualRobot::RobotNodePtr tcp, VirtualRobot::IKSolver::CartesianSelection mode, float tolerancePosition, float toleranceRotation, Eigen::VectorXf tcpWeight);
 
         void setDOFWeights(Eigen::VectorXf dofWeights);
-//        void setTCPWeights(Eigen::VectorXf tcpWeights);
+        //        void setTCPWeights(Eigen::VectorXf tcpWeights);
         bool computeSteps(float stepSize = 1.f, float mininumChange = 0.01f, int maxNStep = 50);
         bool computeSteps(Eigen::VectorXf& resultJointDelta, float stepSize = 1.f, float mininumChange = 0.01f, int maxNStep = 50, ComputeFunction computeFunction = &DifferentialIK::computeStep);
         Eigen::VectorXf computeStep(float stepSize);
-        void applyDOFWeightsToJacobian(Eigen::MatrixXf &Jacobian);
-        void applyTCPWeights(VirtualRobot::RobotNodePtr tcp, Eigen::MatrixXf &partJacobian);
-        void applyTCPWeights(Eigen::MatrixXf &invJacobian);
+        void applyDOFWeightsToJacobian(Eigen::MatrixXf& Jacobian);
+        void applyTCPWeights(VirtualRobot::RobotNodePtr tcp, Eigen::MatrixXf& partJacobian);
+        void applyTCPWeights(Eigen::MatrixXf& invJacobian);
         float getWeightedError();
         float getWeightedErrorPosition(VirtualRobot::SceneObjectPtr tcp);
         Eigen::VectorXf computeStepIndependently(float stepSize);
         bool solveIK(float stepSize = 1, float minChange = 0.01f, int maxSteps = 50, bool useAlternativeOnFail = false);
     protected:
-        bool adjustDOFWeightsToJointLimits(const Eigen::VectorXf &plannedJointDeltas);
+        bool adjustDOFWeightsToJointLimits(const Eigen::VectorXf& plannedJointDeltas);
 
         Eigen::VectorXf dofWeights;
         std::map<VirtualRobot:: SceneObjectPtr, Eigen::VectorXf> tcpWeights;
diff --git a/source/RobotAPI/components/units/TCPControlUnitObserver.cpp b/source/RobotAPI/components/units/TCPControlUnitObserver.cpp
index 9a9465a9af879902ab94e1f02fcc0f01fce3652d..2c34c81588359653d6c2592568a0c822a8f7a1b1 100644
--- a/source/RobotAPI/components/units/TCPControlUnitObserver.cpp
+++ b/source/RobotAPI/components/units/TCPControlUnitObserver.cpp
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,26 +16,27 @@
 * @package    ArmarX::
 * @author     Mirko Waechter ( mirko.waechter at kit dot edu)
 * @date       2013
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
 #include "TCPControlUnitObserver.h"
 
-//#include <Core/core/checks/ConditionCheckEqualsPoseWithTolerance.h>
-#include <Core/observers/checks/ConditionCheckUpdated.h>
-#include <Core/observers/checks/ConditionCheckEquals.h>
-#include <Core/observers/checks/ConditionCheckInRange.h>
-#include <Core/observers/checks/ConditionCheckLarger.h>
-#include <Core/observers/checks/ConditionCheckSmaller.h>
+//#include <ArmarXCore/core/checks/ConditionCheckEqualsPoseWithTolerance.h>
+#include <ArmarXCore/observers/checks/ConditionCheckUpdated.h>
+#include <ArmarXCore/observers/checks/ConditionCheckEquals.h>
+#include <ArmarXCore/observers/checks/ConditionCheckInRange.h>
+#include <ArmarXCore/observers/checks/ConditionCheckLarger.h>
+#include <ArmarXCore/observers/checks/ConditionCheckSmaller.h>
 #include <RobotAPI/libraries/core/checks/ConditionCheckEqualsPoseWithTolerance.h>
 #include <RobotAPI/libraries/core/checks/ConditionCheckMagnitudeChecks.h>
-#include <Core/core/exceptions/local/ExpressionException.h>
+#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 
 #define TCP_POSE_CHANNEL "TCPPose"
 #define TCP_TRANS_VELOCITIES_CHANNEL "TCPVelocities"
 
-namespace armarx {
+namespace armarx
+{
 
     TCPControlUnitObserver::TCPControlUnitObserver()
     {
@@ -51,7 +51,7 @@ namespace armarx {
         offerConditionCheck("larger", new ConditionCheckLarger());
         offerConditionCheck("equals", new ConditionCheckEquals());
         offerConditionCheck("smaller", new ConditionCheckSmaller());
-    //    offerConditionCheck("magnitudeinrange", new ConditionCheckInRange());
+        //    offerConditionCheck("magnitudeinrange", new ConditionCheckInRange());
         offerConditionCheck("magnitudelarger", new ConditionCheckMagnitudeLarger());
         offerConditionCheck("approx", new ConditionCheckApproxPose());
 
@@ -69,95 +69,116 @@ namespace armarx {
     PropertyDefinitionsPtr TCPControlUnitObserver::createPropertyDefinitions()
     {
         return PropertyDefinitionsPtr(new TCPControlUnitObserverPropertyDefinitions(
-                                               getConfigIdentifier()));
+                                          getConfigIdentifier()));
     }
 
-    void TCPControlUnitObserver::reportTCPPose(const FramedPoseBaseMap &poseMap, const Ice::Current &)
+    void TCPControlUnitObserver::reportTCPPose(const FramedPoseBaseMap& poseMap, const Ice::Current&)
     {
         ScopedLock lock(dataMutex);
-//        ARMARX_INFO << deactivateSpam() << "new tcp poses reported";
+        //        ARMARX_INFO << deactivateSpam() << "new tcp poses reported";
         FramedPoseBaseMap::const_iterator it = poseMap.begin();
-        for(; it != poseMap.end(); it++)
+
+        for (; it != poseMap.end(); it++)
         {
 
             FramedPosePtr vec = FramedPosePtr::dynamicCast(it->second);
-            const std::string &tcpName = it->first;
-            if(!existsDataField(TCP_POSE_CHANNEL, tcpName))
+            const std::string& tcpName = it->first;
+
+            if (!existsDataField(TCP_POSE_CHANNEL, tcpName))
+            {
                 offerDataFieldWithDefault(TCP_POSE_CHANNEL, tcpName, Variant(it->second), "Pose of " + tcpName);
+            }
             else
+            {
                 setDataField(TCP_POSE_CHANNEL, tcpName, Variant(it->second));
+            }
+
             updateChannel(TCP_POSE_CHANNEL);
-            if(!existsChannel(tcpName))
+
+            if (!existsChannel(tcpName))
             {
                 offerChannel(tcpName, "pose components of " + tcpName);
-                offerDataFieldWithDefault(tcpName,"x", Variant(vec->position->x), "X axis");
-                offerDataFieldWithDefault(tcpName,"y", Variant(vec->position->y), "Y axis");
-                offerDataFieldWithDefault(tcpName,"z", Variant(vec->position->z), "Z axis");
-                offerDataFieldWithDefault(tcpName,"qx", Variant(vec->orientation->qx), "Quaternion part x");
-                offerDataFieldWithDefault(tcpName,"qy", Variant(vec->orientation->qy), "Quaternion part y");
-                offerDataFieldWithDefault(tcpName,"qz", Variant(vec->orientation->qz), "Quaternion part z");
-                offerDataFieldWithDefault(tcpName,"qw", Variant(vec->orientation->qw), "Quaternion part w");
-                offerDataFieldWithDefault(tcpName,"frame", Variant(vec->frame), "Reference Frame");
+                offerDataFieldWithDefault(tcpName, "x", Variant(vec->position->x), "X axis");
+                offerDataFieldWithDefault(tcpName, "y", Variant(vec->position->y), "Y axis");
+                offerDataFieldWithDefault(tcpName, "z", Variant(vec->position->z), "Z axis");
+                offerDataFieldWithDefault(tcpName, "qx", Variant(vec->orientation->qx), "Quaternion part x");
+                offerDataFieldWithDefault(tcpName, "qy", Variant(vec->orientation->qy), "Quaternion part y");
+                offerDataFieldWithDefault(tcpName, "qz", Variant(vec->orientation->qz), "Quaternion part z");
+                offerDataFieldWithDefault(tcpName, "qw", Variant(vec->orientation->qw), "Quaternion part w");
+                offerDataFieldWithDefault(tcpName, "frame", Variant(vec->frame), "Reference Frame");
             }
             else
             {
-                setDataField(tcpName,"x", Variant(vec->position->x));
-                setDataField(tcpName,"y", Variant(vec->position->y));
-                setDataField(tcpName,"z", Variant(vec->position->z));
-                setDataField(tcpName,"qx", Variant(vec->orientation->qx));
-                setDataField(tcpName,"qy", Variant(vec->orientation->qy));
-                setDataField(tcpName,"qz", Variant(vec->orientation->qz));
-                setDataField(tcpName,"qw", Variant(vec->orientation->qw));
-                setDataField(tcpName,"frame", Variant(vec->frame));
+                setDataField(tcpName, "x", Variant(vec->position->x));
+                setDataField(tcpName, "y", Variant(vec->position->y));
+                setDataField(tcpName, "z", Variant(vec->position->z));
+                setDataField(tcpName, "qx", Variant(vec->orientation->qx));
+                setDataField(tcpName, "qy", Variant(vec->orientation->qy));
+                setDataField(tcpName, "qz", Variant(vec->orientation->qz));
+                setDataField(tcpName, "qw", Variant(vec->orientation->qw));
+                setDataField(tcpName, "frame", Variant(vec->frame));
             }
+
             updateChannel(tcpName);
 
         }
     }
 
-    void TCPControlUnitObserver::reportTCPVelocities(const FramedDirectionMap &tcpTranslationVelocities, const FramedDirectionMap &tcpOrientationVelocities, const Ice::Current &)
+    void TCPControlUnitObserver::reportTCPVelocities(const FramedDirectionMap& tcpTranslationVelocities, const FramedDirectionMap& tcpOrientationVelocities, const Ice::Current&)
     {
         ScopedLock lock(dataMutex);
         FramedDirectionMap::const_iterator it = tcpTranslationVelocities.begin();
-        for(; it != tcpTranslationVelocities.end(); it++)
+
+        for (; it != tcpTranslationVelocities.end(); it++)
         {
 
             FramedDirectionPtr vec = FramedDirectionPtr::dynamicCast(it->second);
             FramedDirectionPtr vecOri;
             FramedDirectionMap::const_iterator itOri = tcpOrientationVelocities.find(it->first);
-            if(itOri != tcpOrientationVelocities.end())
+
+            if (itOri != tcpOrientationVelocities.end())
+            {
                 vecOri = FramedDirectionPtr::dynamicCast(itOri->second);
-            const std::string &tcpName = it->first;
+            }
+
+            const std::string& tcpName = it->first;
 
             ARMARX_CHECK_EXPRESSION(vec->frame == vecOri->frame);
 
-            if(!existsDataField(TCP_TRANS_VELOCITIES_CHANNEL, tcpName))
+            if (!existsDataField(TCP_TRANS_VELOCITIES_CHANNEL, tcpName))
+            {
                 offerDataFieldWithDefault(TCP_TRANS_VELOCITIES_CHANNEL, tcpName, Variant(it->second), "Pose of " + tcpName);
+            }
             else
+            {
                 setDataField(TCP_TRANS_VELOCITIES_CHANNEL, tcpName, Variant(it->second));
+            }
+
             updateChannel(TCP_TRANS_VELOCITIES_CHANNEL);
-            const std::string channelName = tcpName+"Velocities";
-            if(!existsChannel(channelName))
+            const std::string channelName = tcpName + "Velocities";
+
+            if (!existsChannel(channelName))
             {
                 offerChannel(channelName, "pose components of " + tcpName);
-                offerDataFieldWithDefault(channelName,"x", Variant(vec->x), "X axis");
-                offerDataFieldWithDefault(channelName,"y", Variant(vec->y), "Y axis");
-                offerDataFieldWithDefault(channelName,"z", Variant(vec->z), "Z axis");
-                offerDataFieldWithDefault(channelName,"roll", Variant(vecOri->x), "Roll");
-                offerDataFieldWithDefault(channelName,"pitch", Variant(vecOri->y), "Pitch");
-                offerDataFieldWithDefault(channelName,"yaw", Variant(vecOri->z), "Yaw");
-                offerDataFieldWithDefault(channelName,"frame", Variant(vecOri->frame), "Reference Frame");
+                offerDataFieldWithDefault(channelName, "x", Variant(vec->x), "X axis");
+                offerDataFieldWithDefault(channelName, "y", Variant(vec->y), "Y axis");
+                offerDataFieldWithDefault(channelName, "z", Variant(vec->z), "Z axis");
+                offerDataFieldWithDefault(channelName, "roll", Variant(vecOri->x), "Roll");
+                offerDataFieldWithDefault(channelName, "pitch", Variant(vecOri->y), "Pitch");
+                offerDataFieldWithDefault(channelName, "yaw", Variant(vecOri->z), "Yaw");
+                offerDataFieldWithDefault(channelName, "frame", Variant(vecOri->frame), "Reference Frame");
             }
             else
             {
-                setDataField(channelName,"x", Variant(vec->x));
-                setDataField(channelName,"y", Variant(vec->y));
-                setDataField(channelName,"z", Variant(vec->z));
-                setDataField(channelName,"roll", Variant(vecOri->x));
-                setDataField(channelName,"pitch", Variant(vecOri->y));
-                setDataField(channelName,"yaw", Variant(vecOri->z));
-                setDataField(channelName,"frame", Variant(vec->frame));
+                setDataField(channelName, "x", Variant(vec->x));
+                setDataField(channelName, "y", Variant(vec->y));
+                setDataField(channelName, "z", Variant(vec->z));
+                setDataField(channelName, "roll", Variant(vecOri->x));
+                setDataField(channelName, "pitch", Variant(vecOri->y));
+                setDataField(channelName, "yaw", Variant(vecOri->z));
+                setDataField(channelName, "frame", Variant(vec->frame));
             }
+
             updateChannel(channelName);
 
         }
diff --git a/source/RobotAPI/components/units/TCPControlUnitObserver.h b/source/RobotAPI/components/units/TCPControlUnitObserver.h
index e8af6aaf86700be5e58d956b405cf2005356ca61..e3903b39e30d60d91a30acaea2d75e245f5e824f 100644
--- a/source/RobotAPI/components/units/TCPControlUnitObserver.h
+++ b/source/RobotAPI/components/units/TCPControlUnitObserver.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,28 +16,29 @@
 * @package    ArmarX::
 * @author     Mirko Waechter ( mirko.waechter at kit dot edu)
 * @date       2013
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 #ifndef _ARMARX_TCPCONTROLUNITOBSERVER_H
 #define _ARMARX_TCPCONTROLUNITOBSERVER_H
 
-#include <Core/observers/Observer.h>
+#include <ArmarXCore/observers/Observer.h>
 #include <RobotAPI/interface/units/TCPControlUnit.h>
 
-namespace armarx {
+namespace armarx
+{
     /**
      * \class TCPControlUnitObserverPropertyDefinitions
      * \brief
      */
     class TCPControlUnitObserverPropertyDefinitions:
-            public ComponentPropertyDefinitions
+        public ComponentPropertyDefinitions
     {
     public:
         TCPControlUnitObserverPropertyDefinitions(std::string prefix):
             ComponentPropertyDefinitions(prefix)
         {
-            defineRequiredProperty<std::string>("TCPControlUnitName","Name of the TCPControlUnit");
+            defineRequiredProperty<std::string>("TCPControlUnitName", "Name of the TCPControlUnit");
         }
     };
 
@@ -53,14 +53,17 @@ namespace armarx {
      * Available condition checks are: *updated*, *equals*, *approx*, *larger*, *smaller* and *magnitudelarger*.
      */
     class TCPControlUnitObserver :
-            virtual public Observer,
-            virtual public TCPControlUnitObserverInterface
+        virtual public Observer,
+        virtual public TCPControlUnitObserverInterface
     {
     public:
         TCPControlUnitObserver();
 
         // framework hooks
-        virtual std::string getDefaultName() const { return "TCPControlUnitObserver"; }
+        virtual std::string getDefaultName() const
+        {
+            return "TCPControlUnitObserver";
+        }
         void onInitObserver();
         void onConnectObserver();
 
@@ -71,8 +74,8 @@ namespace armarx {
 
     public:
         // TCPControlUnitListener interface
-        void reportTCPPose(const FramedPoseBaseMap &poseMap, const Ice::Current &c = Ice::Current());
-        void reportTCPVelocities(const FramedDirectionMap &tcpTranslationVelocities, const FramedDirectionMap &tcpOrientationVelocities, const Ice::Current &c = Ice::Current());
+        void reportTCPPose(const FramedPoseBaseMap& poseMap, const Ice::Current& c = Ice::Current());
+        void reportTCPVelocities(const FramedDirectionMap& tcpTranslationVelocities, const FramedDirectionMap& tcpOrientationVelocities, const Ice::Current& c = Ice::Current());
 
         Mutex dataMutex;
     };
diff --git a/source/RobotAPI/gui-plugins/CMakeLists.txt b/source/RobotAPI/gui-plugins/CMakeLists.txt
index a28c3cba32952879bbbc36d7a6182a54eac57986..423ec3285d801635b8d00309258cebcc9683a053 100644
--- a/source/RobotAPI/gui-plugins/CMakeLists.txt
+++ b/source/RobotAPI/gui-plugins/CMakeLists.txt
@@ -1,12 +1,9 @@
 add_subdirectory(KinematicUnitPlugin)
-
 add_subdirectory(HandUnitPlugin)
 add_subdirectory(PlatformUnitPlugin)
 add_subdirectory(SensorActorWidgetsPlugin)
 add_subdirectory(HapticUnitPlugin)
 add_subdirectory(RobotViewerPlugin)
-add_subdirectory(RobotIKPlugin)
 
-#add_subdirectory(ObjectExaminerPlugin)
 
 
diff --git a/source/RobotAPI/gui-plugins/HandUnitPlugin/CMakeLists.txt b/source/RobotAPI/gui-plugins/HandUnitPlugin/CMakeLists.txt
index 6bed53b72473a1516a251bfad620ca64a30a96fe..08df5c4fc989202a524b3987e304e83a1eaeb21c 100644
--- a/source/RobotAPI/gui-plugins/HandUnitPlugin/CMakeLists.txt
+++ b/source/RobotAPI/gui-plugins/HandUnitPlugin/CMakeLists.txt
@@ -27,11 +27,11 @@ set(GUI_UIS
     HandUnitConfigDialog.ui
 )
 
-set(COMPONENT_LIBS RobotAPIUnits ArmarXInterfaces ${Simox_LIBRARIES})
+set(COMPONENT_LIBS RobotAPIUnits ArmarXCoreInterfaces ${Simox_LIBRARIES})
+
+
 
-set(LIB_VERSION    0.1.0)
-set(LIB_SOVERSION  0)
 
 if (ArmarXGui_FOUND)
-	armarx_gui_library(HandUnitGuiPlugin "${SOURCES}" "${GUI_MOC_HDRS}" "${GUI_UIS}" "" "${COMPONENT_LIBS}" "${LIB_VERSION}" "${LIB_SOVERSION}")
+	armarx_gui_library(HandUnitGuiPlugin "${SOURCES}" "${GUI_MOC_HDRS}" "${GUI_UIS}" "" "${COMPONENT_LIBS}" )
 endif()
diff --git a/source/RobotAPI/gui-plugins/HandUnitPlugin/HandUnitConfigDialog.cpp b/source/RobotAPI/gui-plugins/HandUnitPlugin/HandUnitConfigDialog.cpp
index 831e9b33631f98dd92cdad52cf84ef059a6b74c6..1c29574a9c4a0e85d4de52ed1528f5beba14066a 100644
--- a/source/RobotAPI/gui-plugins/HandUnitPlugin/HandUnitConfigDialog.cpp
+++ b/source/RobotAPI/gui-plugins/HandUnitPlugin/HandUnitConfigDialog.cpp
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::
 * @author     Nikolaus Vahrenkamp ( vahrenkamp at kit dot edu)
 * @date       2012
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -27,7 +26,7 @@
 #include <RobotAPI/components/units/HandUnit.h>
 #include <IceUtil/UUID.h>
 
-armarx::HandUnitConfigDialog::HandUnitConfigDialog(QWidget *parent) :
+armarx::HandUnitConfigDialog::HandUnitConfigDialog(QWidget* parent) :
     QDialog(parent),
     ui(new Ui::HandUnitConfigDialog),
     uuid(IceUtil::generateUUID())
diff --git a/source/RobotAPI/gui-plugins/HandUnitPlugin/HandUnitConfigDialog.h b/source/RobotAPI/gui-plugins/HandUnitPlugin/HandUnitConfigDialog.h
index 3a13864f4448f85715c0e03a36ac88d732f32b2f..3dad9189a3231bb20cd479fff5b09ff09efc6749 100644
--- a/source/RobotAPI/gui-plugins/HandUnitPlugin/HandUnitConfigDialog.h
+++ b/source/RobotAPI/gui-plugins/HandUnitPlugin/HandUnitConfigDialog.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::
 * @author     Nikolaus Vahrenkamp ( vahrenkamp at kit dot edu)
 * @date       2012
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -26,11 +25,12 @@
 
 #include <QDialog>
 
-#include <Core/core/IceManager.h>
+#include <ArmarXCore/core/IceManager.h>
 
-#include <Gui/libraries/ArmarXGuiBase/widgets/IceProxyFinder.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/widgets/IceProxyFinder.h>
 
-namespace Ui {
+namespace Ui
+{
     class HandUnitConfigDialog;
 }
 
@@ -43,17 +43,20 @@ namespace armarx
         Q_OBJECT
 
     public:
-        explicit HandUnitConfigDialog(QWidget *parent = 0);
+        explicit HandUnitConfigDialog(QWidget* parent = 0);
         ~HandUnitConfigDialog();
 
     protected:
         // ManagedIceObject interface
-        std::string getDefaultName() const { return "HandUnitConfigDialog" + uuid;}
+        std::string getDefaultName() const
+        {
+            return "HandUnitConfigDialog" + uuid;
+        }
         void onInitComponent();
         void onConnectComponent();
 
     private:
-        Ui::HandUnitConfigDialog *ui;
+        Ui::HandUnitConfigDialog* ui;
 
         IceProxyFinderBase* proxyFinder;
         std::string uuid;
diff --git a/source/RobotAPI/gui-plugins/HandUnitPlugin/HandUnitGuiPlugin.cpp b/source/RobotAPI/gui-plugins/HandUnitPlugin/HandUnitGuiPlugin.cpp
index 41d7d68b6116d476855e372273366e86755a0df2..11628ca2e20f32473b81d9bdc6f1b30a2d60ae5b 100644
--- a/source/RobotAPI/gui-plugins/HandUnitPlugin/HandUnitGuiPlugin.cpp
+++ b/source/RobotAPI/gui-plugins/HandUnitPlugin/HandUnitGuiPlugin.cpp
@@ -1,7 +1,7 @@
 #include "HandUnitGuiPlugin.h"
 #include "HandUnitConfigDialog.h"
 #include "ui_HandUnitConfigDialog.h"
-#include <Core/core/system/ArmarXDataPath.h>
+#include <ArmarXCore/core/system/ArmarXDataPath.h>
 
 // Qt headers
 #include <Qt>
@@ -11,7 +11,7 @@
 #include <QLineEdit>
 #include <QMessageBox>
 
-#include <Core/observers/variant/SingleTypeVariantList.h>
+#include <ArmarXCore/observers/variant/SingleTypeVariantList.h>
 
 using namespace armarx;
 
@@ -50,7 +50,7 @@ void HandUnitWidget::onConnectComponent()
     handName = handUnitProxy->getHandName();
 
     // @@@ In simulation hand is called 'Hand L'/'Hand R'. On 3b Hand is called 'TCP R'
-    if(handName != "Hand L" && handName != "Hand R" && handName != "TCP L" && handName != "TCP R")
+    if (handName != "Hand L" && handName != "Hand R" && handName != "TCP L" && handName != "TCP R")
     {
         //QMessageBox::warning(NULL, "Hand not supported", QString("Hand with name \"") + QString::fromStdString(handName) + " \" is not suppored.");
         ARMARX_WARNING << "Hand with name \"" << handName << "\" is not supported.";
@@ -61,11 +61,13 @@ void HandUnitWidget::onConnectComponent()
     SingleTypeVariantListPtr preshapeStrings = SingleTypeVariantListPtr::dynamicCast(handUnitProxy->getShapeNames());
     QStringList list;
     int preshapeCount = preshapeStrings->getSize();
+
     for (int i = 0; i < preshapeCount; ++i)
     {
         std::string shape = ((preshapeStrings->getVariant(i))->get<std::string>());
         list << QString::fromStdString(shape);
     }
+
     ui.comboPreshapes->clear();
     ui.comboPreshapes->addItems(list);
 }
@@ -81,12 +83,13 @@ void HandUnitWidget::onExitComponent()
 
 QPointer<QDialog> HandUnitWidget::getConfigDialog(QWidget* parent)
 {
-    if(!dialog)
+    if (!dialog)
     {
         dialog = new HandUnitConfigDialog(parent);
         //dialog->ui->editHandUnitName->setText(QString::fromStdString(handUnitProxyName));
         //dialog->ui->editHandName->setText(QString::fromStdString(handName));
     }
+
     return qobject_cast<HandUnitConfigDialog*>(dialog);
 }
 
@@ -102,21 +105,22 @@ void HandUnitWidget::preshapeHand()
 
 void HandUnitWidget::setJointAngles()
 {
-    if(!handUnitProxy)
+    if (!handUnitProxy)
     {
         ARMARX_WARNING << "invalid proxy";
         return;
     }
 
-    if(!setJointAnglesFlag)
+    if (!setJointAnglesFlag)
     {
         return;
     }
+
     setJointAnglesFlag = false;
 
     NameValueMap ja;
 
-    if(handName == "Hand L" || handName == "TCP L")
+    if (handName == "Hand L" || handName == "TCP L")
     {
         ja["Hand Palm 2 L"] = ui.horizontalSliderPalm->value() * M_PI / 180;
         ja["Index L J0"] = ui.horizontalSliderIndexJ0->value() * M_PI / 180;
@@ -131,7 +135,7 @@ void HandUnitWidget::setJointAngles()
         ja["Pinky L J0"] = rinkyValue;
         ja["Pinky L J1"] = rinkyValue;
     }
-    else if(handName == "Hand R" || handName == "TCP R")
+    else if (handName == "Hand R" || handName == "TCP R")
     {
         ja["Hand Palm 2 R"] = ui.horizontalSliderPalm->value() * M_PI / 180;
         ja["Index R J0"] = ui.horizontalSliderIndexJ0->value() * M_PI / 180;
@@ -185,13 +189,13 @@ void HandUnitWidget::setPreshape(std::string preshape)
     handUnitProxy->setShape(preshape);
 }
 
-void HandUnitWidget::loadSettings(QSettings *settings)
+void HandUnitWidget::loadSettings(QSettings* settings)
 {
     handUnitProxyName = settings->value("handUnitProxyName", QString::fromStdString(handUnitProxyName)).toString().toStdString();
     handName = settings->value("handName", QString::fromStdString(handName)).toString().toStdString();
 }
 
-void HandUnitWidget::saveSettings(QSettings *settings)
+void HandUnitWidget::saveSettings(QSettings* settings)
 {
     settings->setValue("handUnitProxyName", QString::fromStdString(handUnitProxyName));
     settings->setValue("handName", QString::fromStdString(handName));
@@ -221,26 +225,26 @@ void HandUnitWidget::connectSlots()
 
 
 
-void armarx::HandUnitWidget::reportHandShaped(const std::string &handName, const std::string &handShapeName, const Ice::Current &)
+void armarx::HandUnitWidget::reportHandShaped(const std::string& handName, const std::string& handShapeName, const Ice::Current&)
 {
     ARMARX_IMPORTANT << handName << ": " << handShapeName;
 }
 
-void armarx::HandUnitWidget::reportNewHandShapeName(const std::string &handName, const std::string &handShapeName, const Ice::Current &)
+void armarx::HandUnitWidget::reportNewHandShapeName(const std::string& handName, const std::string& handShapeName, const Ice::Current&)
 {
     ARMARX_IMPORTANT << handName << ": " << handShapeName;
 }
 
 
 
-void armarx::HandUnitWidget::reportJointAngles(const armarx::NameValueMap &actualJointAngles, const Ice::Current &c)
+void armarx::HandUnitWidget::reportJointAngles(const armarx::NameValueMap& actualJointAngles, const Ice::Current& c)
 {
 
 }
 
 
 
-void armarx::HandUnitWidget::reportJointPressures(const armarx::NameValueMap &actualJointPressures, const Ice::Current &c)
+void armarx::HandUnitWidget::reportJointPressures(const armarx::NameValueMap& actualJointPressures, const Ice::Current& c)
 {
 
 }
diff --git a/source/RobotAPI/gui-plugins/HandUnitPlugin/HandUnitGuiPlugin.h b/source/RobotAPI/gui-plugins/HandUnitPlugin/HandUnitGuiPlugin.h
index d3706a9128d5504c3500eef63c26fec3a195e367..b28665be31d178f915f633b45e15bb14b678976a 100644
--- a/source/RobotAPI/gui-plugins/HandUnitPlugin/HandUnitGuiPlugin.h
+++ b/source/RobotAPI/gui-plugins/HandUnitPlugin/HandUnitGuiPlugin.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::Component::ObjectExaminerGuiPlugin
 * @author     Nikolaus Vahrenkamp ( vahrenkamp at kit dot edu)
 * @copyright  2012
-* @license    http://www.gnu.org/licenses/gpl.txt
+* @license    http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 
 */
@@ -27,9 +26,9 @@
 
 /* ArmarX headers */
 #include "ui_HandUnitGuiPlugin.h"
-#include <Core/core/Component.h>
-#include <Gui/libraries/ArmarXGuiBase/ArmarXGuiPlugin.h>
-#include <Gui/libraries/ArmarXGuiBase/ArmarXComponentWidgetController.h>
+#include <ArmarXCore/core/Component.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXGuiPlugin.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXComponentWidgetController.h>
 
 #include <RobotAPI/interface/units/HandUnitInterface.h>
 
@@ -38,7 +37,7 @@
 
 #include <string>
 
-#include <Core/core/services/tasks/PeriodicTask.h>
+#include <ArmarXCore/core/services/tasks/PeriodicTask.h>
 
 
 namespace armarx
@@ -51,7 +50,7 @@ namespace armarx
       \see HandUnitWidget
       */
     class HandUnitGuiPlugin :
-            public ArmarXGuiPlugin
+        public ArmarXGuiPlugin
     {
     public:
         HandUnitGuiPlugin();
@@ -62,23 +61,20 @@ namespace armarx
     };
 
     /*!
-     * \class HandUnitWidget
+     * \page RobotAPI-GuiPlugins-HandUnitWidget HandUnitGuiPlugin
      * \brief With this widget the HandUnit can be controlled.
      * \image html HandUnitGUI.png
      * You can either select a preshape from the drop-down-menu on top or set each
      * joint individually.
      * When you add the widget to the Gui, you need to specify the following parameters:
-     * 
+     *
      * Parameter Name   | Example Value     | Required?     | Description
      *  :----------------  | :-------------:   | :-------------- |:--------------------
      * Proxy     | LeftHandUnit   | Yes | The hand unit you want to control.
-     *         
-     * \ingroup RobotAPI-ArmarXGuiPlugins ArmarXGuiPlugins
-     * \see HandUnitGuiPlugin
      */
     class HandUnitWidget :
-            public ArmarXComponentWidgetController,
-            public HandUnitListener
+        public ArmarXComponentWidgetController,
+        public HandUnitListener
     {
         Q_OBJECT
     public:
@@ -93,17 +89,23 @@ namespace armarx
         virtual void onExitComponent();
 
         // HandUnitListener interface
-        void reportHandShaped(const std::string &, const std::string &, const Ice::Current &);
-        void reportNewHandShapeName(const std::string &, const std::string &, const Ice::Current &);
+        void reportHandShaped(const std::string&, const std::string&, const Ice::Current&);
+        void reportNewHandShapeName(const std::string&, const std::string&, const Ice::Current&);
 
 
         // inherited of ArmarXWidget
-        virtual QString getWidgetName() const { return "RobotControl.HandUnitGUI"; }
-        virtual QIcon getWidgetIcon() const { return QIcon("://icons/hand.svg"); }
+        virtual QString getWidgetName() const
+        {
+            return "RobotControl.HandUnitGUI";
+        }
+        virtual QIcon getWidgetIcon() const
+        {
+            return QIcon("://icons/hand.svg");
+        }
 
         QPointer<QDialog> getConfigDialog(QWidget* parent = 0);
-        virtual void loadSettings(QSettings * settings);
-        virtual void saveSettings(QSettings * settings);
+        virtual void loadSettings(QSettings* settings);
+        virtual void saveSettings(QSettings* settings);
         void configured();
 
     public slots:
@@ -140,8 +142,8 @@ namespace armarx
 
         // HandUnitListener interface
     public:
-        void reportJointAngles(const::armarx::NameValueMap &actualJointAngles, const Ice::Current &);
-        void reportJointPressures(const::armarx::NameValueMap &actualJointPressures, const Ice::Current &);
+        void reportJointAngles(const::armarx::NameValueMap& actualJointAngles, const Ice::Current&);
+        void reportJointPressures(const::armarx::NameValueMap& actualJointPressures, const Ice::Current&);
     };
     typedef boost::shared_ptr<HandUnitWidget> HandUnitGuiPluginPtr;
 }
diff --git a/source/RobotAPI/gui-plugins/HapticUnitPlugin/CMakeLists.txt b/source/RobotAPI/gui-plugins/HapticUnitPlugin/CMakeLists.txt
index 9caeeee68f7beded8305dce337f2fa83c8c02904..2c9d477b35b77e4b6cbc2558cd6df738803670fe 100644
--- a/source/RobotAPI/gui-plugins/HapticUnitPlugin/CMakeLists.txt
+++ b/source/RobotAPI/gui-plugins/HapticUnitPlugin/CMakeLists.txt
@@ -42,11 +42,11 @@ set(GUI_UIS
     MatrixDisplayWidget.ui
 )
 
-set(COMPONENT_LIBS RobotAPIUnits ArmarXInterfaces ArmarXCoreEigen3Variants ${Simox_LIBRARIES})
+set(COMPONENT_LIBS RobotAPIUnits ArmarXCoreInterfaces ArmarXCoreEigen3Variants ${Simox_LIBRARIES})
+
+
 
-set(LIB_VERSION    0.1.0)
-set(LIB_SOVERSION  0)
 
 if (ArmarXGui_FOUND)
-	armarx_gui_library(HapticUnitGuiPlugin "${SOURCES}" "${GUI_MOC_HDRS}" "${GUI_UIS}" "" "${COMPONENT_LIBS}" "${LIB_VERSION}" "${LIB_SOVERSION}")
+	armarx_gui_library(HapticUnitGuiPlugin "${SOURCES}" "${GUI_MOC_HDRS}" "${GUI_UIS}" "" "${COMPONENT_LIBS}" )
 endif()
diff --git a/source/RobotAPI/gui-plugins/HapticUnitPlugin/HapticUnitConfigDialog.cpp b/source/RobotAPI/gui-plugins/HapticUnitPlugin/HapticUnitConfigDialog.cpp
index 55aefcec1a51f80f8fda01b5a69d70936f58f859..d450ab1607339c95e83fe9eea17976c5d1ab35b7 100644
--- a/source/RobotAPI/gui-plugins/HapticUnitPlugin/HapticUnitConfigDialog.cpp
+++ b/source/RobotAPI/gui-plugins/HapticUnitPlugin/HapticUnitConfigDialog.cpp
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,14 +16,14 @@
 * @package    ArmarX::
 * @author     Nikolaus Vahrenkamp ( vahrenkamp at kit dot edu)
 * @date       2012
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
 #include "HapticUnitConfigDialog.h"
 #include "ui_HapticUnitConfigDialog.h"
 
-armarx::HapticUnitConfigDialog::HapticUnitConfigDialog(QWidget *parent) :
+armarx::HapticUnitConfigDialog::HapticUnitConfigDialog(QWidget* parent) :
     QDialog(parent),
     ui(new Ui::HapticUnitConfigDialog)
 {
diff --git a/source/RobotAPI/gui-plugins/HapticUnitPlugin/HapticUnitConfigDialog.h b/source/RobotAPI/gui-plugins/HapticUnitPlugin/HapticUnitConfigDialog.h
index 1e7f3f94ae20a38593e6104f74dec8b20f9f2f63..3592cf3244d74024dc6ac1bb486ba892b1dea84c 100644
--- a/source/RobotAPI/gui-plugins/HapticUnitPlugin/HapticUnitConfigDialog.h
+++ b/source/RobotAPI/gui-plugins/HapticUnitPlugin/HapticUnitConfigDialog.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::
 * @author     Nikolaus Vahrenkamp ( vahrenkamp at kit dot edu)
 * @date       2012
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -26,7 +25,8 @@
 
 #include <QDialog>
 
-namespace Ui {
+namespace Ui
+{
     class HapticUnitConfigDialog;
 }
 
@@ -38,11 +38,11 @@ namespace armarx
         Q_OBJECT
 
     public:
-        explicit HapticUnitConfigDialog(QWidget *parent = 0);
+        explicit HapticUnitConfigDialog(QWidget* parent = 0);
         ~HapticUnitConfigDialog();
 
     private:
-        Ui::HapticUnitConfigDialog *ui;
+        Ui::HapticUnitConfigDialog* ui;
 
         //friend class HapticUnitWidget;
     };
diff --git a/source/RobotAPI/gui-plugins/HapticUnitPlugin/HapticUnitGuiPlugin.cpp b/source/RobotAPI/gui-plugins/HapticUnitPlugin/HapticUnitGuiPlugin.cpp
index 78208f7189a63fa974c173035642662d0b9bcf38..a3437fbd79e0b255c956d7bfc3383a9746faf56b 100644
--- a/source/RobotAPI/gui-plugins/HapticUnitPlugin/HapticUnitGuiPlugin.cpp
+++ b/source/RobotAPI/gui-plugins/HapticUnitPlugin/HapticUnitGuiPlugin.cpp
@@ -2,10 +2,10 @@
 #include "HapticUnitConfigDialog.h"
 #include "ui_HapticUnitConfigDialog.h"
 
-#include <Core/core/system/ArmarXDataPath.h>
-#include <Core/observers/variant/SingleTypeVariantList.h>
-#include <Core/util/variants/eigen3/MatrixVariant.h>
-#include <Core/observers/variant/TimestampVariant.h>
+#include <ArmarXCore/core/system/ArmarXDataPath.h>
+#include <ArmarXCore/observers/variant/SingleTypeVariantList.h>
+#include <ArmarXCore/util/variants/eigen3/MatrixVariant.h>
+#include <ArmarXCore/observers/variant/TimestampVariant.h>
 #include <IceUtil/Time.h>
 
 
@@ -75,10 +75,11 @@ void HapticUnitWidget::onDisconnectComponent()
 
 QPointer<QDialog> HapticUnitWidget::getConfigDialog(QWidget* parent)
 {
-    if(!dialog)
+    if (!dialog)
     {
         dialog = new HapticUnitConfigDialog(parent);
     }
+
     return qobject_cast<HapticUnitConfigDialog*>(dialog);
 }
 
@@ -91,7 +92,7 @@ void HapticUnitWidget::configured()
 void HapticUnitWidget::updateData()
 {
 
-    for(std::pair<std::string, MatrixDatafieldDisplayWidget*> pair : matrixDisplays)
+    for (std::pair<std::string, MatrixDatafieldDisplayWidget*> pair : matrixDisplays)
     {
         //MatrixFloatPtr matrix = VariantPtr::dynamicCast(hapticObserverProxy->getDataField(new DataFieldIdentifier(hapticObserverProxyName, pair.first, "matrix")))->get<MatrixFloat>();
         std::string name = hapticObserverProxy->getDataField(new DataFieldIdentifier(hapticObserverProxyName, pair.first, "name"))->getString();
@@ -109,7 +110,11 @@ void HapticUnitWidget::onContextMenu(QPoint point)
 {
     QMenu* contextMenu = new QMenu(getWidget());
     MatrixDatafieldDisplayWidget* matrixDisplay = qobject_cast<MatrixDatafieldDisplayWidget*>(sender());
-    if(!matrixDisplay) return;
+
+    if (!matrixDisplay)
+    {
+        return;
+    }
 
     QAction* setDeviceTag = contextMenu->addAction(tr("Set Device Tag"));
 
@@ -118,14 +123,15 @@ void HapticUnitWidget::onContextMenu(QPoint point)
     std::string channelName = channelNameReverseMap.at(matrixDisplay);
     std::string deviceName = deviceNameReverseMap.at(matrixDisplay);
 
-    if(action == setDeviceTag)
+    if (action == setDeviceTag)
     {
         std::string tag = hapticObserverProxy->getDataField(new DataFieldIdentifier(hapticObserverProxyName, channelName, "name"))->getString();
 
         bool ok;
         QString newTag = QInputDialog::getText(getWidget(), tr("Set Device Tag"),
-                                             QString::fromStdString("New Tag for Device '" + deviceName + "'"), QLineEdit::Normal,
-                                             QString::fromStdString(tag), &ok);
+                                               QString::fromStdString("New Tag for Device '" + deviceName + "'"), QLineEdit::Normal,
+                                               QString::fromStdString(tag), &ok);
+
         if (ok && !newTag.isEmpty())
         {
             ARMARX_IMPORTANT_S << "requesting to set new device tag for " << deviceName << ": " << newTag.toStdString();
@@ -137,12 +143,12 @@ void HapticUnitWidget::onContextMenu(QPoint point)
 }
 
 
-void HapticUnitWidget::loadSettings(QSettings *settings)
+void HapticUnitWidget::loadSettings(QSettings* settings)
 {
 }
 
 
-void HapticUnitWidget::saveSettings(QSettings *settings)
+void HapticUnitWidget::saveSettings(QSettings* settings)
 {
 }
 
@@ -162,14 +168,17 @@ void HapticUnitWidget::createMatrixWidgets()
 
 void HapticUnitWidget::updateDisplayWidgets()
 {
-    QLayoutItem *child;
-    while ((child = ui.gridLayoutDisplay->takeAt(0)) != 0) {
+    QLayoutItem* child;
+
+    while ((child = ui.gridLayoutDisplay->takeAt(0)) != 0)
+    {
         delete child;
     }
 
     int i = 0;
     ChannelRegistry channels = hapticObserverProxy->getAvailableChannels(false);
-    for(std::pair<std::string, ChannelRegistryEntry> pair : channels)
+
+    for (std::pair<std::string, ChannelRegistryEntry> pair : channels)
     {
         std::string channelName = pair.first;
         MatrixDatafieldDisplayWidget* matrixDisplay = new MatrixDatafieldDisplayWidget(new DatafieldRef(hapticObserverProxy, channelName, "matrix"), hapticObserverProxy, getWidget());
@@ -188,7 +197,7 @@ void HapticUnitWidget::updateDisplayWidgets()
 void HapticUnitWidget::onCheckBoxOffsetFilterStateChanged(int state)
 {
     //ARMARX_IMPORTANT << "onCheckBoxOffsetFilterToggled: " << state;
-    for(std::pair<std::string, MatrixDatafieldDisplayWidget*> pair : matrixDisplays)
+    for (std::pair<std::string, MatrixDatafieldDisplayWidget*> pair : matrixDisplays)
     {
         pair.second->enableOffsetFilter(ui.checkBoxOffsetFilter->isChecked());
     }
diff --git a/source/RobotAPI/gui-plugins/HapticUnitPlugin/HapticUnitGuiPlugin.h b/source/RobotAPI/gui-plugins/HapticUnitPlugin/HapticUnitGuiPlugin.h
index a466e382eeffebd3c1534d7ff888cff3ed50b786..36201d76340544e05115f1666599fb957a946e99 100644
--- a/source/RobotAPI/gui-plugins/HapticUnitPlugin/HapticUnitGuiPlugin.h
+++ b/source/RobotAPI/gui-plugins/HapticUnitPlugin/HapticUnitGuiPlugin.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::Component::ObjectExaminerGuiPlugin
 * @author     Nikolaus Vahrenkamp ( vahrenkamp at kit dot edu)
 * @copyright  2012
-* @license    http://www.gnu.org/licenses/gpl.txt
+* @license    http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 
 */
@@ -27,10 +26,10 @@
 
 /* ArmarX headers */
 #include "ui_HapticUnitGuiPlugin.h"
-#include <Core/core/Component.h>
-#include <Gui/libraries/ArmarXGuiBase/ArmarXGuiPlugin.h>
-#include <Gui/libraries/ArmarXGuiBase/ArmarXComponentWidgetController.h>
-#include <Core/observers/Observer.h>
+#include <ArmarXCore/core/Component.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXGuiPlugin.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXComponentWidgetController.h>
+#include <ArmarXCore/observers/Observer.h>
 
 /* Qt headers */
 #include <QtGui/QMainWindow>
@@ -46,14 +45,8 @@ namespace armarx
 {
     class HapticUnitConfigDialog;
 
-    /*!
-      \class HapticUnitGuiPlugin
-      \brief This plugin provides a widget with which the HapticUnit can be controlled.
-
-      \see HapticUnitWidget
-      */
     class HapticUnitGuiPlugin :
-            public ArmarXGuiPlugin
+        public ArmarXGuiPlugin
     {
     public:
         HapticUnitGuiPlugin();
@@ -64,14 +57,11 @@ namespace armarx
     };
 
     /*!
-      \class HapticUnitWidget
+      \page RobotAPI-GuiPlugins-HapticUnitPlugin HapticUnitPlugin
       \brief With this widget the HapticUnit can be controlled.
-
-      \ingroup RobotAPI-ArmarXGuiPlugins ArmarXGuiPlugins
-      \see HapticUnitGuiPlugin
       */
     class HapticUnitWidget :
-            public ArmarXComponentWidgetController
+        public ArmarXComponentWidgetController
     {
         Q_OBJECT
     public:
@@ -86,12 +76,18 @@ namespace armarx
         virtual void onDisconnectComponent();
 
         // inherited of ArmarXWidget
-        virtual QString getWidgetName() const { return "RobotControl.HapticUnitGUI"; }
-        virtual QIcon getWidgetIcon() const { return QIcon("://icons/haptic-hand.png"); }
+        virtual QString getWidgetName() const
+        {
+            return "RobotControl.HapticUnitGUI";
+        }
+        virtual QIcon getWidgetIcon() const
+        {
+            return QIcon("://icons/haptic-hand.png");
+        }
 
         QPointer<QDialog> getConfigDialog(QWidget* parent = 0);
-        virtual void loadSettings(QSettings * settings);
-        virtual void saveSettings(QSettings * settings);
+        virtual void loadSettings(QSettings* settings);
+        virtual void saveSettings(QSettings* settings);
         void configured();
 
     public slots:
diff --git a/source/RobotAPI/gui-plugins/HapticUnitPlugin/MatrixDatafieldDisplayWidget.cpp b/source/RobotAPI/gui-plugins/HapticUnitPlugin/MatrixDatafieldDisplayWidget.cpp
index 655237021a4aa994631d08be2a760feb7eea6ab1..ba3f893e94292aaedab26bf463ee311196d20c40 100644
--- a/source/RobotAPI/gui-plugins/HapticUnitPlugin/MatrixDatafieldDisplayWidget.cpp
+++ b/source/RobotAPI/gui-plugins/HapticUnitPlugin/MatrixDatafieldDisplayWidget.cpp
@@ -20,7 +20,7 @@ void MatrixDatafieldDisplayWidget::updateRequested()
     update();
 }
 
-MatrixDatafieldDisplayWidget::MatrixDatafieldDisplayWidget(DatafieldRefBasePtr matrixDatafield, ObserverInterfacePrx observer, QWidget *parent) :
+MatrixDatafieldDisplayWidget::MatrixDatafieldDisplayWidget(DatafieldRefBasePtr matrixDatafield, ObserverInterfacePrx observer, QWidget* parent) :
     QWidget(parent)
 {
     this->matrixDatafield = DatafieldRefPtr::dynamicCast(matrixDatafield);
@@ -31,7 +31,8 @@ MatrixDatafieldDisplayWidget::MatrixDatafieldDisplayWidget(DatafieldRefBasePtr m
     this->data(0, 0) = 0;
     enableOffsetFilter(false);
     QColor c[] = {QColor::fromHsv(0, 0, 0), QColor::fromHsv(240, 255, 255), QColor::fromHsv(270, 255, 255), QColor::fromHsv(300, 255, 255),
-                  QColor::fromHsv(0, 255, 255), QColor::fromHsv(30, 255, 255), QColor::fromHsv(60, 255, 255)};
+                  QColor::fromHsv(0, 255, 255), QColor::fromHsv(30, 255, 255), QColor::fromHsv(60, 255, 255)
+                 };
     this->colors = std::valarray<QColor>(c, sizeof c / sizeof c[0]);
 
     //connect(this, SIGNAL(updateData(MatrixXf)), SLOT(setData(MatrixXf)), Qt::QueuedConnection);
@@ -43,13 +44,13 @@ MatrixDatafieldDisplayWidget::~MatrixDatafieldDisplayWidget()
     //delete ui;
 }
 
-void MatrixDatafieldDisplayWidget::paintEvent(QPaintEvent *)
+void MatrixDatafieldDisplayWidget::paintEvent(QPaintEvent*)
 {
     mtx.lock();
 
     int paddingBottom = 40;
     QPainter painter(this);
-    painter.fillRect(rect(), QColor::fromRgb(0,0,0));
+    painter.fillRect(rect(), QColor::fromRgb(0, 0, 0));
     int matrixHeight = (height() - paddingBottom) * 8 / 10;
     int percentilesHeight = (height() - paddingBottom) - matrixHeight;
     drawMatrix(QRect(0, 0, width(), matrixHeight), painter);
@@ -64,7 +65,7 @@ void MatrixDatafieldDisplayWidget::paintEvent(QPaintEvent *)
 
 void MatrixDatafieldDisplayWidget::enableOffsetFilter(bool enabled)
 {
-    if(enabled)
+    if (enabled)
     {
         this->matrixDatafieldOffsetFiltered = DatafieldRefPtr::dynamicCast(observer->createFilteredDatafield(DatafieldFilterBasePtr(new filters::OffsetFilter()), matrixDatafield));
     }
@@ -72,23 +73,33 @@ void MatrixDatafieldDisplayWidget::enableOffsetFilter(bool enabled)
     {
         this->matrixDatafieldOffsetFiltered = this->matrixDatafield;
     }
+
     this->percentilesDatafield = DatafieldRefPtr::dynamicCast(observer->createFilteredDatafield(DatafieldFilterBasePtr(new filters::MatrixPercentilesFilter(50)), matrixDatafieldOffsetFiltered));
 }
 
 QColor MatrixDatafieldDisplayWidget::getColor(float value, float min, float max)
 {
     value = (value - min) / (max - min) * (colors.size() - 1);
-    if(value < 0) return colors[0];
-    if(value >= colors.size() - 1) return colors[colors.size() - 1];
+
+    if (value < 0)
+    {
+        return colors[0];
+    }
+
+    if (value >= colors.size() - 1)
+    {
+        return colors[colors.size() - 1];
+    }
+
     int i = (int)value;
     float f2 = value - i;
-    float f1 = 1- f2;
+    float f1 = 1 - f2;
     QColor c1 = colors[i];
     QColor c2 = colors[i + 1];
     return QColor((int)(c1.red() * f1 + c2.red() * f2), (int)(c1.green() * f1 + c2.green() * f2), (int)(c1.blue() * f1 + c2.blue() * f2));
 }
 
-void MatrixDatafieldDisplayWidget::drawMatrix(const QRect &target, QPainter &painter)
+void MatrixDatafieldDisplayWidget::drawMatrix(const QRect& target, QPainter& painter)
 {
     int pixelSize = std::min(target.width() / data.cols(), target.height() / data.rows());
     int dx = (target.width() - pixelSize * data.cols()) / 2;
@@ -96,9 +107,9 @@ void MatrixDatafieldDisplayWidget::drawMatrix(const QRect &target, QPainter &pai
     painter.setFont(QFont("Arial", 8));
     painter.setPen(QColor(Qt::GlobalColor::gray));
 
-    for(int x = 0; x < data.cols(); x++)
+    for (int x = 0; x < data.cols(); x++)
     {
-        for(int y = 0; y < data.rows(); y++)
+        for (int y = 0; y < data.rows(); y++)
         {
             QRect target = QRect(dx + x * pixelSize, dy + y * pixelSize, pixelSize, pixelSize);
             painter.fillRect(target, getColor(data(y, x), min, max));
@@ -107,12 +118,13 @@ void MatrixDatafieldDisplayWidget::drawMatrix(const QRect &target, QPainter &pai
     }
 }
 
-void MatrixDatafieldDisplayWidget::drawPercentiles(const QRect &target, QPainter &painter)
+void MatrixDatafieldDisplayWidget::drawPercentiles(const QRect& target, QPainter& painter)
 {
     painter.setPen(QColor(Qt::GlobalColor::gray));
     painter.drawRect(target);
     painter.setPen(QColor(Qt::GlobalColor::red));
-    for(int i = 0; i < (int)percentiles.size() - 1; i++)
+
+    for (int i = 0; i < (int)percentiles.size() - 1; i++)
     {
         int x1 = i * target.width() / (percentiles.size() - 1);
         int x2 = (i + 1) * target.width() / (percentiles.size() - 1);
diff --git a/source/RobotAPI/gui-plugins/HapticUnitPlugin/MatrixDatafieldDisplayWidget.h b/source/RobotAPI/gui-plugins/HapticUnitPlugin/MatrixDatafieldDisplayWidget.h
index edc77d914906d094e59a2a89a28dc14f7ae33b75..76c0d573ccc91d4d850e96476ec4604b05fb1d31 100644
--- a/source/RobotAPI/gui-plugins/HapticUnitPlugin/MatrixDatafieldDisplayWidget.h
+++ b/source/RobotAPI/gui-plugins/HapticUnitPlugin/MatrixDatafieldDisplayWidget.h
@@ -5,14 +5,15 @@
 #include <QMutex>
 #include <eigen3/Eigen/Dense>
 #include <valarray>
-#include <Core/interface/observers/ObserverInterface.h>
-#include <Core/observers/variant/DatafieldRef.h>
+#include <ArmarXCore/interface/observers/ObserverInterface.h>
+#include <ArmarXCore/observers/variant/DatafieldRef.h>
 
 
 using Eigen::MatrixXf;
 
-namespace Ui {
-class MatrixDatafieldDisplayWidget;
+namespace Ui
+{
+    class MatrixDatafieldDisplayWidget;
 }
 
 namespace armarx
@@ -28,9 +29,9 @@ namespace armarx
         void updateRequested();
 
     public:
-        explicit MatrixDatafieldDisplayWidget(DatafieldRefBasePtr matrixDatafield, ObserverInterfacePrx observer, QWidget *parent = 0);
+        explicit MatrixDatafieldDisplayWidget(DatafieldRefBasePtr matrixDatafield, ObserverInterfacePrx observer, QWidget* parent = 0);
         ~MatrixDatafieldDisplayWidget();
-        void paintEvent(QPaintEvent *);
+        void paintEvent(QPaintEvent*);
 
 
         void setRange(float min, float max)
@@ -41,7 +42,8 @@ namespace armarx
         void enableOffsetFilter(bool enabled);
         QColor getColor(float value, float min, float max);
 
-        void invokeUpdate(){
+        void invokeUpdate()
+        {
             emit doUpdate();
         }
         void setInfoOverlay(QString infoOverlay)
@@ -52,11 +54,11 @@ namespace armarx
         }
 
     private:
-        void drawMatrix(const QRect &target, QPainter &painter);
-        void drawPercentiles(const QRect &target, QPainter &painter);
+        void drawMatrix(const QRect& target, QPainter& painter);
+        void drawPercentiles(const QRect& target, QPainter& painter);
 
     private:
-        Ui::MatrixDatafieldDisplayWidget *ui;
+        Ui::MatrixDatafieldDisplayWidget* ui;
         MatrixXf data;
         std::vector<float> percentiles;
         float min, max;
diff --git a/source/RobotAPI/gui-plugins/HapticUnitPlugin/MatrixDisplayWidget.cpp b/source/RobotAPI/gui-plugins/HapticUnitPlugin/MatrixDisplayWidget.cpp
index dc1124675d390a9ba43e9a57726cc3321e67f998..85bfd0506081b94bb2f9664ce9fc8948646d3a33 100644
--- a/source/RobotAPI/gui-plugins/HapticUnitPlugin/MatrixDisplayWidget.cpp
+++ b/source/RobotAPI/gui-plugins/HapticUnitPlugin/MatrixDisplayWidget.cpp
@@ -8,7 +8,7 @@
 using namespace std;
 using namespace armarx;
 
-MatrixDisplayWidget::MatrixDisplayWidget(QWidget *parent) :
+MatrixDisplayWidget::MatrixDisplayWidget(QWidget* parent) :
     QWidget(parent),
     ui(new Ui::MatrixDisplayWidget)
 {
@@ -18,7 +18,8 @@ MatrixDisplayWidget::MatrixDisplayWidget(QWidget *parent) :
     this->data = MatrixXf(1, 1);
     this->data(0, 0) = 0;
     QColor c[] = {QColor::fromHsv(0, 0, 0), QColor::fromHsv(240, 255, 255), QColor::fromHsv(270, 255, 255), QColor::fromHsv(300, 255, 255),
-                  QColor::fromHsv(0, 255, 255), QColor::fromHsv(30, 255, 255), QColor::fromHsv(60, 255, 255)};
+                  QColor::fromHsv(0, 255, 255), QColor::fromHsv(30, 255, 255), QColor::fromHsv(60, 255, 255)
+                 };
     this->colors = std::valarray<QColor>(c, sizeof c / sizeof c[0]);
 
     //connect(this, SIGNAL(updateData(MatrixXf)), SLOT(setData(MatrixXf)), Qt::QueuedConnection);
@@ -30,7 +31,7 @@ MatrixDisplayWidget::~MatrixDisplayWidget()
     delete ui;
 }
 
-void MatrixDisplayWidget::paintEvent(QPaintEvent *)
+void MatrixDisplayWidget::paintEvent(QPaintEvent*)
 {
     mtx.lock();
     MatrixXf data = this->data;
@@ -41,18 +42,19 @@ void MatrixDisplayWidget::paintEvent(QPaintEvent *)
     int dx = (width() - pixelSize * data.cols()) / 2;
     int dy = (height() - pixelSize * data.rows()) / 2;
     QPainter painter(this);
-    painter.fillRect(rect(), QColor::fromRgb(0,0,0));
+    painter.fillRect(rect(), QColor::fromRgb(0, 0, 0));
     painter.setFont(QFont("Arial", 8));
 
-    for(int x = 0; x < data.cols(); x++)
+    for (int x = 0; x < data.cols(); x++)
     {
-        for(int y = 0; y < data.rows(); y++)
+        for (int y = 0; y < data.rows(); y++)
         {
             QRect target = QRect(dx + x * pixelSize, dy + y * pixelSize, pixelSize, pixelSize);
             painter.fillRect(target, getColor(data(y, x), min, max));
             painter.drawText(target, Qt::AlignCenter, QString::number(data(y, x)));
         }
     }
+
     painter.setFont(QFont("Arial", 12));
     painter.drawText(rect(), Qt::AlignBottom | Qt::AlignRight, infoOverlay);
 
@@ -62,11 +64,20 @@ void MatrixDisplayWidget::paintEvent(QPaintEvent *)
 QColor MatrixDisplayWidget::getColor(float value, float min, float max)
 {
     value = (value - min) / (max - min) * (colors.size() - 1);
-    if(value < 0) return colors[0];
-    if(value >= colors.size() - 1) return colors[colors.size() - 1];
+
+    if (value < 0)
+    {
+        return colors[0];
+    }
+
+    if (value >= colors.size() - 1)
+    {
+        return colors[colors.size() - 1];
+    }
+
     int i = (int)value;
     float f2 = value - i;
-    float f1 = 1- f2;
+    float f1 = 1 - f2;
     QColor c1 = colors[i];
     QColor c2 = colors[i + 1];
     return QColor((int)(c1.red() * f1 + c2.red() * f2), (int)(c1.green() * f1 + c2.green() * f2), (int)(c1.blue() * f1 + c2.blue() * f2));
diff --git a/source/RobotAPI/gui-plugins/HapticUnitPlugin/MatrixDisplayWidget.h b/source/RobotAPI/gui-plugins/HapticUnitPlugin/MatrixDisplayWidget.h
index 33480b6a827ba490812895638a9ca7febca3124c..6354d65c7d01d0e15cade9187c41dbd4823a99d1 100644
--- a/source/RobotAPI/gui-plugins/HapticUnitPlugin/MatrixDisplayWidget.h
+++ b/source/RobotAPI/gui-plugins/HapticUnitPlugin/MatrixDisplayWidget.h
@@ -8,8 +8,9 @@
 
 using Eigen::MatrixXf;
 
-namespace Ui {
-class MatrixDisplayWidget;
+namespace Ui
+{
+    class MatrixDisplayWidget;
 }
 
 namespace armarx
@@ -31,9 +32,9 @@ namespace armarx
         }
 
     public:
-        explicit MatrixDisplayWidget(QWidget *parent = 0);
+        explicit MatrixDisplayWidget(QWidget* parent = 0);
         ~MatrixDisplayWidget();
-        void paintEvent(QPaintEvent *);
+        void paintEvent(QPaintEvent*);
 
 
 
@@ -44,7 +45,8 @@ namespace armarx
         }
         QColor getColor(float value, float min, float max);
 
-        void invokeUpdate(){
+        void invokeUpdate()
+        {
             emit doUpdate();
         }
         void setInfoOverlay(QString infoOverlay)
@@ -55,7 +57,7 @@ namespace armarx
         }
 
     private:
-        Ui::MatrixDisplayWidget *ui;
+        Ui::MatrixDisplayWidget* ui;
         MatrixXf data;
         float min, max;
         std::valarray<QColor> colors;
diff --git a/source/RobotAPI/gui-plugins/KinematicUnitPlugin/CMakeLists.txt b/source/RobotAPI/gui-plugins/KinematicUnitPlugin/CMakeLists.txt
index e901507cfff19d9c499ce4eec8fc097485364bfb..bb44103a45f2fdce5cf3e469399f0b907576cd1b 100644
--- a/source/RobotAPI/gui-plugins/KinematicUnitPlugin/CMakeLists.txt
+++ b/source/RobotAPI/gui-plugins/KinematicUnitPlugin/CMakeLists.txt
@@ -38,9 +38,9 @@ set(GUI_UIS
 
 set(COMPONENT_LIBS RobotAPIUnits DebugDrawer ${Simox_LIBRARIES})
 
-set(LIB_VERSION    0.1.0)
-set(LIB_SOVERSION  0)
+
+
 
 if (ArmarXGui_FOUND)
-	armarx_gui_library(KinematicUnitGuiPlugin "${SOURCES}" "${GUI_MOC_HDRS}" "${GUI_UIS}" "" "${COMPONENT_LIBS}" "${LIB_VERSION}" "${LIB_SOVERSION}")
+	armarx_gui_library(KinematicUnitGuiPlugin "${SOURCES}" "${GUI_MOC_HDRS}" "${GUI_UIS}" "" "${COMPONENT_LIBS}" )
 endif()
diff --git a/source/RobotAPI/gui-plugins/KinematicUnitPlugin/KinematicUnitConfigDialog.cpp b/source/RobotAPI/gui-plugins/KinematicUnitPlugin/KinematicUnitConfigDialog.cpp
index 4b0c7d6209d149221a18abc78d882bfd769ea56b..80817194c02ed3b42a3d0b7e21a16293bc45348e 100644
--- a/source/RobotAPI/gui-plugins/KinematicUnitPlugin/KinematicUnitConfigDialog.cpp
+++ b/source/RobotAPI/gui-plugins/KinematicUnitPlugin/KinematicUnitConfigDialog.cpp
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::
 * @author     Mirko Waechter ( mirko.waechter at kit dot edu)
 * @date       2012
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -34,11 +33,11 @@
 
 #include <IceUtil/UUID.h>
 
-#include <Gui/libraries/ArmarXGuiBase/widgets/IceProxyFinder.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/widgets/IceProxyFinder.h>
 
 using namespace armarx;
 
-KinematicUnitConfigDialog::KinematicUnitConfigDialog(QWidget *parent) :
+KinematicUnitConfigDialog::KinematicUnitConfigDialog(QWidget* parent) :
     QDialog(parent),
     ui(new Ui::KinematicUnitConfigDialog),
     uuid(IceUtil::generateUUID())
@@ -49,18 +48,18 @@ KinematicUnitConfigDialog::KinematicUnitConfigDialog(QWidget *parent) :
     fileDialog->setFileMode(QFileDialog::ExistingFiles);
     QStringList fileTypes;
     fileTypes << tr("XML (*.xml)")
-        << tr("All Files (*.*)");
+              << tr("All Files (*.*)");
     fileDialog->setNameFilters(fileTypes);
     connect(ui->btnSelectModelFile, SIGNAL(clicked()), fileDialog, SLOT(show()));
     connect(fileDialog, SIGNAL(accepted()), this, SLOT(modelFileSelected()));
     connect(this->ui->buttonBox, SIGNAL(accepted()), this, SLOT(verifyConfig()));
-    ui->buttonBox->button( QDialogButtonBox::Ok )->setDefault(true);
+    ui->buttonBox->button(QDialogButtonBox::Ok)->setDefault(true);
     proxyFinder = new IceProxyFinder<KinematicUnitInterfacePrx>(this);
-    proxyFinder->setSearchMask("*Unit");
-    ui->gridLayout->addWidget(proxyFinder, 2,1,1,2);
+    proxyFinder->setSearchMask("*");
+    ui->gridLayout->addWidget(proxyFinder, 2, 1, 1, 2);
     topicFinder = new IceTopicFinder(this);
     topicFinder->setSearchMask("*RobotState");
-    ui->gridLayout->addWidget(topicFinder, 3,1,1,2);
+    ui->gridLayout->addWidget(topicFinder, 3, 1, 1, 2);
 
 }
 
@@ -95,14 +94,18 @@ void KinematicUnitConfigDialog::modelFileSelected()
 
 void KinematicUnitConfigDialog::verifyConfig()
 {
-    if(proxyFinder->getSelectedProxyName().trimmed().length() == 0)
+    if (proxyFinder->getSelectedProxyName().trimmed().length() == 0)
     {
         QMessageBox::critical(this, "Invalid Configuration", "The proxy name must not be empty");
     }
-    else if(topicFinder->getSelectedProxyName().trimmed().length() == 0)
+    else if (topicFinder->getSelectedProxyName().trimmed().length() == 0)
+    {
         QMessageBox::critical(this, "Invalid Configuration", "The topic name must not be empty");
+    }
     else
+    {
         this->accept();
+    }
 }
 
 
diff --git a/source/RobotAPI/gui-plugins/KinematicUnitPlugin/KinematicUnitConfigDialog.h b/source/RobotAPI/gui-plugins/KinematicUnitPlugin/KinematicUnitConfigDialog.h
index 59fdf584f1285a3ad0905322fab7c3d47377ed82..a6990bacf5483eea1b60311a1aff04bae05fecf3 100644
--- a/source/RobotAPI/gui-plugins/KinematicUnitPlugin/KinematicUnitConfigDialog.h
+++ b/source/RobotAPI/gui-plugins/KinematicUnitPlugin/KinematicUnitConfigDialog.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::
 * @author     Mirko Waechter ( mirko.waechter at kit dot edu)
 * @date       2012
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -27,16 +26,18 @@
 #include <QDialog>
 #include <QFileDialog>
 
-#include <Core/core/services/tasks/RunningTask.h>
-#include <Core/core/IceManager.h>
-#include <Core/core/ManagedIceObject.h>
-#include <Gui/libraries/ArmarXGuiBase/widgets/IceProxyFinder.h>
+#include <ArmarXCore/core/services/tasks/RunningTask.h>
+#include <ArmarXCore/core/IceManager.h>
+#include <ArmarXCore/core/ManagedIceObject.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/widgets/IceProxyFinder.h>
 
-namespace Ui {
+namespace Ui
+{
     class KinematicUnitConfigDialog;
 }
 
-namespace armarx{
+namespace armarx
+{
     class KinematicUnitConfigDialog :
         public QDialog,
         virtual public ManagedIceObject
@@ -44,11 +45,14 @@ namespace armarx{
         Q_OBJECT
 
     public:
-        explicit KinematicUnitConfigDialog(QWidget *parent = 0);
+        explicit KinematicUnitConfigDialog(QWidget* parent = 0);
         ~KinematicUnitConfigDialog();
 
         // inherited from ManagedIceObject
-        std::string getDefaultName() const { return "KinematicUnitConfigDialog" + uuid;}
+        std::string getDefaultName() const
+        {
+            return "KinematicUnitConfigDialog" + uuid;
+        }
         void onInitComponent();
         void onConnectComponent();
         void onExitComponent();
@@ -63,7 +67,7 @@ namespace armarx{
 
         IceProxyFinderBase* proxyFinder;
         IceProxyFinderBase* topicFinder;
-        Ui::KinematicUnitConfigDialog *ui;
+        Ui::KinematicUnitConfigDialog* ui;
         QFileDialog* fileDialog;
         std::string uuid;
         friend class KinematicUnitWidgetController;
diff --git a/source/RobotAPI/gui-plugins/KinematicUnitPlugin/KinematicUnitGuiPlugin.cpp b/source/RobotAPI/gui-plugins/KinematicUnitPlugin/KinematicUnitGuiPlugin.cpp
index 0791cf16dd584128744c355a894d996888955641..636b567c2345a9f74b66b1422e80e7c846b7b4fb 100644
--- a/source/RobotAPI/gui-plugins/KinematicUnitPlugin/KinematicUnitGuiPlugin.cpp
+++ b/source/RobotAPI/gui-plugins/KinematicUnitPlugin/KinematicUnitGuiPlugin.cpp
@@ -3,9 +3,10 @@
 
 #include <RobotAPI/gui-plugins/KinematicUnitPlugin/ui_KinematicUnitConfigDialog.h>
 
-#include <Core/core/system/ArmarXDataPath.h>
-#include <Core/core/ArmarXObjectScheduler.h>
-#include <Core/core/ArmarXManager.h>
+#include <ArmarXCore/core/system/cmake/CMakePackageFinder.h>
+#include <ArmarXCore/core/system/ArmarXDataPath.h>
+#include <ArmarXCore/core/ArmarXObjectScheduler.h>
+#include <ArmarXCore/core/ArmarXManager.h>
 
 #include <VirtualRobot/XML/RobotIO.h>
 
@@ -33,6 +34,10 @@
 #include <boost/filesystem.hpp>
 
 
+#define KINEMATIC_UNIT_FILE_DEFAULT std::string("RobotAPI/robots/Armar3/ArmarIII.xml")
+#define KINEMATIC_UNIT_FILE_DEFAULT_PACKAGE std::string("RobotAPI")
+#define KINEMATIC_UNIT_NAME_DEFAULT "Robot"
+#define TOPIC_NAME_DEFAULT "RobotState"
 
 using namespace armarx;
 using namespace VirtualRobot;
@@ -44,7 +49,6 @@ KinematicUnitGuiPlugin::KinematicUnitGuiPlugin()
     addWidget<KinematicUnitWidgetController>();
 }
 
-
 KinematicUnitWidgetController::KinematicUnitWidgetController() :
     kinematicUnitNode(nullptr),
     selectedControlMode(ePositionControl)
@@ -59,17 +63,16 @@ KinematicUnitWidgetController::KinematicUnitWidgetController() :
     ui.tableJointList->setItemDelegateForColumn(eTabelColumnAngleProgressbar, &delegate);
 }
 
-
 void KinematicUnitWidgetController::onInitComponent()
 {
-    dirty_squaresum_old.resize(5,0);
+    dirty_squaresum_old.resize(5, 0);
     ARMARX_INFO << flush;
     verbose = true;
 
-//    // parsing properties from ice config
-//    kinematicUnitFile = getProperty<std::string>("RobotFileName").getValue();
-//    robotNodeSetName = getProperty<std::string>("RobotNodeSetName").getValue();
-//    kinematicUnitName = getProperty<std::string>("KinematicUnitName").getValue();
+    //    // parsing properties from ice config
+    //    kinematicUnitFile = getProperty<std::string>("RobotFileName").getValue();
+    //    robotNodeSetName = getProperty<std::string>("RobotNodeSetName").getValue();
+    //    kinematicUnitName = getProperty<std::string>("KinematicUnitName").getValue();
 
     ARMARX_INFO << "RobotFileName: " << kinematicUnitFile << flush;
     ARMARX_INFO << "RobotNodeSetName: " << robotNodeSetName << flush;
@@ -79,11 +82,16 @@ void KinematicUnitWidgetController::onInitComponent()
 
     // init
     robot = loadRobotFile(kinematicUnitFile);
-    if(!robot)
+
+    if (!robot)
     {
         getObjectScheduler()->terminate();
-        if(getWidget()->parentWidget())
+
+        if (getWidget()->parentWidget())
+        {
             getWidget()->parentWidget()->close();
+        }
+
         std::cout << "returning" << std::endl;
         return;
     }
@@ -97,7 +105,7 @@ void KinematicUnitWidgetController::onInitComponent()
 
     robotNodeSet = getRobotNodeSet(robot, robotNodeSetName);
 
-    if(!robotNodeSet)
+    if (!robotNodeSet)
     {
         ARMARX_ERROR << "Failed to obtain RobotNodeSet '" << robotNodeSetName << "'";
     }
@@ -105,13 +113,18 @@ void KinematicUnitWidgetController::onInitComponent()
     // create the debugdrawer component
     std::string debugDrawerComponentName = "KinemticUnitGUIDebugDrawer_" + getName();
     ARMARX_INFO << "Creating component " << debugDrawerComponentName;
-    debugDrawer = Component::create<DebugDrawerComponent>(properties,debugDrawerComponentName);
+    debugDrawer = Component::create<DebugDrawerComponent>(properties, debugDrawerComponentName);
+
     if (mutex3D)
     {
         //ARMARX_IMPORTANT << "mutex3d:" << mutex3D.get();
         debugDrawer->setMutex(mutex3D);
-    } else
+    }
+    else
+    {
         ARMARX_ERROR << " No 3d mutex available...";
+    }
+
     ArmarXManagerPtr m = getArmarXManager();
     m->addObject(debugDrawer, false);
 
@@ -138,8 +151,11 @@ void KinematicUnitWidgetController::onInitComponent()
 
 void KinematicUnitWidgetController::onConnectComponent()
 {
-    if(!robot)
+    if (!robot)
+    {
         return;
+    }
+
     ARMARX_INFO << flush;
 
     // get proxy to send commands to the kinematic unit
@@ -176,45 +192,60 @@ void KinematicUnitWidgetController::onExitComponent()
         }
     }
 
-/*
-    if (debugDrawer && debugDrawer->getObjectScheduler())
-    {
-        ARMARX_INFO << "Removing DebugDrawer component...";
-        debugDrawer->getObjectScheduler()->terminate();
-        ARMARX_INFO << "Removing DebugDrawer component...done";
-    }
-*/
+    /*
+        if (debugDrawer && debugDrawer->getObjectScheduler())
+        {
+            ARMARX_INFO << "Removing DebugDrawer component...";
+            debugDrawer->getObjectScheduler()->terminate();
+            ARMARX_INFO << "Removing DebugDrawer component...done";
+        }
+    */
 }
 
 QPointer<QDialog> KinematicUnitWidgetController::getConfigDialog(QWidget* parent)
 {
-    if(!dialog)
+    if (!dialog)
     {
         dialog = new KinematicUnitConfigDialog(parent);
         dialog->setName(dialog->getDefaultName());
-        boost::filesystem::path dir(KINEMATIC_UNIT_FILE_DEFAULT);
+
+        armarx::CMakePackageFinder finder(KINEMATIC_UNIT_FILE_DEFAULT_PACKAGE);
+
+        if (!finder.packageFound())
+        {
+            ARMARX_WARNING << "ArmarX Package " << KINEMATIC_UNIT_FILE_DEFAULT_PACKAGE << " has not been found!";
+        }
+        else
+        {
+            ARMARX_INFO << "Adding to datapaths: " << finder.getDataDir();
+            armarx::ArmarXDataPath::addDataPaths(finder.getDataDir());
+        }
+
+        std::string filename =  KINEMATIC_UNIT_FILE_DEFAULT;
+        ArmarXDataPath::getAbsolutePath(filename, filename);
+
+        boost::filesystem::path dir(filename);
+
 
         dialog->fileDialog->setDirectory(QString::fromStdString(dir.remove_filename().string()));
-        dialog->ui->editRobotFilepath->setText(QString::fromStdString(KINEMATIC_UNIT_FILE_DEFAULT));
+        dialog->ui->editRobotFilepath->setText(QString::fromStdString(filename));
         dialog->ui->ediRobotNodeSetName->setText(KINEMATIC_UNIT_NAME_DEFAULT);
 
     }
+
     return qobject_cast<KinematicUnitConfigDialog*>(dialog);
 }
 
+void KinematicUnitWidgetController::configured()
+{
+    ARMARX_VERBOSE << "KinematicUnitWidget::configured()";
+    kinematicUnitFile = dialog->ui->editRobotFilepath->text().toStdString();
+    robotNodeSetName = dialog->ui->ediRobotNodeSetName->text().toStdString();
+    kinematicUnitName = dialog->proxyFinder->getSelectedProxyName().toStdString();
+    topicName = dialog->topicFinder->getSelectedProxyName().toStdString();
+}
 
-
- void KinematicUnitWidgetController::configured()
- {
-     ARMARX_VERBOSE << "KinematicUnitWidget::configured()";
-     kinematicUnitFile = dialog->ui->editRobotFilepath->text().toStdString();
-     robotNodeSetName = dialog->ui->ediRobotNodeSetName->text().toStdString();
-     kinematicUnitName = dialog->proxyFinder->getSelectedProxyName().toStdString();
-     topicName = dialog->topicFinder->getSelectedProxyName().toStdString();
- }
-
-
-void KinematicUnitWidgetController::loadSettings(QSettings *settings)
+void KinematicUnitWidgetController::loadSettings(QSettings* settings)
 {
     kinematicUnitFile = settings->value("kinematicUnitFile", QString::fromStdString(KINEMATIC_UNIT_FILE_DEFAULT)).toString().toStdString();
     ArmarXDataPath::getAbsolutePath(kinematicUnitFile, kinematicUnitFile);
@@ -223,13 +254,15 @@ void KinematicUnitWidgetController::loadSettings(QSettings *settings)
     topicName = settings->value("topicName", TOPIC_NAME_DEFAULT).toString().toStdString();
 }
 
-void KinematicUnitWidgetController::saveSettings(QSettings *settings)
+void KinematicUnitWidgetController::saveSettings(QSettings* settings)
 {
     std::string robFile = kinematicUnitFile;
+
     try
     {
         robFile = ArmarXDataPath::getRelativeArmarXPath(robFile);
-    } catch (...)
+    }
+    catch (...)
     {
         ARMARX_WARNING << "Could not get relative filename, using full filename:" << robFile;
     }
@@ -245,7 +278,7 @@ void KinematicUnitWidgetController::showVisuLayers(bool show)
 {
     if (debugDrawer)
     {
-        if(show)
+        if (show)
         {
             debugDrawer->enableAllLayers();
         }
@@ -253,7 +286,7 @@ void KinematicUnitWidgetController::showVisuLayers(bool show)
         {
             debugDrawer->disableAllLayers();
         }
-     }
+    }
 }
 
 void KinematicUnitWidgetController::updateGuiElements()
@@ -263,21 +296,15 @@ void KinematicUnitWidgetController::updateGuiElements()
 
 void KinematicUnitWidgetController::modelUpdateCB()
 {
-
 }
 
-SoNode *KinematicUnitWidgetController::getScene()
+SoNode* KinematicUnitWidgetController::getScene()
 {
-    //if(kinematicUnitNode)
-    //    std::cout << "returning scene=" << kinematicUnitNode->getName() << std::endl;
     return rootVisu;
 }
 
-
-
 void KinematicUnitWidgetController::connectSlots()
 {
-
     connect(ui.pushButtonKinematicUnitPos1,  SIGNAL(clicked()), this, SLOT(kinematicUnitZeroPosition()));
 
     connect(ui.nodeListComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(selectJoint(int)));
@@ -291,12 +318,6 @@ void KinematicUnitWidgetController::connectSlots()
 
     connect(ui.showDebugLayer, SIGNAL(toggled(bool)), this, SLOT(showVisuLayers(bool)), Qt::QueuedConnection);
 
-   /* connect(this, SIGNAL(jointAnglesReported()), this, SLOT(updateJointAnglesTable()), Qt::QueuedConnection);
-    connect(this, SIGNAL(jointVelocitiesReported()), this, SLOT(updateJointVelocitiesTable()), Qt::QueuedConnection);
-    connect(this, SIGNAL(jointTorquesReported()), this, SLOT(updateJointTorquesTable()), Qt::QueuedConnection);
-    connect(this, SIGNAL(jointControlModesReported()), this, SLOT(updateControlModesTable()), Qt::QueuedConnection);
-    connect(this, SIGNAL(jointMotorTemperaturesReported()), this, SLOT(updateJointMotorTemperaturesTable()), Qt::QueuedConnection);
-    */
     connect(this, SIGNAL(jointAnglesReported()), this, SLOT(updateJointAnglesTable()), Qt::QueuedConnection);
     connect(this, SIGNAL(jointVelocitiesReported()), this, SLOT(updateJointVelocitiesTable()), Qt::QueuedConnection);
     connect(this, SIGNAL(jointTorquesReported()), this, SLOT(updateJointTorquesTable()), Qt::QueuedConnection);
@@ -305,8 +326,7 @@ void KinematicUnitWidgetController::connectSlots()
     connect(this, SIGNAL(jointMotorTemperaturesReported()), this, SLOT(updateJointMotorTemperaturesTable()), Qt::QueuedConnection);
     connect(this, SIGNAL(jointStatusesReported()), this, SLOT(updateJointStatusesTable()), Qt::QueuedConnection);
 
-
-    connect(ui.tableJointList, SIGNAL(cellDoubleClicked(int,int)), this, SLOT(selectJointFromTableWidget(int,int)), Qt::QueuedConnection);
+    connect(ui.tableJointList, SIGNAL(cellDoubleClicked(int, int)), this, SLOT(selectJointFromTableWidget(int, int)), Qt::QueuedConnection);
 }
 
 void KinematicUnitWidgetController::initializeUi()
@@ -319,7 +339,7 @@ void KinematicUnitWidgetController::initializeUi()
 
 void KinematicUnitWidgetController::kinematicUnitZeroPosition()
 {
-    if(!robotNodeSet)
+    if (!robotNodeSet)
     {
         return;
     }
@@ -328,16 +348,18 @@ void KinematicUnitWidgetController::kinematicUnitZeroPosition()
     std::vector< RobotNodePtr > rn = robotNodeSet->getAllRobotNodes();
     NameValueMap jointAngles;
     NameControlModeMap jointModes;
-    for (unsigned int i=0;i<rn.size();i++)
+
+    for (unsigned int i = 0; i < rn.size(); i++)
     {
         jointModes[rn[i]->getName()] = ePositionControl;
-        jointAngles[rn[i]->getName()]=0.0f;
+        jointAngles[rn[i]->getName()] = 0.0f;
     }
+
     kinematicUnitInterfacePrx->switchControlMode(jointModes);
     kinematicUnitInterfacePrx->setJointAngles(jointAngles);
 
     //set slider to 0 if position control mode is used
-    if(selectedControlMode == ePositionControl)
+    if (selectedControlMode == ePositionControl)
     {
         ui.horizontalSliderKinematicUnitPos->setSliderPosition(SLIDER_ZERO_POSITION);
     }
@@ -355,34 +377,43 @@ void KinematicUnitWidgetController::setControlModePosition()
 {
     NameControlModeMap jointModes;
     selectedControlMode = ePositionControl;
+
     if (currentNode)
     {
         jointModes[currentNode->getName()] = ePositionControl;
 
-
-
         if (kinematicUnitInterfacePrx)
+        {
             kinematicUnitInterfacePrx->switchControlMode(jointModes);
+        }
 
         float lo = currentNode->getJointLimitLo() * 180.0 / M_PI;
         float hi = currentNode->getJointLimitHi() * 180.0 / M_PI;
-        if (hi-lo <= 0.0f)
+
+        if (hi - lo <= 0.0f)
+        {
             return;
+        }
+
         float pos = currentNode->getJointValue() * 180.0 / M_PI;
         ARMARX_INFO << "setting position control for current Node Name: " << currentNode->getName() << " with current value: " << pos;
-    //    ARMARX_INFO << "current joint position of " << currentNode->getName() << ": " << pos;
+
+        // Setting the slider position to pos will set the position to the slider tick closest to pos
+        // This will initially send a position target with a small delta to the joint.
+        ui.horizontalSliderKinematicUnitPos->blockSignals(true);
+
         ui.horizontalSliderKinematicUnitPos->setMaximum(hi);
         ui.horizontalSliderKinematicUnitPos->setMinimum(lo);
-    //        float ticks = (float)(ui.horizontalSliderKinematicUnitPos->maximum() - ui.horizontalSliderKinematicUnitPos->minimum()+1);
-    //        float posT = (pos-lo) / (hi-lo) * ticks + (float)ui.horizontalSliderKinematicUnitPos->minimum();
         ui.horizontalSliderKinematicUnitPos->setSliderPosition((int)(pos));
-    }
 
+        ui.horizontalSliderKinematicUnitPos->blockSignals(false);
+    }
 }
 
 void KinematicUnitWidgetController::setControlModeVelocity()
 {
     NameControlModeMap jointModes;
+
     if (currentNode)
     {
         jointModes[currentNode->getName()] = eVelocityControl;
@@ -392,16 +423,20 @@ void KinematicUnitWidgetController::setControlModeVelocity()
         ui.horizontalSliderKinematicUnitPos->setMinimum(-90);
 
         if (kinematicUnitInterfacePrx)
+        {
             kinematicUnitInterfacePrx->switchControlMode(jointModes);
+        }
 
         selectedControlMode = eVelocityControl;
     }
+
     resetSliderInVelocityControl();
 }
 
 void KinematicUnitWidgetController::setControlModeTorque()
 {
     NameControlModeMap jointModes;
+
     if (currentNode)
     {
         jointModes[currentNode->getName()] = eTorqueControl;
@@ -410,8 +445,11 @@ void KinematicUnitWidgetController::setControlModeTorque()
         ARMARX_INFO << "setting torque control for current Node Name: " << currentNode->getName() << flush;
 
         if (kinematicUnitInterfacePrx)
+        {
             kinematicUnitInterfacePrx->switchControlMode(jointModes);
+        }
     }
+
     selectedControlMode = eTorqueControl;
 }
 
@@ -420,13 +458,17 @@ VirtualRobot::RobotPtr KinematicUnitWidgetController::loadRobotFile(std::string
     VirtualRobot::RobotPtr robot;
 
     if (verbose)
+    {
         ARMARX_INFO << "Loading KinematicUnit " << kinematicUnitName << " from " << kinematicUnitFile << " ..." << flush;
+    }
 
-    if (!ArmarXDataPath::getAbsolutePath(fileName,fileName))
+    if (!ArmarXDataPath::getAbsolutePath(fileName, fileName))
     {
-       ARMARX_INFO << "Could not find Robot XML file with name " << fileName << flush;
+        ARMARX_INFO << "Could not find Robot XML file with name " << fileName << flush;
     }
+
     robot = RobotIO::loadRobot(fileName);
+
     if (!robot)
     {
         ARMARX_INFO << "Could not find Robot XML file with name " << fileName << "(" << kinematicUnitName << ")" << flush;
@@ -467,6 +509,7 @@ VirtualRobot::RobotNodeSetPtr KinematicUnitWidgetController::getRobotNodeSet(Vir
 
         }
     }
+
     return nodeSetPtr;
 }
 
@@ -478,17 +521,20 @@ bool KinematicUnitWidgetController::initGUIComboBox(VirtualRobot::RobotNodeSetPt
     if (robotNodeSet)
     {
         std::vector< RobotNodePtr > rn = robotNodeSet->getAllRobotNodes();
-        for (unsigned int i=0;i<rn.size();i++)
+
+        for (unsigned int i = 0; i < rn.size(); i++)
         {
             //            ARMARX_INFO << "adding item to joint combo box" << rn[i]->getName() << flush;
             QString name(rn[i]->getName().c_str());
             ui.nodeListComboBox->addItem(name);
         }
+
         selectJoint(0);
         ui.nodeListComboBox->setCurrentIndex(0);
 
         return true;
     }
+
     return false;
 }
 
@@ -536,22 +582,22 @@ bool KinematicUnitWidgetController::initGUIJointListTable(VirtualRobot::RobotNod
 
 
         // fill in joint names
-        for (unsigned int i=0;i<rn.size();i++)
+        for (unsigned int i = 0; i < rn.size(); i++)
         {
             //         ARMARX_INFO << "adding item to joint table" << rn[i]->getName() << flush;
             QString name(rn[i]->getName().c_str());
 
-            QTableWidgetItem *newItem = new QTableWidgetItem(name);
+            QTableWidgetItem* newItem = new QTableWidgetItem(name);
             ui.tableJointList->setItem(i, eTabelColumnName, newItem);
         }
 
         // init missing table fields with default values
-        for (unsigned int i=0;i<rn.size();i++)
+        for (unsigned int i = 0; i < rn.size(); i++)
         {
-            for (unsigned int j=1;j<numberOfColumns;j++)
+            for (unsigned int j = 1; j < numberOfColumns; j++)
             {
                 QString state = "--";
-                QTableWidgetItem *newItem = new QTableWidgetItem(state);
+                QTableWidgetItem* newItem = new QTableWidgetItem(state);
                 ui.tableJointList->setItem(i, j, newItem);
             }
         }
@@ -559,13 +605,14 @@ bool KinematicUnitWidgetController::initGUIJointListTable(VirtualRobot::RobotNod
         //hide columns Operation, Error, Enabled and Emergency Stop
         //they will be shown when changes occur
         // TODO: for some reason the columns are not hidden
-        ui.tableJointList->setColumnHidden(eTabelColumnOperation,true);
-        ui.tableJointList->setColumnHidden(eTabelColumnError ,true);
-        ui.tableJointList->setColumnHidden(eTabelColumnEnabled ,true);
-        ui.tableJointList->setColumnHidden(eTabelColumnEmergencyStop ,true);
+        ui.tableJointList->setColumnHidden(eTabelColumnOperation, true);
+        ui.tableJointList->setColumnHidden(eTabelColumnError , true);
+        ui.tableJointList->setColumnHidden(eTabelColumnEnabled , true);
+        ui.tableJointList->setColumnHidden(eTabelColumnEmergencyStop , true);
 
         return true;
     }
+
     return false;
 }
 
@@ -573,19 +620,23 @@ bool KinematicUnitWidgetController::initGUIJointListTable(VirtualRobot::RobotNod
 void KinematicUnitWidgetController::selectJoint(int i)
 {
     boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
-    if (!robotNodeSet || i<0 || i>=(int)robotNodeSet->getSize())
+
+    if (!robotNodeSet || i < 0 || i >= (int)robotNodeSet->getSize())
+    {
         return;
+    }
 
     currentNode = robotNodeSet->getAllRobotNodes()[i];
+
     /*
     //ui.lcdNumberKinematicUnitJointValue->display(pos*180.0f/(float)M_PI);
     ui.lcdNumberKinematicUnitJointValue->display(posT);
     */
-    if(selectedControlMode == ePositionControl)
+    if (selectedControlMode == ePositionControl)
     {
         setControlModePosition();
     }
-    else if(selectedControlMode == eVelocityControl)
+    else if (selectedControlMode == eVelocityControl)
     {
         ui.horizontalSliderKinematicUnitPos->setMaximum(60);
         ui.horizontalSliderKinematicUnitPos->setMinimum(-60);
@@ -593,38 +644,40 @@ void KinematicUnitWidgetController::selectJoint(int i)
         setControlModeVelocity();
         ui.horizontalSliderKinematicUnitPos->setSliderPosition(SLIDER_ZERO_POSITION);
     }
-    else if(selectedControlMode == eTorqueControl)
+    else if (selectedControlMode == eTorqueControl)
     {
         ui.horizontalSliderKinematicUnitPos->setMaximum(60);
         ui.horizontalSliderKinematicUnitPos->setMinimum(-60);
         setControlModeTorque();
         ui.horizontalSliderKinematicUnitPos->setSliderPosition(SLIDER_ZERO_POSITION);
     }
-
 }
 
 void KinematicUnitWidgetController::selectJointFromTableWidget(int row, int column)
 {
-    if(column == eTabelColumnName)
+    if (column == eTabelColumnName)
     {
         ui.nodeListComboBox->setCurrentIndex(row);
-//        selectJoint(row);
+        //        selectJoint(row);
     }
 }
 
 void KinematicUnitWidgetController::sliderValueChanged(int pos)
 {
     boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
+
     if (!currentNode)
+    {
         return;
+    }
 
-//    float ticks = static_cast<float>(ui.horizontalSliderKinematicUnitPos->maximum() - ui.horizontalSliderKinematicUnitPos->minimum()+1);
+    //    float ticks = static_cast<float>(ui.horizontalSliderKinematicUnitPos->maximum() - ui.horizontalSliderKinematicUnitPos->minimum()+1);
     float value = static_cast<float>(ui.horizontalSliderKinematicUnitPos->value());
-//    float perc = (value - static_cast<float>(ui.horizontalSliderKinematicUnitPos->minimum())) / ticks;
+    //    float perc = (value - static_cast<float>(ui.horizontalSliderKinematicUnitPos->minimum())) / ticks;
 
-//    NameControlModeMap::const_iterator it;
-//    it = reportedJointControlModes.find(currentNode->getName());
-//    const ControlMode currentControlMode = it->second;
+    //    NameControlModeMap::const_iterator it;
+    //    it = reportedJointControlModes.find(currentNode->getName());
+    //    const ControlMode currentControlMode = it->second;
     const ControlMode currentControlMode = selectedControlMode;
 
     if (currentControlMode == ePositionControl)
@@ -633,11 +686,11 @@ void KinematicUnitWidgetController::sliderValueChanged(int pos)
         //float lo = currentNode->getJointLimitLo();
         //float hi = currentNode->getJointLimitHi();
         //float result = lo + (hi-lo)*perc;
-
+        //jointAngles[currentNode->getName()] = (perc - 0.5) * 2 * M_PI;
 
         NameValueMap jointAngles;
-//        jointAngles[currentNode->getName()] = (perc - 0.5) * 2 * M_PI;
         jointAngles[currentNode->getName()] = value / 180.0 * M_PI;
+
         if (kinematicUnitInterfacePrx)
         {
             kinematicUnitInterfacePrx->setJointAngles(jointAngles);
@@ -648,16 +701,18 @@ void KinematicUnitWidgetController::sliderValueChanged(int pos)
     {
         NameValueMap jointVelocities;
         jointVelocities[currentNode->getName()] = value / 180.0 * M_PI;;
+
         if (kinematicUnitInterfacePrx)
         {
             kinematicUnitInterfacePrx->setJointVelocities(jointVelocities);
             updateModel();
         }
     }
-    else if(currentControlMode == eTorqueControl)
+    else if (currentControlMode == eTorqueControl)
     {
         NameValueMap jointTorques;
-        jointTorques[currentNode->getName()] = value/10.0f;
+        jointTorques[currentNode->getName()] = value / 10.0f;
+
         if (kinematicUnitInterfacePrx)
         {
             kinematicUnitInterfacePrx->setJointTorques(jointTorques);
@@ -674,19 +729,24 @@ void KinematicUnitWidgetController::sliderValueChanged(int pos)
 
 void KinematicUnitWidgetController::updateControlModesTable()
 {
-    if(!getWidget() || !robotNodeSet)
+    if (!getWidget() || !robotNodeSet)
+    {
         return;
+    }
 
     boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
     std::vector< RobotNodePtr > rn = robotNodeSet->getAllRobotNodes();
+
     for (unsigned int i = 0; i < rn.size(); i++)
     {
         NameControlModeMap::const_iterator it;
         it = reportedJointControlModes.find(rn[i]->getName());
         QString state;
 
-        if (it==reportedJointControlModes.end())
+        if (it == reportedJointControlModes.end())
+        {
             state = "unknown";
+        }
         else
         {
             ControlMode currentMode = it->second;
@@ -694,14 +754,14 @@ void KinematicUnitWidgetController::updateControlModesTable()
 
             switch (currentMode)
             {
-                /*case eNoMode:
-                    state = "None";
-                    break;
-
-                case eUnknownMode:
-                    state = "Unknown";
-                    break;
-                */
+                    /*case eNoMode:
+                        state = "None";
+                        break;
+
+                    case eUnknownMode:
+                        state = "Unknown";
+                        break;
+                    */
                 case eDisabled:
                     state = "Disabled";
                     break;
@@ -734,18 +794,21 @@ void KinematicUnitWidgetController::updateControlModesTable()
             }
         }
 
-        QTableWidgetItem *newItem = new QTableWidgetItem(state);
+        QTableWidgetItem* newItem = new QTableWidgetItem(state);
         ui.tableJointList->setItem(i, eTabelColumnControlMode, newItem);
     }
 }
 
 void KinematicUnitWidgetController::updateJointStatusesTable()
 {
-    if(!getWidget() || !robotNodeSet)
+    if (!getWidget() || !robotNodeSet)
+    {
         return;
+    }
 
     boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
     std::vector< RobotNodePtr > rn = robotNodeSet->getAllRobotNodes();
+
     for (unsigned int i = 0; i < rn.size(); i++)
     {
         NameStatusMap::const_iterator it;
@@ -753,32 +816,33 @@ void KinematicUnitWidgetController::updateJointStatusesTable()
         JointStatus currentStatus = it->second;
 
         QString state = translateStatus(currentStatus.operation);
-        QTableWidgetItem *newItem = new QTableWidgetItem(state);
+        QTableWidgetItem* newItem = new QTableWidgetItem(state);
         ui.tableJointList->setItem(i, eTabelColumnOperation, newItem);
 
         state = translateStatus(currentStatus.error);
         newItem = new QTableWidgetItem(state);
         ui.tableJointList->setItem(i, eTabelColumnError, newItem);
 
-        state = currentStatus.enabled? "X" : "-";
+        state = currentStatus.enabled ? "X" : "-";
         newItem = new QTableWidgetItem(state);
         ui.tableJointList->setItem(i, eTabelColumnEnabled, newItem);
 
-        state = currentStatus.emergencyStop? "X" : "-";
+        state = currentStatus.emergencyStop ? "X" : "-";
         newItem = new QTableWidgetItem(state);
         ui.tableJointList->setItem(i, eTabelColumnEmergencyStop, newItem);
     }
+
     //show columns
 
-    ui.tableJointList->setColumnHidden(eTabelColumnOperation,false);
-    ui.tableJointList->setColumnHidden(eTabelColumnError,false);
-    ui.tableJointList->setColumnHidden(eTabelColumnEnabled,false);
-    ui.tableJointList->setColumnHidden(eTabelColumnEmergencyStop,false);
+    ui.tableJointList->setColumnHidden(eTabelColumnOperation, false);
+    ui.tableJointList->setColumnHidden(eTabelColumnError, false);
+    ui.tableJointList->setColumnHidden(eTabelColumnEnabled, false);
+    ui.tableJointList->setColumnHidden(eTabelColumnEmergencyStop, false);
 }
 
 QString KinematicUnitWidgetController::translateStatus(OperationStatus status)
 {
-    switch(status)
+    switch (status)
     {
         case eOffline:
             return "Offline";
@@ -796,7 +860,7 @@ QString KinematicUnitWidgetController::translateStatus(OperationStatus status)
 
 QString KinematicUnitWidgetController::translateStatus(ErrorStatus status)
 {
-    switch(status)
+    switch (status)
     {
         case eOk:
             return "Ok";
@@ -814,7 +878,7 @@ QString KinematicUnitWidgetController::translateStatus(ErrorStatus status)
 
 void KinematicUnitWidgetController::updateJointAnglesTable()
 {
-    if(!robotNodeSet)
+    if (!robotNodeSet)
     {
         return;
     }
@@ -830,12 +894,14 @@ void KinematicUnitWidgetController::updateJointAnglesTable()
         NameValueMap::const_iterator it;
         RobotNodePtr node = rn[i];
         it = reportedJointAngles.find(node->getName());
-        if(it == reportedJointAngles.end())
+
+        if (it == reportedJointAngles.end())
         {
             continue;
         }
+
         const float currentValue = it->second;
-        dirty_squaresum += currentValue*currentValue;
+        dirty_squaresum += currentValue * currentValue;
 
         QModelIndex index = ui.tableJointList->model()->index(i, eTabelColumnAngleProgressbar);
 
@@ -849,33 +915,41 @@ void KinematicUnitWidgetController::updateJointAnglesTable()
     {
         updateModel();
         dirty_squaresum_old[0] = dirty_squaresum;
-//        ARMARX_INFO << "update model" << flush;
+        //        ARMARX_INFO << "update model" << flush;
     }
 }
 
-void KinematicUnitWidgetController::updateJointVelocitiesTable(){
-    if(!getWidget() || !robotNodeSet)
+void KinematicUnitWidgetController::updateJointVelocitiesTable()
+{
+    if (!getWidget() || !robotNodeSet)
+    {
         return;
+    }
 
     float dirty_squaresum = 0;
     boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
     std::vector< RobotNodePtr > rn = robotNodeSet->getAllRobotNodes();
     QTableWidgetItem* newItem;
+
     for (unsigned int i = 0; i < rn.size(); i++)
     {
         NameValueMap::const_iterator it;
         it = reportedJointVelocities.find(rn[i]->getName());
-        if(it == reportedJointVelocities.end())
+
+        if (it == reportedJointVelocities.end())
         {
             continue;
         }
+
         const float currentValue = it->second;
-        dirty_squaresum += currentValue*currentValue;
+        dirty_squaresum += currentValue * currentValue;
         const QString Text = QString::number(cutJitter(currentValue));
         newItem = new QTableWidgetItem(Text);
         ui.tableJointList->setItem(i, eTabelColumnVelocity, newItem);
     }
-    if ( (fabs(dirty_squaresum_old[1] - dirty_squaresum)) > 0.0000005)  {
+
+    if ((fabs(dirty_squaresum_old[1] - dirty_squaresum)) > 0.0000005)
+    {
         updateModel();
         dirty_squaresum_old[1] = dirty_squaresum;
     }
@@ -883,8 +957,10 @@ void KinematicUnitWidgetController::updateJointVelocitiesTable(){
 
 void KinematicUnitWidgetController::updateJointTorquesTable()
 {
-    if(!getWidget() || !robotNodeSet)
+    if (!getWidget() || !robotNodeSet)
+    {
         return;
+    }
 
     boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
     std::vector< RobotNodePtr > rn = robotNodeSet->getAllRobotNodes();
@@ -894,7 +970,8 @@ void KinematicUnitWidgetController::updateJointTorquesTable()
     for (unsigned int i = 0; i < rn.size(); i++)
     {
         it = reportedJointTorques.find(rn[i]->getName());
-        if(it == reportedJointTorques.end())
+
+        if (it == reportedJointTorques.end())
         {
             continue;
         }
@@ -907,8 +984,10 @@ void KinematicUnitWidgetController::updateJointTorquesTable()
 
 void KinematicUnitWidgetController::updateJointCurrentsTable()
 {
-    if(!getWidget() || !robotNodeSet)
+    if (!getWidget() || !robotNodeSet)
+    {
         return;
+    }
 
     boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
     std::vector< RobotNodePtr > rn = robotNodeSet->getAllRobotNodes();
@@ -918,7 +997,8 @@ void KinematicUnitWidgetController::updateJointCurrentsTable()
     for (unsigned int i = 0; i < rn.size(); i++)
     {
         it = reportedJointCurrents.find(rn[i]->getName());
-        if(it == reportedJointCurrents.end())
+
+        if (it == reportedJointCurrents.end())
         {
             continue;
         }
@@ -931,8 +1011,10 @@ void KinematicUnitWidgetController::updateJointCurrentsTable()
 
 void KinematicUnitWidgetController::updateJointMotorTemperaturesTable()
 {
-    if(!getWidget() || !robotNodeSet)
+    if (!getWidget() || !robotNodeSet)
+    {
         return;
+    }
 
     boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
     std::vector< RobotNodePtr > rn = robotNodeSet->getAllRobotNodes();
@@ -942,7 +1024,8 @@ void KinematicUnitWidgetController::updateJointMotorTemperaturesTable()
     for (unsigned int i = 0; i < rn.size(); i++)
     {
         it = reportedJointMotorTemperatures.find(rn[i]->getName());
-        if(it == reportedJointMotorTemperatures.end())
+
+        if (it == reportedJointMotorTemperatures.end())
         {
             continue;
         }
@@ -955,8 +1038,10 @@ void KinematicUnitWidgetController::updateJointMotorTemperaturesTable()
 
 void KinematicUnitWidgetController::reportJointAngles(const NameValueMap& jointAngles, bool aValueChanged, const Ice::Current& c)
 {
-    if(!aValueChanged && reportedJointAngles.size() > 0)
+    if (!aValueChanged && reportedJointAngles.size() > 0)
+    {
         return;
+    }
 
     boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
     reportedJointAngles = jointAngles;
@@ -965,8 +1050,10 @@ void KinematicUnitWidgetController::reportJointAngles(const NameValueMap& jointA
 
 void KinematicUnitWidgetController::reportJointVelocities(const NameValueMap& jointVelocities, bool aValueChanged, const Ice::Current& c)
 {
-    if(!aValueChanged && reportedJointVelocities.size() > 0)
+    if (!aValueChanged && reportedJointVelocities.size() > 0)
+    {
         return;
+    }
 
     boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
     reportedJointVelocities = jointVelocities;
@@ -975,8 +1062,10 @@ void KinematicUnitWidgetController::reportJointVelocities(const NameValueMap& jo
 
 void KinematicUnitWidgetController::reportJointTorques(const NameValueMap& jointTorques, bool aValueChanged, const Ice::Current& c)
 {
-    if(!aValueChanged && reportedJointTorques.size() > 0)
+    if (!aValueChanged && reportedJointTorques.size() > 0)
+    {
         return;
+    }
 
     boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
     reportedJointTorques = jointTorques;
@@ -984,19 +1073,20 @@ void KinematicUnitWidgetController::reportJointTorques(const NameValueMap& joint
     emit jointTorquesReported();
 }
 
-void KinematicUnitWidgetController::reportJointAccelerations(const NameValueMap &jointAccelerations, bool aValueChanged, const Ice::Current &c)
+void KinematicUnitWidgetController::reportJointAccelerations(const NameValueMap& jointAccelerations, bool aValueChanged, const Ice::Current& c)
 {
 
 }
 
 void KinematicUnitWidgetController::reportControlModeChanged(const NameControlModeMap& jointModes, bool aValueChanged, const Ice::Current& c)
 {
-//    if(!aValueChanged && reportedJointControlModes.size() > 0)
-//        return;
+    //    if(!aValueChanged && reportedJointControlModes.size() > 0)
+    //        return;
     boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
-    for(auto&e : jointModes)
+
+    for (auto & e : jointModes)
     {
-//        ARMARX_INFO << "Setting jointMode of joint " << e.first << " to " << e.second;
+        //        ARMARX_INFO << "Setting jointMode of joint " << e.first << " to " << e.second;
 
         reportedJointControlModes[e.first] = e.second;
     }
@@ -1006,8 +1096,10 @@ void KinematicUnitWidgetController::reportControlModeChanged(const NameControlMo
 
 void KinematicUnitWidgetController::reportJointCurrents(const NameValueMap& jointCurrents, bool aValueChanged, const Ice::Current& c)
 {
-    if(!aValueChanged && reportedJointCurrents.size() > 0)
+    if (!aValueChanged && reportedJointCurrents.size() > 0)
+    {
         return;
+    }
 
     boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
     reportedJointCurrents = jointCurrents;
@@ -1017,8 +1109,10 @@ void KinematicUnitWidgetController::reportJointCurrents(const NameValueMap& join
 
 void KinematicUnitWidgetController::reportJointMotorTemperatures(const NameValueMap& jointMotorTemperatures, bool aValueChanged,  const Ice::Current& c)
 {
-    if(!aValueChanged && reportedJointMotorTemperatures.size() > 0)
+    if (!aValueChanged && reportedJointMotorTemperatures.size() > 0)
+    {
         return;
+    }
 
     boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
     reportedJointMotorTemperatures = jointMotorTemperatures;
@@ -1026,10 +1120,12 @@ void KinematicUnitWidgetController::reportJointMotorTemperatures(const NameValue
     emit jointMotorTemperaturesReported();
 }
 
-void KinematicUnitWidgetController::reportJointStatuses(const NameStatusMap &jointStatuses, bool aValueChanged, const Ice::Current &)
+void KinematicUnitWidgetController::reportJointStatuses(const NameStatusMap& jointStatuses, bool aValueChanged, const Ice::Current&)
 {
-    if(!aValueChanged && reportedJointStatuses.size() > 0)
+    if (!aValueChanged && reportedJointStatuses.size() > 0)
+    {
         return;
+    }
 
     boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
     reportedJointStatuses = jointStatuses;
@@ -1040,12 +1136,12 @@ void KinematicUnitWidgetController::reportJointStatuses(const NameStatusMap &joi
 
 void KinematicUnitWidgetController::updateModel()
 {
-    if(!robotNodeSet)
+    if (!robotNodeSet)
     {
         return;
     }
 
-//    ARMARX_INFO << "updateModel()" << flush;
+    //    ARMARX_INFO << "updateModel()" << flush;
     boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
     std::vector< RobotNodePtr > rn2 = robotNodeSet->getAllRobotNodes();
 
@@ -1057,12 +1153,14 @@ void KinematicUnitWidgetController::updateModel()
         VirtualRobot::RobotNodePtr node = robot->getRobotNode(rn2[i]->getName());
         NameValueMap::const_iterator it;
         it = reportedJointAngles.find(node->getName());
-        if(it != reportedJointAngles.end())
+
+        if (it != reportedJointAngles.end())
         {
             usedNodes.push_back(node);
             jv.push_back(it->second);
         }
     }
+
     robot->setJointValues(usedNodes, jv);
 }
 
@@ -1071,33 +1169,39 @@ void KinematicUnitWidgetController::setMutex3D(boost::shared_ptr<boost::recursiv
     //ARMARX_IMPORTANT << "KinematicUnitWidgetController controller " << getInstanceName() << ": set mutex " << mutex3D.get();
 
     this->mutex3D = mutex3D;
+
     if (debugDrawer)
+    {
         debugDrawer->setMutex(mutex3D);
+    }
 }
 
 float KinematicUnitWidgetController::cutJitter(float value)
 {
-    return (abs(value)<static_cast<float>(ui.jitterThresholdSpinBox->value()))?0:value;
+    return (abs(value) < static_cast<float>(ui.jitterThresholdSpinBox->value())) ? 0 : value;
 }
 
 
 
-void RangeValueDelegate::paint(QPainter *painter, const QStyleOptionViewItem &option, const QModelIndex &index) const
+void RangeValueDelegate::paint(QPainter* painter, const QStyleOptionViewItem& option, const QModelIndex& index) const
 {
-    if (index.column() == KinematicUnitWidgetController::eTabelColumnAngleProgressbar) {
+    if (index.column() == KinematicUnitWidgetController::eTabelColumnAngleProgressbar)
+    {
         float jointValue = index.data(KinematicUnitWidgetController::eJointAngleRole).toFloat();
-        float loDeg = index.data(KinematicUnitWidgetController::eJointLoRole).toFloat()*180/M_PI;
-        float hiDeg = index.data(KinematicUnitWidgetController::eJointHiRole).toFloat()*180/M_PI;
-        if(hiDeg-loDeg <= 0)
+        float loDeg = index.data(KinematicUnitWidgetController::eJointLoRole).toFloat() * 180 / M_PI;
+        float hiDeg = index.data(KinematicUnitWidgetController::eJointHiRole).toFloat() * 180 / M_PI;
+
+        if (hiDeg - loDeg <= 0)
         {
             QStyledItemDelegate::paint(painter, option, index);
             return;
         }
+
         QStyleOptionProgressBarV2 progressBarOption;
         progressBarOption.rect = option.rect;
         progressBarOption.minimum = loDeg;
         progressBarOption.maximum = hiDeg;
-        progressBarOption.progress = jointValue*180/M_PI;
+        progressBarOption.progress = jointValue * 180 / M_PI;
         progressBarOption.text = QString::number(jointValue);
         progressBarOption.textVisible = true;
         QPalette pal;
@@ -1106,26 +1210,29 @@ void RangeValueDelegate::paint(QPainter *painter, const QStyleOptionViewItem &op
         QApplication::style()->drawControl(QStyle::CE_ProgressBar,
                                            &progressBarOption, painter);
 
-//        QProgressBar renderer;
-//        float progressPercentage = (jointValue*180.0f/M_PI-loDeg)/(hiDeg - loDeg);
-//        ARMARX_INFO_S << VAROUT(progressPercentage);
-//        // Customize style using style-sheet..
-//        QColor color((int)(255*progressPercentage), ((int)(255*(1-progressPercentage))), 0);
-//        QString style = renderer.styleSheet();
-//        style += "QProgressBar::chunk { background-color: " + color.name() + "}";
-//        ARMARX_INFO_S << VAROUT(style);
-//        renderer.resize(option.rect.size());
-//        renderer.setMinimum(loDeg);
-//        renderer.setMaximum(hiDeg);
-//        renderer.setValue(jointValue*180.0f);
-
-//        renderer.setStyleSheet(style);
-//        painter->save();
-//        painter->translate(option.rect.topLeft());
-//        renderer.render(painter);
-//        painter->restore();
-    } else
+        //        QProgressBar renderer;
+        //        float progressPercentage = (jointValue*180.0f/M_PI-loDeg)/(hiDeg - loDeg);
+        //        ARMARX_INFO_S << VAROUT(progressPercentage);
+        //        // Customize style using style-sheet..
+        //        QColor color((int)(255*progressPercentage), ((int)(255*(1-progressPercentage))), 0);
+        //        QString style = renderer.styleSheet();
+        //        style += "QProgressBar::chunk { background-color: " + color.name() + "}";
+        //        ARMARX_INFO_S << VAROUT(style);
+        //        renderer.resize(option.rect.size());
+        //        renderer.setMinimum(loDeg);
+        //        renderer.setMaximum(hiDeg);
+        //        renderer.setValue(jointValue*180.0f);
+
+        //        renderer.setStyleSheet(style);
+        //        painter->save();
+        //        painter->translate(option.rect.topLeft());
+        //        renderer.render(painter);
+        //        painter->restore();
+    }
+    else
+    {
         QStyledItemDelegate::paint(painter, option, index);
+    }
 }
 
 Q_EXPORT_PLUGIN2(robotapi_gui_KinematicUnitGuiPlugin, KinematicUnitGuiPlugin)
diff --git a/source/RobotAPI/gui-plugins/KinematicUnitPlugin/KinematicUnitGuiPlugin.h b/source/RobotAPI/gui-plugins/KinematicUnitPlugin/KinematicUnitGuiPlugin.h
index 721cd4bdd23360c4b67311163c3b7d39074fc603..6c248994f988b044802ef130c7a0cd078217995a 100644
--- a/source/RobotAPI/gui-plugins/KinematicUnitPlugin/KinematicUnitGuiPlugin.h
+++ b/source/RobotAPI/gui-plugins/KinematicUnitPlugin/KinematicUnitGuiPlugin.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::Component::KinematicUnitGuiPlugin
 * @author     Christian Boege <boege at kit dot edu>
 * @copyright  2011 Christian Böge
-* @license    http://www.gnu.org/licenses/gpl.txt
+* @license    http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 
 */
@@ -30,10 +29,10 @@
 #include <RobotAPI/interface/units/KinematicUnitInterface.h>
 #include <RobotAPI/components/DebugDrawer/DebugDrawerComponent.h>
 
-#include <Gui/libraries/ArmarXGuiBase/ArmarXGuiPlugin.h>
-#include <Gui/libraries/ArmarXGuiBase/ArmarXComponentWidgetController.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXGuiPlugin.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXComponentWidgetController.h>
 
-#include <Core/core/Component.h>
+#include <ArmarXCore/core/Component.h>
 
 /* Qt headers */
 #include <QtGui/QMainWindow>
@@ -56,10 +55,6 @@
 #include <boost/shared_ptr.hpp>
 #include <boost/cstdint.hpp>
 
-#define KINEMATIC_UNIT_FILE_DEFAULT armarx::ArmarXDataPath::getHomePath() + std::string("Armar3/data/Armar3/robotmodel/ArmarIII.xml")
-#define KINEMATIC_UNIT_NAME_DEFAULT "Robot"
-#define TOPIC_NAME_DEFAULT "RobotState"
-
 namespace armarx
 {
     typedef boost::shared_ptr<VirtualRobot::CoinVisualization> CoinVisualizationPtr;
@@ -72,7 +67,7 @@ namespace armarx
      \see KinematicUnitWidget
     */
     class KinematicUnitGuiPlugin :
-            public ArmarXGuiPlugin
+        public ArmarXGuiPlugin
     {
     public:
         KinematicUnitGuiPlugin();
@@ -84,37 +79,35 @@ namespace armarx
     };
 
     class RangeValueDelegate :
-            public QStyledItemDelegate
+        public QStyledItemDelegate
     {
-        void paint(QPainter *painter, const QStyleOptionViewItem &option, const QModelIndex &index) const;
+        void paint(QPainter* painter, const QStyleOptionViewItem& option, const QModelIndex& index) const;
     };
 
     /*!
-      \class KinematicUnitWidget
+      \page RobotAPI-GuiPlugins-KinematicUnitPlugin KinematicUnitPlugin
+
       \brief This widget shows position and velocity of all joints. Optionally a 3d robot model can be visualized.
 
       \image html KinematicUnitGUI.png
       When you add the widget to the Gui, you need to specify the following parameters:
-     
+
       Parameter Name   | Example Value     | Required?     | Description
       :----------------  | :-------------:   | :-------------- |:--------------------
       Robot model filepath     | $ArmarX_Core/Armar3/data/Armar3/robotmodel/ArmarIII.xml  | Yes | The robot model to use. This needs to be the same model the kinematic unit is using.
       Robot nodeset name     | Robot          | Yes | ?
-      Kinematic unit name - Proxy | Armar3KinematicUnit | Yes | The kinematic unit you wish to observe/control. 
+      Kinematic unit name - Proxy | Armar3KinematicUnit | Yes | The kinematic unit you wish to observe/control.
       RobotState Topic Name | RobotState | ? | ?
-    
-      This widget allows you to both observe and control a kinematic unit. All joints are listed in 
-      the table in the center of the widget. The 3D viewer shows the current state of the robot. 
+
+      This widget allows you to both observe and control a kinematic unit. All joints are listed in
+      the table in the center of the widget. The 3D viewer shows the current state of the robot.
 
       On the top you can select the joint you wish to control and the control mode. You can control
       a joint with the slider below.
-      
-      \ingroup RobotAPI-ArmarXGuiPlugins ArmarXGuiPlugins
-      \see KinematicUnitGuiPlugin
      */
     class KinematicUnitWidgetController :
-            public ArmarXComponentWidgetController,
-            public KinematicUnitListener
+        public ArmarXComponentWidgetController,
+        public KinematicUnitListener
     {
         Q_OBJECT
     public:
@@ -122,7 +115,7 @@ namespace armarx
          * @brief Holds the column index for the joint tabel.
          * Used to avoid magic numbers.
          */
-        enum JointTabelColumnIndex: int
+        enum JointTabelColumnIndex : int
         {
             eTabelColumnName = 0,
             eTabelColumnControlMode,
@@ -137,7 +130,8 @@ namespace armarx
             eTabelColumnEmergencyStop
         };
 
-        enum Roles {
+        enum Roles
+        {
             eJointAngleRole = Qt::UserRole + 1,
             eJointHiRole,
             eJointLoRole
@@ -152,12 +146,18 @@ namespace armarx
         virtual void onExitComponent();
 
         // inherited of ArmarXWidget
-        virtual QString getWidgetName() const { return "RobotControl.KinematicUnitGUI"; }
-        virtual QIcon getWidgetIcon() const { return QIcon("://icons/kinematic_icon.svg"); }
+        virtual QString getWidgetName() const
+        {
+            return "RobotControl.KinematicUnitGUI";
+        }
+        virtual QIcon getWidgetIcon() const
+        {
+            return QIcon("://icons/kinematic_icon.svg");
+        }
 
         QPointer<QDialog> getConfigDialog(QWidget* parent = 0);
-        virtual void loadSettings(QSettings * settings);
-        virtual void saveSettings(QSettings * settings);
+        virtual void loadSettings(QSettings* settings);
+        virtual void saveSettings(QSettings* settings);
         void configured();
 
         SoNode* getScene();
@@ -249,7 +249,7 @@ namespace armarx
         void reportJointAccelerations(const NameValueMap& jointAccelerations, bool aValueChanged, const Ice::Current& c);
         void reportJointCurrents(const NameValueMap& jointCurrents, bool aValueChanged, const Ice::Current& c);
         void reportJointMotorTemperatures(const NameValueMap& jointMotorTemperatures, bool aValueChanged, const Ice::Current& c);
-        void reportJointStatuses(const NameStatusMap& jointStatuses, bool aValueChanged, const Ice::Current &);
+        void reportJointStatuses(const NameStatusMap& jointStatuses, bool aValueChanged, const Ice::Current&);
 
 
         void updateModel();
@@ -286,8 +286,6 @@ namespace armarx
          */
         static const int SLIDER_ZERO_POSITION = 0;
 
-
-
         /**
          * @brief Returns values in
          * (-ui.jitterThresholdSpinBox->value(),ui.jitterThresholdSpinBox->value())
diff --git a/source/RobotAPI/gui-plugins/PlatformUnitPlugin/CMakeLists.txt b/source/RobotAPI/gui-plugins/PlatformUnitPlugin/CMakeLists.txt
index 14ee4c60b1c6de31ae9080b0dec02e321e666d40..0ef6bf397bea8520d2e10b7497392e3b7c2d612d 100644
--- a/source/RobotAPI/gui-plugins/PlatformUnitPlugin/CMakeLists.txt
+++ b/source/RobotAPI/gui-plugins/PlatformUnitPlugin/CMakeLists.txt
@@ -27,11 +27,11 @@ set(GUI_UIS
     PlatformUnitConfigDialog.ui
 )
 
-set(COMPONENT_LIBS RobotAPIUnits ArmarXInterfaces ${Simox_LIBRARIES})
+set(COMPONENT_LIBS RobotAPIUnits ArmarXCoreInterfaces ${Simox_LIBRARIES})
+
+
 
-set(LIB_VERSION    0.1.0)
-set(LIB_SOVERSION  0)
 
 if (ArmarXGui_FOUND)
-	armarx_gui_library(PlatformUnitGuiPlugin "${SOURCES}" "${GUI_MOC_HDRS}" "${GUI_UIS}" "" "${COMPONENT_LIBS}" "${LIB_VERSION}" "${LIB_SOVERSION}")
+	armarx_gui_library(PlatformUnitGuiPlugin "${SOURCES}" "${GUI_MOC_HDRS}" "${GUI_UIS}" "" "${COMPONENT_LIBS}" )
 endif()
diff --git a/source/RobotAPI/gui-plugins/PlatformUnitPlugin/PlatformUnitConfigDialog.cpp b/source/RobotAPI/gui-plugins/PlatformUnitPlugin/PlatformUnitConfigDialog.cpp
index 756c9cc1128483ddab954686a56d0419e5676c1f..8683057dd13c94900addaf91f665bb8e6428d5d1 100644
--- a/source/RobotAPI/gui-plugins/PlatformUnitPlugin/PlatformUnitConfigDialog.cpp
+++ b/source/RobotAPI/gui-plugins/PlatformUnitPlugin/PlatformUnitConfigDialog.cpp
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::
 * @author     Nikolaus Vahrenkamp ( vahrenkamp at kit dot edu)
 * @date       2012
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -27,7 +26,7 @@
 #include <IceUtil/UUID.h>
 
 
-armarx::PlatformUnitConfigDialog::PlatformUnitConfigDialog(QWidget *parent) :
+armarx::PlatformUnitConfigDialog::PlatformUnitConfigDialog(QWidget* parent) :
     QDialog(parent),
     ui(new Ui::PlatformUnitConfigDialog),
     uuid(IceUtil::generateUUID())
@@ -35,7 +34,7 @@ armarx::PlatformUnitConfigDialog::PlatformUnitConfigDialog(QWidget *parent) :
     ui->setupUi(this);
     finder = new IceProxyFinder<PlatformUnitInterfacePrx>(this);
     finder->setSearchMask("*Unit");
-    ui->gridLayout->addWidget(finder,0,1);
+    ui->gridLayout->addWidget(finder, 0, 1);
 }
 
 armarx::PlatformUnitConfigDialog::~PlatformUnitConfigDialog()
diff --git a/source/RobotAPI/gui-plugins/PlatformUnitPlugin/PlatformUnitConfigDialog.h b/source/RobotAPI/gui-plugins/PlatformUnitPlugin/PlatformUnitConfigDialog.h
index 8c0040a6cfaadceb930fee91dc4dbb7334657e1d..d735579e18c76c4132483da93455758dc3d20e3e 100644
--- a/source/RobotAPI/gui-plugins/PlatformUnitPlugin/PlatformUnitConfigDialog.h
+++ b/source/RobotAPI/gui-plugins/PlatformUnitPlugin/PlatformUnitConfigDialog.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::
 * @author     Nikolaus Vahrenkamp ( vahrenkamp at kit dot edu)
 * @date       2012
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -26,10 +25,11 @@
 
 #include <QDialog>
 
-#include <Gui/libraries/ArmarXGuiBase/widgets/IceProxyFinder.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/widgets/IceProxyFinder.h>
 #include <RobotAPI/interface/units/PlatformUnitInterface.h>
 
-namespace Ui {
+namespace Ui
+{
     class PlatformUnitConfigDialog;
 }
 
@@ -37,18 +37,18 @@ namespace armarx
 {
     class PlatformUnitConfigDialog :
         public QDialog,
-            virtual public ManagedIceObject
+        virtual public ManagedIceObject
     {
         Q_OBJECT
 
     public:
-        explicit PlatformUnitConfigDialog(QWidget *parent = 0);
+        explicit PlatformUnitConfigDialog(QWidget* parent = 0);
         ~PlatformUnitConfigDialog();
 
         IceProxyFinder<PlatformUnitInterfacePrx>* finder;
 
     private:
-        Ui::PlatformUnitConfigDialog *ui;
+        Ui::PlatformUnitConfigDialog* ui;
         std::string uuid;
         friend class PlatformUnitWidget;
 
diff --git a/source/RobotAPI/gui-plugins/PlatformUnitPlugin/PlatformUnitGuiPlugin.cpp b/source/RobotAPI/gui-plugins/PlatformUnitPlugin/PlatformUnitGuiPlugin.cpp
index 68ab6a2c4932d4eff7b834a7089c079e8c60cf24..00c597a2be1467b87c331c9059726c50c5a0bb81 100644
--- a/source/RobotAPI/gui-plugins/PlatformUnitPlugin/PlatformUnitGuiPlugin.cpp
+++ b/source/RobotAPI/gui-plugins/PlatformUnitPlugin/PlatformUnitGuiPlugin.cpp
@@ -1,7 +1,7 @@
 #include "PlatformUnitGuiPlugin.h"
 #include "PlatformUnitConfigDialog.h"
 #include "ui_PlatformUnitConfigDialog.h"
-#include <Core/core/system/ArmarXDataPath.h>
+#include <ArmarXCore/core/system/ArmarXDataPath.h>
 
 // Qt headers
 #include <Qt>
@@ -25,11 +25,11 @@ PlatformUnitGuiPlugin::PlatformUnitGuiPlugin()
 PlatformUnitWidget::PlatformUnitWidget() :
     platformUnitProxyName("PlatformUnit"),  // overwritten in loadSettings() anyway?
     platformName("Platform"),
-    speedCtrl{nullptr},
-    rotaCtrl{nullptr},
-    ctrlEvaluationTimer{},
-    platformRotation{0},
-    platformMoves{false}
+    speedCtrl {nullptr},
+          rotaCtrl {nullptr},
+          ctrlEvaluationTimer {},
+          platformRotation {0},
+platformMoves {false}
 {
     // init gui
     ui.setupUi(getWidget());
@@ -42,8 +42,8 @@ PlatformUnitWidget::PlatformUnitWidget() :
     rotaCtrl = rotat.get();
     rotaCtrl->setSteps(0);
     //add joystick controls
-    ui.gridLayout_2->addWidget(rotat.release(),2,0,1,2);
-    ui.gridLayout_3->addWidget(speed.release(),2,0,1,2);
+    ui.gridLayout_2->addWidget(rotat.release(), 2, 0, 1, 2);
+    ui.gridLayout_3->addWidget(speed.release(), 2, 0, 1, 2);
 
     ctrlEvaluationTimer.setSingleShot(false);
 }
@@ -75,28 +75,29 @@ void PlatformUnitWidget::onExitComponent()
 
 QPointer<QDialog> PlatformUnitWidget::getConfigDialog(QWidget* parent)
 {
-    if(!dialog)
+    if (!dialog)
     {
         dialog = new PlatformUnitConfigDialog(parent);
     }
+
     dialog->ui->editPlatformName->setText(QString::fromStdString(platformName));
     return qobject_cast<PlatformUnitConfigDialog*>(dialog);
 }
 
- void PlatformUnitWidget::configured()
- {
-     platformUnitProxyName = dialog->finder->getSelectedProxyName().toStdString();
-     platformName = dialog->ui->editPlatformName->text().toStdString();
- }
+void PlatformUnitWidget::configured()
+{
+    platformUnitProxyName = dialog->finder->getSelectedProxyName().toStdString();
+    platformName = dialog->ui->editPlatformName->text().toStdString();
+}
 
 
-void PlatformUnitWidget::loadSettings(QSettings *settings)
+void PlatformUnitWidget::loadSettings(QSettings* settings)
 {
     platformUnitProxyName = settings->value("platformUnitProxyName", QString::fromStdString(platformUnitProxyName)).toString().toStdString();
     platformName = settings->value("platformName", QString::fromStdString(platformName)).toString().toStdString();
 }
 
-void PlatformUnitWidget::saveSettings(QSettings *settings)
+void PlatformUnitWidget::saveSettings(QSettings* settings)
 {
     settings->setValue("platformUnitProxyName", QString::fromStdString(platformUnitProxyName));
     settings->setValue("platformName", QString::fromStdString(platformName));
@@ -107,10 +108,10 @@ void PlatformUnitWidget::connectSlots()
 {
     connect(ui.buttonMoveToPosition, SIGNAL(clicked()), this, SLOT(moveTo()));
     connect(&ctrlEvaluationTimer, SIGNAL(timeout()), this, SLOT(controlTimerTick()));
-    connect(speedCtrl,SIGNAL(pressed()), this, SLOT(startControlTimer()));
-    connect(rotaCtrl,SIGNAL(pressed()), this, SLOT(startControlTimer()));
-    connect(speedCtrl,SIGNAL(released()), this, SLOT(stopPlatform()));
-    connect(speedCtrl,SIGNAL(released()), this, SLOT(stopControlTimer()));
+    connect(speedCtrl, SIGNAL(pressed()), this, SLOT(startControlTimer()));
+    connect(rotaCtrl, SIGNAL(pressed()), this, SLOT(startControlTimer()));
+    connect(speedCtrl, SIGNAL(released()), this, SLOT(stopPlatform()));
+    connect(speedCtrl, SIGNAL(released()), this, SLOT(stopControlTimer()));
     connect(rotaCtrl, SIGNAL(released()), this, SLOT(stopPlatform()));
     connect(rotaCtrl, SIGNAL(released()), this, SLOT(stopControlTimer()));
     connect(ui.buttonStopPlatform, SIGNAL(pressed()), this, SLOT(stopPlatform()));
@@ -187,7 +188,7 @@ void PlatformUnitWidget::controlTimerTick()
 {
     float translationFactor = ui.maxTranslationSpeed->value();
     float rotationFactor = ui.maxRotationSpeed->value() * -1;
-    float rotationVel =  rotaCtrl->getRotation()/M_PI_2 * rotationFactor;
+    float rotationVel =  rotaCtrl->getRotation() / M_PI_2 * rotationFactor;
     ARMARX_INFO << deactivateSpam(0.5) << speedCtrl->getPosition().x()*translationFactor << ", " << speedCtrl->getPosition().y()*translationFactor;
     ARMARX_INFO << deactivateSpam(0.5) << "Rotation Speed: "  << (rotationVel);
     platformUnitProxy->move(speedCtrl->getPosition().x()*translationFactor, -1 * speedCtrl->getPosition().y()*translationFactor, rotationVel);
diff --git a/source/RobotAPI/gui-plugins/PlatformUnitPlugin/PlatformUnitGuiPlugin.h b/source/RobotAPI/gui-plugins/PlatformUnitPlugin/PlatformUnitGuiPlugin.h
index 5c794a22caea8efc57a108fe6507592bafc630a5..b7a0985614fc2b87b96d3fb2544034ec1a366c54 100644
--- a/source/RobotAPI/gui-plugins/PlatformUnitPlugin/PlatformUnitGuiPlugin.h
+++ b/source/RobotAPI/gui-plugins/PlatformUnitPlugin/PlatformUnitGuiPlugin.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * \package    ArmarX::Component::ObjectExaminerGuiPlugin
 * \author     Nikolaus Vahrenkamp ( vahrenkamp at kit dot edu)
 * \copyright  2012
-* \license    http://www.gnu.org/licenses/gpl.txt
+* \license    http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 
 */
@@ -27,10 +26,10 @@
 
 /* ArmarX headers */
 #include "ui_PlatformUnitGuiPlugin.h"
-#include <Gui/libraries/ArmarXGuiBase/widgets/JoystickControlWidget.h>
-#include <Core/core/Component.h>
-#include <Gui/libraries/ArmarXGuiBase/ArmarXGuiPlugin.h>
-#include <Gui/libraries/ArmarXGuiBase/ArmarXComponentWidgetController.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/widgets/JoystickControlWidget.h>
+#include <ArmarXCore/core/Component.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXGuiPlugin.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXComponentWidgetController.h>
 
 #include <RobotAPI/interface/units/PlatformUnitInterface.h>
 
@@ -51,7 +50,7 @@ namespace armarx
       \see PlatformUnitWidget
       */
     class PlatformUnitGuiPlugin :
-            public ArmarXGuiPlugin
+        public ArmarXGuiPlugin
     {
     public:
         PlatformUnitGuiPlugin();
@@ -62,9 +61,9 @@ namespace armarx
     };
 
     /*!
-      \class PlatformUnitWidget
+      \page RobotAPI-GuiPlugins-PlatformUnitPlugin PlatformUnitPlugin
       \brief With this widget the PlatformUnit can be controlled.
-      
+
       \image html PlatformUnitGUI.png "The plugin's ui." width=300px
             -# The current position and rotation, fields to enter a new target and a button to set the platform in motion.
             -# A joystick like control widget to move the platform. The platform does not rotate to move in a direction. Up moves the platform forward.
@@ -72,17 +71,15 @@ namespace armarx
             -# Be careful to set a maximum velocity before using the joysticks.
 
        When you add the widget to the Gui, you need to specify the following parameters:
-       
+
        Parameter Name   | Example Value     | Required?     | Description
        :----------------  | :-------------:   | :-------------- |:--------------------
        PlatformUnit - Proxy     | PlatformUnit   | Yes | The name of the platform unit.
        Platform | Platform | Yes | The name of the platform.
-      \see PlatformUnitGuiPlugin
-      \ingroup RobotAPI-ArmarXGuiPlugins ArmarXGuiPlugins
       */
     class PlatformUnitWidget :
-            public ArmarXComponentWidgetController,
-            public PlatformUnitListener
+        public ArmarXComponentWidgetController,
+        public PlatformUnitListener
     {
         Q_OBJECT
     public:
@@ -102,12 +99,18 @@ namespace armarx
         void reportPlatformVelocity(::Ice::Float currentPlatformVelocityX, ::Ice::Float currentPlatformVelocityY, ::Ice::Float currentPlatformVelocityRotation, const Ice::Current& c = ::Ice::Current());
 
         // inherited of ArmarXWidget
-        virtual QString getWidgetName() const { return "RobotControl.PlatformUnitGUI"; }
-        virtual QIcon getWidgetIcon() const { return QIcon("://icons/retro_joystick2.svg"); }
+        virtual QString getWidgetName() const
+        {
+            return "RobotControl.PlatformUnitGUI";
+        }
+        virtual QIcon getWidgetIcon() const
+        {
+            return QIcon("://icons/retro_joystick2.svg");
+        }
 
         QPointer<QDialog> getConfigDialog(QWidget* parent = 0);
-        virtual void loadSettings(QSettings * settings);
-        virtual void saveSettings(QSettings * settings);
+        virtual void loadSettings(QSettings* settings);
+        virtual void saveSettings(QSettings* settings);
         void configured();
 
     public slots:
@@ -132,9 +135,9 @@ namespace armarx
          */
         void controlTimerTick();
 
-	/**
-          \brief Stops the platform
-          */
+        /**
+              \brief Stops the platform
+              */
         void stopPlatform();
 
     private:
diff --git a/source/RobotAPI/gui-plugins/PlatformUnitPlugin/PlatformUnitGuiPlugin.ui b/source/RobotAPI/gui-plugins/PlatformUnitPlugin/PlatformUnitGuiPlugin.ui
index fb9e733f4cd1f651dcece335a8a01000f1b20d2d..6575f4db2b6403eba7887e3e0622dc263f7cc73b 100644
--- a/source/RobotAPI/gui-plugins/PlatformUnitPlugin/PlatformUnitGuiPlugin.ui
+++ b/source/RobotAPI/gui-plugins/PlatformUnitPlugin/PlatformUnitGuiPlugin.ui
@@ -141,7 +141,7 @@
          <item row="1" column="1">
           <widget class="QDoubleSpinBox" name="maxRotationSpeed">
            <property name="value">
-            <double>1.000000000000000</double>
+            <double>0.500000000000000</double>
            </property>
           </widget>
          </item>
diff --git a/source/RobotAPI/gui-plugins/RobotIKPlugin/RobotIKGuiPlugin.h b/source/RobotAPI/gui-plugins/RobotIKPlugin/RobotIKGuiPlugin.h
deleted file mode 100644
index 3ad05d929a7186d10bb6c5ce7921ab3fe096c9e1..0000000000000000000000000000000000000000
--- a/source/RobotAPI/gui-plugins/RobotIKPlugin/RobotIKGuiPlugin.h
+++ /dev/null
@@ -1,151 +0,0 @@
-/*
-* This file is part of ArmarX.
-*
-* ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
-*
-* ArmarX is distributed in the hope that it will be useful, but
-* WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
-*
-* You should have received a copy of the GNU General Public License
-* along with this program. If not, see <http://www.gnu.org/licenses/>.
-*
-* @package    ArmarX::
-* @author     Philipp Schmidt
-* @date       2015
-* @license    http://www.gnu.org/licenses/gpl.txt
-*             GNU General Public License
-
-*/
-
-#ifndef RobotIKGUIPLUGIN_H
-#define RobotIKGUIPLUGIN_H
-
-//Gui
-#include "RobotIKConfigDialog.h"
-#include "ui_RobotIKGuiPlugin.h"
-
-//ArmarX includes
-#include <Gui/libraries/ArmarXGuiBase/ArmarXGuiPlugin.h>
-#include <Gui/libraries/ArmarXGuiBase/ArmarXComponentWidgetController.h>
-#include <RobotAPI/interface/core/RobotIK.h>
-#include <RobotAPI/interface/core/RobotState.h>
-#include <RobotAPI/libraries/core/remoterobot/RemoteRobot.h>
-
-//Qt includes
-#include <QObject>
-
-//VirtualRobot includes
-#include <VirtualRobot/Robot.h>
-#include <VirtualRobot/Visualization/CoinVisualization/CoinVisualization.h>
-
-//Inventor includes
-#include <Inventor/sensors/SoTimerSensor.h>
-#include <Inventor/manips/SoTransformerManip.h>
-#include <Inventor/nodes/SoSphere.h>
-#include <Inventor/nodes/SoMaterial.h>
-
-namespace armarx
-{
-    class RobotIKConfigDialog;
-
-    class RobotIKGuiPlugin : public ArmarXGuiPlugin
-    {
-        public:
-            RobotIKGuiPlugin();
-
-            QString getPluginName()
-            {
-                return "RobotIKGuiPlugin";
-            }
-    };
-
-    /**
-     * \class RobotIKWidget
-     * \ingroup RobotAPI-ArmarXGuiPlugins ArmarXGuiPlugins
-     * \brief Widget for IK computation.
-     */
-    class RobotIKWidgetController : public ArmarXComponentWidgetController
-    {
-        Q_OBJECT
-
-        public:
-            RobotIKWidgetController();
-            virtual ~RobotIKWidgetController() {}
-
-            // inherited from Component
-            virtual void onInitComponent();
-            virtual void onConnectComponent();
-            virtual void onDisconnectComponent();
-            virtual void onExitComponent();
-
-            // inherited of ArmarXWidget
-            virtual QString getWidgetName() const
-            {
-                return "RobotControl.RobotIK";
-            }
-            QPointer<QDialog> getConfigDialog(QWidget* parent = 0);
-            virtual void loadSettings(QSettings * settings);
-            virtual void saveSettings(QSettings * settings);
-            void configured();
-
-        public slots:
-            void solveIK();
-            void kinematicChainChanged(const QString &arg1);
-            void caertesianSelectionChanged(const QString &arg1);
-            void resetManip();
-
-        protected:
-            RobotStateComponentInterfacePrx robotStateComponentPrx;
-            KinematicUnitInterfacePrx kinematicUnitInterfacePrx;
-            RobotIKInterfacePrx robotIKPrx;
-
-            Ui::RobotIKGuiPlugin ui;
-
-        private:
-            void connectSlots();
-            std::string robotStateComponentName;
-            std::string kinematicUnitComponentName;
-            std::string robotIKComponentName;
-
-            QPointer<RobotIKConfigDialog> dialog;
-
-            VirtualRobot::RobotPtr robot;
-            StringList getIncludePaths();
-            VirtualRobot::RobotPtr loadRobot(StringList includePaths);
-
-            SoSeparator* manipSeparator;
-            SoSeparator* currentSeparator;
-
-            SoTransformerManip* tcpManip;
-            static void manipFinishCallback(void *data, SoDragger* manip);
-            SoTransform* tcpManipTransform;
-            SoMaterial* tcpManipColor;
-            SoSphere* tcpManipSphere;
-
-            SoTransform* tcpCurrentTransform;
-            SoMaterial* tcpCurrentColor;
-            SoSphere* tcpCurrentSphere;
-
-            SoTimerSensor* robotUpdateSensor;
-            static void robotUpdateTimerCB(void *data, SoSensor *sensor);
-
-            SoTimerSensor* textFieldUpdateSensor;
-            static void textFieldUpdateTimerCB(void *data, SoSensor *sensor);
-
-            ExtendedIKResult getIKSolution();
-
-            CartesianSelection convertOption(std::string option);
-
-            bool startUpCameraPositioningFlag;
-
-    };
-    typedef boost::shared_ptr<RobotIKWidgetController> RobotIKGuiPluginPtr;
-    typedef boost::shared_ptr<VirtualRobot::CoinVisualization> CoinVisualizationPtr;
-}
-
-#endif
diff --git a/source/RobotAPI/gui-plugins/RobotIKPlugin/RobotViewerWidget.h b/source/RobotAPI/gui-plugins/RobotIKPlugin/RobotViewerWidget.h
deleted file mode 100644
index 81379c8e7d8f633699a932edce961792a60d2840..0000000000000000000000000000000000000000
--- a/source/RobotAPI/gui-plugins/RobotIKPlugin/RobotViewerWidget.h
+++ /dev/null
@@ -1,45 +0,0 @@
-#ifndef RobotViewerWidget_h
-#define RobotViewerWidget_h
-
-/* Qt headers */
-#include <QWidget>
-
-/* boost headers */
-#include <boost/smart_ptr/shared_ptr.hpp>
-
-#include "RobotViewer.h"
-
-typedef boost::shared_ptr<armarx::RobotViewer> RobotViewerPtr;
-
-namespace armarx
-{
-    class RobotViewerWidget : public QWidget
-    {
-        Q_OBJECT
-
-        public:
-            /**
-            * Constructor.
-            * Constructs a robot viewer widget.
-            * Expects a controller::ControllerPtr.
-            *
-            * @param    control     shared pointer to controller::controller
-            * @param    parent      parent widget
-            *
-            */
-            explicit RobotViewerWidget(QWidget* parent = 0);
-
-            /**
-            * Destructor.
-            *
-            */
-            ~RobotViewerWidget();
-
-            RobotViewerPtr getRobotViewer();
-
-        private:
-            RobotViewerPtr viewer;
-    };
-}
-
-#endif
diff --git a/source/RobotAPI/gui-plugins/RobotViewerPlugin/CMakeLists.txt b/source/RobotAPI/gui-plugins/RobotViewerPlugin/CMakeLists.txt
index 1ba70a06971a57439f9f0045c0ca5d4e3680eb53..6e53b6c2a4742d847aee982716cbda1ddb3a0464 100644
--- a/source/RobotAPI/gui-plugins/RobotViewerPlugin/CMakeLists.txt
+++ b/source/RobotAPI/gui-plugins/RobotViewerPlugin/CMakeLists.txt
@@ -38,9 +38,9 @@ set(GUI_UIS
 
 set(COMPONENT_LIBS RobotAPIUnits DebugDrawer ${Simox_LIBRARIES})
 
-set(LIB_VERSION    0.1.0)
-set(LIB_SOVERSION  0)
+
+
 
 if (ArmarXGui_FOUND)
-	armarx_gui_library(RobotViewerGuiPlugin "${SOURCES}" "${GUI_MOC_HDRS}" "${GUI_UIS}" "" "${COMPONENT_LIBS}" "${LIB_VERSION}" "${LIB_SOVERSION}")
+	armarx_gui_library(RobotViewerGuiPlugin "${SOURCES}" "${GUI_MOC_HDRS}" "${GUI_UIS}" "" "${COMPONENT_LIBS}" )
 endif()
diff --git a/source/RobotAPI/gui-plugins/RobotViewerPlugin/RobotViewerConfigDialog.cpp b/source/RobotAPI/gui-plugins/RobotViewerPlugin/RobotViewerConfigDialog.cpp
index 377034291670ebaa1abfced5818fda808e972ffb..13e71860078b7bba0f5dff17c9af0b5551f61c07 100644
--- a/source/RobotAPI/gui-plugins/RobotViewerPlugin/RobotViewerConfigDialog.cpp
+++ b/source/RobotAPI/gui-plugins/RobotViewerPlugin/RobotViewerConfigDialog.cpp
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::
 * @author     Mirko Waechter ( mirko.waechter at kit dot edu)
 * @date       2012
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -31,13 +30,13 @@
 
 #include <IceUtil/UUID.h>
 
-#include <Gui/libraries/ArmarXGuiBase/widgets/IceProxyFinder.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/widgets/IceProxyFinder.h>
 
 #include <RobotAPI/interface/core/RobotState.h>
 
 using namespace armarx;
 
-RobotViewerConfigDialog::RobotViewerConfigDialog(QWidget *parent) :
+RobotViewerConfigDialog::RobotViewerConfigDialog(QWidget* parent) :
     QDialog(parent),
     ui(new Ui::RobotViewerConfigDialog),
     uuid(IceUtil::generateUUID())
@@ -45,10 +44,10 @@ RobotViewerConfigDialog::RobotViewerConfigDialog(QWidget *parent) :
     ui->setupUi(this);
 
     connect(this->ui->buttonBox, SIGNAL(accepted()), this, SLOT(verifyConfig()));
-    ui->buttonBox->button( QDialogButtonBox::Ok )->setDefault(true);
+    ui->buttonBox->button(QDialogButtonBox::Ok)->setDefault(true);
     proxyFinder = new IceProxyFinder<RobotStateComponentInterfacePrx>(this);
     proxyFinder->setSearchMask("RobotState*");
-    ui->gridLayout->addWidget(proxyFinder, 2,1,1,2);
+    ui->gridLayout->addWidget(proxyFinder, 2, 1, 1, 2);
 }
 
 RobotViewerConfigDialog::~RobotViewerConfigDialog()
@@ -76,12 +75,14 @@ void RobotViewerConfigDialog::onExitComponent()
 
 void RobotViewerConfigDialog::verifyConfig()
 {
-    if(proxyFinder->getSelectedProxyName().trimmed().length() == 0)
+    if (proxyFinder->getSelectedProxyName().trimmed().length() == 0)
     {
         QMessageBox::critical(this, "Invalid Configuration", "The proxy name must not be empty");
     }
     else
+    {
         this->accept();
+    }
 }
 
 
diff --git a/source/RobotAPI/gui-plugins/RobotViewerPlugin/RobotViewerConfigDialog.h b/source/RobotAPI/gui-plugins/RobotViewerPlugin/RobotViewerConfigDialog.h
index b828a8e0e274bc540ec7dee4c5a8bcf3fb660669..b1e011efe331c2a50f9d4b41f877e106ec6b14e8 100644
--- a/source/RobotAPI/gui-plugins/RobotViewerPlugin/RobotViewerConfigDialog.h
+++ b/source/RobotAPI/gui-plugins/RobotViewerPlugin/RobotViewerConfigDialog.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::
 * @author     Nikolaus Vahrenkamp
 * @date       2015
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -27,16 +26,18 @@
 #include <QDialog>
 #include <QFileDialog>
 
-#include <Core/core/services/tasks/RunningTask.h>
-#include <Core/core/IceManager.h>
-#include <Core/core/ManagedIceObject.h>
-#include <Gui/libraries/ArmarXGuiBase/widgets/IceProxyFinder.h>
+#include <ArmarXCore/core/services/tasks/RunningTask.h>
+#include <ArmarXCore/core/IceManager.h>
+#include <ArmarXCore/core/ManagedIceObject.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/widgets/IceProxyFinder.h>
 
-namespace Ui {
+namespace Ui
+{
     class RobotViewerConfigDialog;
 }
 
-namespace armarx{
+namespace armarx
+{
     class RobotViewerConfigDialog :
         public QDialog,
         virtual public ManagedIceObject
@@ -44,11 +45,14 @@ namespace armarx{
         Q_OBJECT
 
     public:
-        explicit RobotViewerConfigDialog(QWidget *parent = 0);
+        explicit RobotViewerConfigDialog(QWidget* parent = 0);
         ~RobotViewerConfigDialog();
 
         // inherited from ManagedIceObject
-        std::string getDefaultName() const { return "RobotViewerConfigDialog" + uuid;}
+        std::string getDefaultName() const
+        {
+            return "RobotViewerConfigDialog" + uuid;
+        }
         void onInitComponent();
         void onConnectComponent();
         void onExitComponent();
@@ -61,7 +65,7 @@ namespace armarx{
     private:
 
         IceProxyFinderBase* proxyFinder;
-        Ui::RobotViewerConfigDialog *ui;
+        Ui::RobotViewerConfigDialog* ui;
         std::string uuid;
         friend class RobotViewerWidgetController;
     };
diff --git a/source/RobotAPI/gui-plugins/RobotViewerPlugin/RobotViewerGuiPlugin.cpp b/source/RobotAPI/gui-plugins/RobotViewerPlugin/RobotViewerGuiPlugin.cpp
index eeb89f8db30dc69883ee957107ded4a680076d97..838783ebd9aca7d7c665fdae629ed9052ddc92c4 100644
--- a/source/RobotAPI/gui-plugins/RobotViewerPlugin/RobotViewerGuiPlugin.cpp
+++ b/source/RobotAPI/gui-plugins/RobotViewerPlugin/RobotViewerGuiPlugin.cpp
@@ -3,11 +3,11 @@
 
 #include <RobotAPI/gui-plugins/RobotViewerPlugin/ui_RobotViewerConfigDialog.h>
 
-#include <Core/core/system/ArmarXDataPath.h>
-#include <Core/core/ArmarXObjectScheduler.h>
-#include <Core/core/ArmarXManager.h>
-#include <Core/core/system/cmake/CMakePackageFinder.h>
-#include <Core/core/application/Application.h>
+#include <ArmarXCore/core/system/ArmarXDataPath.h>
+#include <ArmarXCore/core/ArmarXObjectScheduler.h>
+#include <ArmarXCore/core/ArmarXManager.h>
+#include <ArmarXCore/core/system/cmake/CMakePackageFinder.h>
+#include <ArmarXCore/core/application/Application.h>
 
 #include <VirtualRobot/XML/RobotIO.h>
 
@@ -81,12 +81,17 @@ void RobotViewerWidgetController::onInitComponent()
     {
         std::string debugDrawerComponentName = "RobotViewerGUIDebugDrawer_" + getName();
         ARMARX_INFO << "Creating component " << debugDrawerComponentName;
-        debugDrawer = Component::create<DebugDrawerComponent>(properties,debugDrawerComponentName);
+        debugDrawer = Component::create<DebugDrawerComponent>(properties, debugDrawerComponentName);
+
         if (mutex3D)
         {
             debugDrawer->setMutex(mutex3D);
-        } else
+        }
+        else
+        {
             ARMARX_ERROR << " No 3d mutex available...";
+        }
+
         ArmarXManagerPtr m = getArmarXManager();
         m->addObject(debugDrawer);
 
@@ -99,6 +104,7 @@ void RobotViewerWidgetController::onInitComponent()
             rootVisu->addChild(debugLayerVisu);
         }
     }
+
     showRoot(true);
 }
 
@@ -107,22 +113,30 @@ void RobotViewerWidgetController::onConnectComponent()
     robotStateComponentPrx = getProxy<RobotStateComponentInterfacePrx>(robotStateComponentName);
 
     if (robotVisu)
+    {
         robotVisu->removeAllChildren();
+    }
+
     robot.reset();
 
-     std::string rfile;
-     StringList includePaths;
+    std::string rfile;
+    StringList includePaths;
 
     // get robot filename
-    try {
+    try
+    {
 
         StringList packages = robotStateComponentPrx->getArmarXPackages();
         packages.push_back(Application::GetProjectName());
         ARMARX_VERBOSE << "ArmarX packages " << packages;
-        for(const std::string &projectName : packages)
+
+        for (const std::string& projectName : packages)
         {
-            if(projectName.empty())
+            if (projectName.empty())
+            {
                 continue;
+            }
+
             CMakePackageFinder project(projectName);
             StringList projectIncludePaths;
             auto pathsString = project.getDataDir();
@@ -135,44 +149,43 @@ void RobotViewerWidgetController::onConnectComponent()
             includePaths.insert(includePaths.end(), projectIncludePaths.begin(), projectIncludePaths.end());
 
         }
+
         rfile = robotStateComponentPrx->getRobotFilename();
         ARMARX_VERBOSE << "Relative robot file " << rfile;
         ArmarXDataPath::getAbsolutePath(rfile, rfile, includePaths);
         ARMARX_VERBOSE << "Absolute robot file " << rfile;
-     } catch (...)
-     {
-         ARMARX_ERROR << "Unable to retrieve robot filename";
-     }
+    }
+    catch (...)
+    {
+        ARMARX_ERROR << "Unable to retrieve robot filename";
+    }
 
-    try {
+    try
+    {
         ARMARX_INFO << "Loading robot from file " << rfile;
         robot = loadRobotFile(rfile);
-    } catch (...)
+    }
+    catch (...)
     {
         ARMARX_ERROR << "Failed to init robot";
     }
 
-    if(!robot)
+    if (!robot)
     {
         getObjectScheduler()->terminate();
-        if(getWidget()->parentWidget())
+
+        if (getWidget()->parentWidget())
+        {
             getWidget()->parentWidget()->close();
+        }
+
         std::cout << "returning" << std::endl;
         return;
     }
 
-    {
-        boost::recursive_mutex::scoped_lock lock(*mutex3D);
+    setRobotVisu(ui.radioButtonCol->isChecked());
+    showRobot(ui.cbRobot->isChecked());
 
-        CoinVisualizationPtr robotViewerVisualization = robot->getVisualization<CoinVisualization>();
-        if (robotViewerVisualization)
-        {
-            robotVisu->addChild(robotViewerVisualization->getCoinVisualization());
-        } else
-        {
-            ARMARX_WARNING << "no robot visu available...";
-        }
-    }
 
     // start update timer
     SoSensorManager* sensor_mgr = SoDB::getSensorManager();
@@ -188,12 +201,14 @@ void RobotViewerWidgetController::onDisconnectComponent()
 {
 
     ARMARX_INFO << "Disconnecting component";
+
     // stop update timer
     if (timerSensor)
     {
         SoSensorManager* sensor_mgr = SoDB::getSensorManager();
         sensor_mgr->removeTimerSensor(timerSensor);
     }
+
     ARMARX_INFO << "Disconnecting component: timer stopped";
 
     robotStateComponentPrx = NULL;
@@ -203,8 +218,9 @@ void RobotViewerWidgetController::onDisconnectComponent()
         if (robotVisu)
         {
             ARMARX_INFO << "Disconnecting component: removing visu";
-             robotVisu->removeAllChildren();
+            robotVisu->removeAllChildren();
         }
+
         robot.reset();
     }
     ARMARX_INFO << "Disconnecting component: finished";
@@ -240,52 +256,89 @@ void RobotViewerWidgetController::onExitComponent()
         }
     }
 
-/*
-    if (debugDrawer && debugDrawer->getObjectScheduler())
-    {
-        ARMARX_INFO << "Removing DebugDrawer component...";
-        debugDrawer->getObjectScheduler()->terminate();
-        ARMARX_INFO << "Removing DebugDrawer component...done";
-    }
-*/
+    /*
+        if (debugDrawer && debugDrawer->getObjectScheduler())
+        {
+            ARMARX_INFO << "Removing DebugDrawer component...";
+            debugDrawer->getObjectScheduler()->terminate();
+            ARMARX_INFO << "Removing DebugDrawer component...done";
+        }
+    */
 }
 
 QPointer<QDialog> RobotViewerWidgetController::getConfigDialog(QWidget* parent)
 {
-    if(!dialog)
+    if (!dialog)
     {
         dialog = new RobotViewerConfigDialog(parent);
         dialog->setName(dialog->getDefaultName());
 
     }
+
     return qobject_cast<RobotViewerConfigDialog*>(dialog);
 }
 
 
 
- void RobotViewerWidgetController::configured()
- {
-     ARMARX_VERBOSE << "RobotViewerWidget::configured()";
-     robotStateComponentName = dialog->proxyFinder->getSelectedProxyName().trimmed().toStdString();
- }
+void RobotViewerWidgetController::configured()
+{
+    ARMARX_VERBOSE << "RobotViewerWidget::configured()";
+    robotStateComponentName = dialog->proxyFinder->getSelectedProxyName().trimmed().toStdString();
+}
 
 
-void RobotViewerWidgetController::loadSettings(QSettings *settings)
+void RobotViewerWidgetController::loadSettings(QSettings* settings)
 {
     robotStateComponentName = settings->value("RobotStateComponent", QString::fromStdString(ROBOTSTATE_NAME_DEFAULT)).toString().toStdString();
+    bool showRob =  settings->value("showRobot", QVariant(true)).toBool();
+    bool fullMod =  settings->value("fullModel", QVariant(true)).toBool();
+    ui.cbRobot->setChecked(showRob);
+    ui.radioButtonFull->setChecked(fullMod);
+    ui.radioButtonCol->setChecked(!fullMod);
 }
 
-void RobotViewerWidgetController::saveSettings(QSettings *settings)
+void RobotViewerWidgetController::saveSettings(QSettings* settings)
 {
     settings->setValue("RobotStateComponent", QString::fromStdString(robotStateComponentName));
+    settings->setValue("showRobot", ui.cbRobot->isChecked());
+    settings->setValue("fullModel", ui.radioButtonFull->isChecked());
 }
 
+void RobotViewerWidgetController::setRobotVisu(bool colModel)
+{
+    robotVisu->removeAllChildren();
+
+    if (!robot)
+    {
+        return;
+    }
+
+    boost::recursive_mutex::scoped_lock lock(*mutex3D);
+
+    VirtualRobot::SceneObject::VisualizationType v = VirtualRobot::SceneObject::Full;
+
+    if (colModel)
+    {
+        v = VirtualRobot::SceneObject::Collision;
+    }
+
+    CoinVisualizationPtr robotViewerVisualization = robot->getVisualization<CoinVisualization>(v);
+
+    if (robotViewerVisualization)
+    {
+        robotVisu->addChild(robotViewerVisualization->getCoinVisualization());
+    }
+    else
+    {
+        ARMARX_WARNING << "no robot visu available...";
+    }
+}
 
 void RobotViewerWidgetController::showVisuLayers(bool show)
 {
     if (debugDrawer)
     {
-        if(show)
+        if (show)
         {
             debugDrawer->enableAllLayers();
         }
@@ -299,14 +352,17 @@ void RobotViewerWidgetController::showVisuLayers(bool show)
 void RobotViewerWidgetController::showRoot(bool show)
 {
     if (!debugDrawer)
+    {
         return;
+    }
 
     std::string poseName("root");
-    if(show)
+
+    if (show)
     {
         Eigen::Matrix4f gp = Eigen::Matrix4f::Identity();
         PosePtr gpP(new Pose(gp));
-        debugDrawer->setPoseDebugLayerVisu(poseName,gpP);
+        debugDrawer->setPoseDebugLayerVisu(poseName, gpP);
     }
     else
     {
@@ -317,19 +373,22 @@ void RobotViewerWidgetController::showRoot(bool show)
 void RobotViewerWidgetController::showRobot(bool show)
 {
     if (!robotVisu)
+    {
         return;
+    }
+
     boost::recursive_mutex::scoped_lock lock(*mutex3D);
 
-    if(show && rootVisu->findChild(robotVisu)<0)
+    if (show && rootVisu->findChild(robotVisu) < 0)
     {
         rootVisu->addChild(robotVisu);
     }
-    else if (!show && rootVisu->findChild(robotVisu)>=0)
+    else if (!show && rootVisu->findChild(robotVisu) >= 0)
     {
         rootVisu->removeChild(robotVisu);
     }
 }
-SoNode *RobotViewerWidgetController::getScene()
+SoNode* RobotViewerWidgetController::getScene()
 {
     return rootVisu;
 }
@@ -337,8 +396,12 @@ SoNode *RobotViewerWidgetController::getScene()
 void RobotViewerWidgetController::timerCB(void* data, SoSensor* sensor)
 {
     RobotViewerWidgetController* controller = static_cast<RobotViewerWidgetController*>(data);
+
     if (!controller)
+    {
         return;
+    }
+
     controller->updateRobotVisu();
 }
 
@@ -349,6 +412,8 @@ void RobotViewerWidgetController::connectSlots()
     connect(ui.cbDebugLayer, SIGNAL(toggled(bool)), this, SLOT(showVisuLayers(bool)), Qt::QueuedConnection);
     connect(ui.cbRoot, SIGNAL(toggled(bool)), this, SLOT(showRoot(bool)), Qt::QueuedConnection);
     connect(ui.cbRobot, SIGNAL(toggled(bool)), this, SLOT(showRobot(bool)), Qt::QueuedConnection);
+    connect(ui.radioButtonCol, SIGNAL(toggled(bool)), this, SLOT(colModel(bool)), Qt::QueuedConnection);
+    connect(ui.radioButtonFull, SIGNAL(toggled(bool)), this, SLOT(colModel(bool)), Qt::QueuedConnection);
 }
 
 
@@ -357,11 +422,13 @@ VirtualRobot::RobotPtr RobotViewerWidgetController::loadRobotFile(std::string fi
 {
     VirtualRobot::RobotPtr robot;
 
-    if (!ArmarXDataPath::getAbsolutePath(fileName,fileName))
+    if (!ArmarXDataPath::getAbsolutePath(fileName, fileName))
     {
-       ARMARX_INFO << "Could not find Robot XML file with name " << fileName;
+        ARMARX_INFO << "Could not find Robot XML file with name " << fileName;
     }
+
     robot = RobotIO::loadRobot(fileName);
+
     if (!robot)
     {
         ARMARX_INFO << "Could not find Robot XML file with name " << fileName;
@@ -371,18 +438,33 @@ VirtualRobot::RobotPtr RobotViewerWidgetController::loadRobotFile(std::string fi
 }
 
 
+void RobotViewerWidgetController::colModel(bool c)
+{
+    bool colModel = false;
+
+    if (ui.radioButtonCol->isChecked())
+    {
+        colModel = true;
+    }
+
+    setRobotVisu(colModel);
+}
+
 
 void RobotViewerWidgetController::updateRobotVisu()
 {
     boost::recursive_mutex::scoped_lock lock(*mutex3D);
 
     if (!robotStateComponentPrx || !robot)
+    {
         return;
+    }
 
     try
     {
-        RemoteRobot::synchronizeLocalClone(robot,robotStateComponentPrx);
-    } catch (...)
+        RemoteRobot::synchronizeLocalClone(robot, robotStateComponentPrx);
+    }
+    catch (...)
     {
         ARMARX_INFO << deactivateSpam(5) << "Robot synchronization failed";
         return;
@@ -390,14 +472,14 @@ void RobotViewerWidgetController::updateRobotVisu()
 
     Eigen::Matrix4f gp = robot->getGlobalPose();
     QString roboInfo("Robot Pose (global): pos: ");
-    roboInfo += QString::number(gp(0,3), 'f', 2);
+    roboInfo += QString::number(gp(0, 3), 'f', 2);
     roboInfo += QString(", ");
-    roboInfo += QString::number(gp(1,3), 'f', 2);
+    roboInfo += QString::number(gp(1, 3), 'f', 2);
     roboInfo += QString(", ");
-    roboInfo += QString::number(gp(2,3), 'f', 2);
+    roboInfo += QString::number(gp(2, 3), 'f', 2);
     roboInfo += QString(", rot:");
     Eigen::Vector3f rpy;
-    VirtualRobot::MathTools::eigen4f2rpy(gp,rpy);
+    VirtualRobot::MathTools::eigen4f2rpy(gp, rpy);
     roboInfo += QString::number(rpy(0), 'f', 2);
     roboInfo += QString(", ");
     roboInfo += QString::number(rpy(1), 'f', 2);
@@ -410,8 +492,11 @@ void RobotViewerWidgetController::setMutex3D(boost::shared_ptr<boost::recursive_
 {
     //ARMARX_IMPORTANT << "set mutex3d :" << mutex3D.get();
     this->mutex3D = mutex3D;
+
     if (debugDrawer)
+    {
         debugDrawer->setMutex(mutex3D);
+    }
 }
 
 
diff --git a/source/RobotAPI/gui-plugins/RobotViewerPlugin/RobotViewerGuiPlugin.h b/source/RobotAPI/gui-plugins/RobotViewerPlugin/RobotViewerGuiPlugin.h
index 6c323274f03677679a3be6006c6806a64b466bef..bc2a8c015a2f1537fdc15d620a1f47ff3348f1d1 100644
--- a/source/RobotAPI/gui-plugins/RobotViewerPlugin/RobotViewerGuiPlugin.h
+++ b/source/RobotAPI/gui-plugins/RobotViewerPlugin/RobotViewerGuiPlugin.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::Component::RobotViewerGuiPlugin
 * @author     Nikolaus Vahrenkamp
 * @copyright  2015 KIT
-* @license    http://www.gnu.org/licenses/gpl.txt
+* @license    http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 
 */
@@ -30,10 +29,10 @@
 #include <RobotAPI/components/DebugDrawer/DebugDrawerComponent.h>
 #include <RobotAPI/libraries/core/remoterobot/RemoteRobot.h>
 
-#include <Gui/libraries/ArmarXGuiBase/ArmarXGuiPlugin.h>
-#include <Gui/libraries/ArmarXGuiBase/ArmarXComponentWidgetController.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXGuiPlugin.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXComponentWidgetController.h>
 
-#include <Core/core/Component.h>
+#include <ArmarXCore/core/Component.h>
 
 /* Qt headers */
 #include <QtGui/QMainWindow>
@@ -62,7 +61,7 @@ namespace armarx
       \see RobotViewerWidget
       */
     class RobotViewerGuiPlugin :
-            public ArmarXGuiPlugin
+        public ArmarXGuiPlugin
     {
     public:
         RobotViewerGuiPlugin();
@@ -74,21 +73,19 @@ namespace armarx
     };
 
     /**
-     \class RobotViewerWidget
+     \page RobotAPI-GuiPlugins-RobotViewerPlugin RobotViewerPlugin
+
      \brief This widget shows a 3D model of the robot. The robot is articulated and moved according to the corresponding RemoteRobot.
      Further, DebugDrawer methods are available.
      \image html RobotViewerGUI.png
      When you add the widget to the Gui, you need to specify the following parameters:
-     
+
      Parameter Name   | Example Value     | Required?     | Description
      :----------------  | :-------------:   | :-------------- |:--------------------
      Proxy     | RobotStateComponent   | Yes | The name of the robot state component.
-
-     \ingroup RobotAPI-ArmarXGuiPlugins ArmarXGuiPlugins
-     \see RobotViewerGuiPlugin
      */
     class RobotViewerWidgetController :
-            public ArmarXComponentWidgetController
+        public ArmarXComponentWidgetController
     {
         Q_OBJECT
     public:
@@ -108,8 +105,8 @@ namespace armarx
             return "RobotControl.RobotViewerGUI";
         }
         QPointer<QDialog> getConfigDialog(QWidget* parent = 0);
-        virtual void loadSettings(QSettings * settings);
-        virtual void saveSettings(QSettings * settings);
+        virtual void loadSettings(QSettings* settings);
+        virtual void saveSettings(QSettings* settings);
         void configured();
 
         SoNode* getScene();
@@ -149,11 +146,13 @@ namespace armarx
         SoSeparator* debugLayerVisu;
         armarx::DebugDrawerComponentPtr debugDrawer;
 
-        static void timerCB(void *data, SoSensor *sensor);
+        static void timerCB(void* data, SoSensor* sensor);
+        void setRobotVisu(bool colModel);
     protected slots:
         void showVisuLayers(bool show);
         void showRoot(bool show);
         void showRobot(bool show);
+        void colModel(bool c);
     private:
 
         // init stuff
diff --git a/source/RobotAPI/gui-plugins/RobotViewerPlugin/RobotViewerGuiPlugin.ui b/source/RobotAPI/gui-plugins/RobotViewerPlugin/RobotViewerGuiPlugin.ui
index 2a8526ac88774d9fb2009fe42d8d29c8d922fca7..ea3435805816af1f4362c9b4fe94e3916265c30b 100644
--- a/source/RobotAPI/gui-plugins/RobotViewerPlugin/RobotViewerGuiPlugin.ui
+++ b/source/RobotAPI/gui-plugins/RobotViewerPlugin/RobotViewerGuiPlugin.ui
@@ -63,10 +63,31 @@
      </item>
     </layout>
    </item>
+   <item row="1" column="0">
+    <layout class="QHBoxLayout" name="horizontalLayout">
+     <item>
+      <widget class="QRadioButton" name="radioButtonFull">
+       <property name="text">
+        <string>Full Model</string>
+       </property>
+       <property name="checked">
+        <bool>true</bool>
+       </property>
+      </widget>
+     </item>
+     <item>
+      <widget class="QRadioButton" name="radioButtonCol">
+       <property name="text">
+        <string>Collision Model</string>
+       </property>
+      </widget>
+     </item>
+    </layout>
+   </item>
    <item row="1" column="1">
-    <widget class="QCheckBox" name="cbRoot">
+    <widget class="QCheckBox" name="cbRobot">
      <property name="text">
-      <string>show root</string>
+      <string>show robot</string>
      </property>
      <property name="checked">
       <bool>true</bool>
@@ -74,9 +95,9 @@
     </widget>
    </item>
    <item row="2" column="1">
-    <widget class="QCheckBox" name="cbRobot">
+    <widget class="QCheckBox" name="cbRoot">
      <property name="text">
-      <string>show robot</string>
+      <string>show root</string>
      </property>
      <property name="checked">
       <bool>true</bool>
diff --git a/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotter.cpp b/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotter.cpp
index f761341ad777fbf0ffdead7c3485465b0d4c6ec1..a0618adeb178f217391532c66e974e3076c868ba 100644
--- a/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotter.cpp
+++ b/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotter.cpp
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,16 +16,16 @@
 * @package    ArmarX::Gui
 * @author     Mirko Waechter ( mirko.waechter at kit dot edu)
 * @date       2012
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
 #include "ArmarXPlotter.h"
 #include "ArmarXPlotterDialog.h"
 
-#include <Core/observers/ObserverObjectFactories.h>
-#include <Core/observers/variant/DataFieldIdentifier.h>
-#include <Core/observers/exceptions/local/InvalidChannelException.h>
+#include <ArmarXCore/observers/ObserverObjectFactories.h>
+#include <ArmarXCore/observers/variant/DataFieldIdentifier.h>
+#include <ArmarXCore/observers/exceptions/local/InvalidChannelException.h>
 
 #include <qwt_plot.h>
 #include <qwt_plot_curve.h>
@@ -71,20 +70,20 @@ namespace armarx
         //  Setup Plotter
         ///////////////
         // panning with the left mouse button
-        ( void ) new QwtPlotPanner( ui.qwtPlot->canvas() );
+        (void) new QwtPlotPanner(ui.qwtPlot->canvas());
 
         // zoom in/out with the wheel
-        QwtPlotMagnifier * magnifier = new QwtPlotMagnifier( ui.qwtPlot->canvas() );
+        QwtPlotMagnifier* magnifier = new QwtPlotMagnifier(ui.qwtPlot->canvas());
         magnifier->setAxisEnabled(QwtPlot::xBottom, false);
 
         ui.qwtPlot->canvas()->setPaintAttribute(QwtPlotCanvas::BackingStore, false); //increases performance for incremental drawing
 
-        QwtLegend *legend = new QwtLegend;
-        legend->setItemMode( QwtLegend::CheckableItem );
-        ui.qwtPlot->insertLegend( legend, QwtPlot::BottomLegend );
+        QwtLegend* legend = new QwtLegend;
+        legend->setItemMode(QwtLegend::CheckableItem);
+        ui.qwtPlot->insertLegend(legend, QwtPlot::BottomLegend);
 
 
-        ui.qwtPlot->setAxisTitle( QwtPlot::xBottom, "Time (in sec)");
+        ui.qwtPlot->setAxisTitle(QwtPlot::xBottom, "Time (in sec)");
         //        ui.qwtPlot->setAutoReplot();
 
         dialog = new ArmarXPlotterDialog(getWidget(), NULL);
@@ -113,7 +112,7 @@ namespace armarx
 
     void ArmarXPlotter::onConnectComponent()
     {
-        ARMARX_VERBOSE<< "ArmarXPlotter started" << flush;
+        ARMARX_VERBOSE << "ArmarXPlotter started" << flush;
         dialog->setIceManager(getIceManager());
 
         connect(dialog, SIGNAL(accepted()), this, SLOT(configDone()));
@@ -122,28 +121,33 @@ namespace armarx
         connect(ui.BTNPlotterStatus, SIGNAL(toggled(bool)), this, SLOT(plottingPaused(bool)));
 
         connect(ui.BTNAutoScale, SIGNAL(toggled(bool)), this, SLOT(autoScale(bool)));
-        connect(  ui.qwtPlot, SIGNAL( legendChecked( QwtPlotItem *, bool ) ),
-                  SLOT( showCurve( QwtPlotItem *, bool ) ) );
+        connect(ui.qwtPlot, SIGNAL(legendChecked(QwtPlotItem*, bool)),
+                SLOT(showCurve(QwtPlotItem*, bool)));
 
         connect(ui.btnLogToFile, SIGNAL(toggled(bool)), this, SLOT(toggleLogging(bool)));
 
-        if(!QMetaObject::invokeMethod(this, "setupCurves"))
+        if (!QMetaObject::invokeMethod(this, "setupCurves"))
+        {
             ARMARX_WARNING << "Failed to invoke enable";
+        }
 
 
     }
 
     void ArmarXPlotter::onExitComponent()
     {
-        if(pollingTask)
+        if (pollingTask)
+        {
             pollingTask->stop();
+        }
     }
 
-    void ArmarXPlotter::onCloseWidget(QCloseEvent *event)
+    void ArmarXPlotter::onCloseWidget(QCloseEvent* event)
     {
         ARMARX_VERBOSE << "closing" << flush;
         timer->stop();
-        if(logstream.is_open())
+
+        if (logstream.is_open())
         {
             logstream.close();
         }
@@ -155,8 +159,11 @@ namespace armarx
 
     void ArmarXPlotter::configDialog()
     {
-        if(!dialog)
+        if (!dialog)
+        {
             return;
+        }
+
         dialog->ui.spinBoxUpdateInterval->setValue(updateInterval);
         dialog->ui.spinBoxShownInterval->setValue(shownInterval);
         dialog->ui.listWidget->clear();
@@ -189,7 +196,7 @@ namespace armarx
 
     void ArmarXPlotter::toggleLogging(bool toggled)
     {
-        if(toggled)
+        if (toggled)
         {
 
             std::string filename = "datalog-" + IceUtil::Time::now().toDateTime() + ".csv";
@@ -198,7 +205,8 @@ namespace armarx
             ARMARX_INFO << "Logging to " << filename;
             logstream.open(filename);
             logStartTime = IceUtil::Time::now();
-            if(!logstream.is_open())
+
+            if (!logstream.is_open())
             {
                 ARMARX_ERROR << "Could not open file for logging: " << filename;
                 ui.btnLogToFile->setChecked(false);
@@ -206,10 +214,12 @@ namespace armarx
             else
             {
                 logstream << "Timestamp";
-                for(auto& channel: selectedChannels)
+
+                for (auto& channel : selectedChannels)
                 {
                     logstream <<  "," << channel.toStdString();
                 }
+
                 logstream << std::endl;
             }
         }
@@ -223,7 +233,8 @@ namespace armarx
     {
         ScopedLock lock(dataMutex);
         auto newData = getData(selectedChannels, dataMap);
-        if(ui.btnLogToFile->isChecked())
+
+        if (ui.btnLogToFile->isChecked())
         {
             logToFile(IceUtil::Time::now(),  newData);
         }
@@ -236,94 +247,131 @@ namespace armarx
         ScopedLock lock(dataMutex);
         QPointF p;
 
-//        int size = shownInterval*1000/updateInterval;
+        //        int size = shownInterval*1000/updateInterval;
         GraphDataMap::iterator it = dataMap.begin();
         IceUtil::Time curTime = IceUtil::Time::now();
 
-        for(; it != dataMap.end(); ++it)
+        for (; it != dataMap.end(); ++it)
         {
 
             QVector<QPointF> pointList;
             pointList.clear();
             std::vector<TimeData>& dataVec = it->second;
-//            int newSize = min(size,(int)dataVec.size());
+            //            int newSize = min(size,(int)dataVec.size());
             pointList.resize(dataVec.size());
+
             try
             {
                 int j = 0;
-                for (int i = dataVec.size()-1; i >=0 ; --i) {
+
+                for (int i = dataVec.size() - 1; i >= 0 ; --i)
+                {
                     TimeData& data = dataVec[i];
                     IceUtil::Time age = (data.time - curTime);
-                    if(age.toMilliSecondsDouble() <= shownInterval*1000)
+
+                    if (age.toMilliSecondsDouble() <= shownInterval * 1000)
                     {
                         VariantPtr var = VariantPtr::dynamicCast(data.data);
-                        if(var->getInitialized())
+
+                        if (var->getInitialized())
                         {
 
-                            if((signed int)j < pointList.size())
+                            if ((signed int)j < pointList.size())
                             {
-                                if(var->getType() == VariantType::Float)
+                                if (var->getType() == VariantType::Float)
+                                {
                                     pointList[j].setY(var->getFloat());
-                                else if(var->getType() == VariantType::Double)
+                                }
+                                else if (var->getType() == VariantType::Double)
+                                {
                                     pointList[j].setY(var->getDouble());
-                                else if(var->getType() == VariantType::Int)
+                                }
+                                else if (var->getType() == VariantType::Int)
+                                {
                                     pointList[j].setY(var->getInt());
-                                else continue;
-                                pointList[j].setX(0.001f*age.toMilliSecondsDouble());
-                            }else
+                                }
+                                else
+                                {
+                                    continue;
+                                }
+
+                                pointList[j].setX(0.001f * age.toMilliSecondsDouble());
+                            }
+                            else
                             {
-                                if(var->getType() == VariantType::Float)
+                                if (var->getType() == VariantType::Float)
+                                {
                                     p.setY(var->getFloat());
-                                else if(var->getType() == VariantType::Double)
+                                }
+                                else if (var->getType() == VariantType::Double)
+                                {
                                     p.setY(var->getDouble());
-                                else if(var->getType() == VariantType::Int)
+                                }
+                                else if (var->getType() == VariantType::Int)
+                                {
                                     p.setY(var->getInt());
-                                else continue;
-                                p.setX(0.001*age.toMilliSecondsDouble());
+                                }
+                                else
+                                {
+                                    continue;
+                                }
+
+                                p.setX(0.001 * age.toMilliSecondsDouble());
                                 pointList.push_back(p);
                             }
+
                             j++;
                         }
                         else
                         {
-                            ARMARX_WARNING<< "uninitialized field: " << it->first;
+                            ARMARX_WARNING << "uninitialized field: " << it->first;
                         }
 
                     }
                     else
-                        break; // data too old from now
+                    {
+                        break;    // data too old from now
+                    }
                 }
             }
-            catch(...)
+            catch (...)
             {
                 handleExceptions();
             }
 
             QwtSeriesData<QPointF>* pointSeries = new  QwtPointSeriesData(pointList);
-            if(curves.find(it->first) != curves.end()){
-                QwtPlotCurve *curve = curves[it->first];
+
+            if (curves.find(it->first) != curves.end())
+            {
+                QwtPlotCurve* curve = curves[it->first];
                 curve->setData(pointSeries);
             }
         }
 
 
-        ui.qwtPlot->setAxisScale( QwtPlot::xBottom, shownInterval*-1, 0.f);
-        if(ui.BTNAutoScale->isChecked())
+        ui.qwtPlot->setAxisScale(QwtPlot::xBottom, shownInterval * -1, 0.f);
+
+        if (ui.BTNAutoScale->isChecked())
+        {
             ui.qwtPlot->setAxisAutoScale(QwtPlot::yLeft, true);
+        }
+
         //        ui.qwtPlot->setAxisScale( QwtPlot::yLeft, -1, 1);
 
         ui.qwtPlot->replot();
     }
 
-    void ArmarXPlotter::showCurve( QwtPlotItem *item, bool on )
+    void ArmarXPlotter::showCurve(QwtPlotItem* item, bool on)
     {
-        item->setVisible( on );
+        item->setVisible(on);
 
-        QwtLegendItem *legendItem =
-                qobject_cast<QwtLegendItem *>( ui.qwtPlot->legend()->find( item ) );
+        QwtLegendItem* legendItem =
+            qobject_cast<QwtLegendItem*>(ui.qwtPlot->legend()->find(item));
 
-        if ( legendItem )
-            legendItem->setChecked( on );
+        if (legendItem)
+        {
+            legendItem->setChecked(on);
+        }
 
         ui.qwtPlot->replot();
     }
@@ -342,9 +390,13 @@ namespace armarx
     {
         ScopedLock lock(dataMutex);
         __plottingPaused = toggled;
-        if(pollingTask)
+
+        if (pollingTask)
+        {
             pollingTask->stop();
-        if(__plottingPaused)
+        }
+
+        if (__plottingPaused)
         {
             timer->stop();
         }
@@ -358,7 +410,7 @@ namespace armarx
 
 
 
-    void ArmarXPlotter::saveSettings(QSettings * settings)
+    void ArmarXPlotter::saveSettings(QSettings* settings)
     {
         ScopedLock lock(dataMutex);
         settings->setValue("updateInterval", updateInterval);
@@ -368,7 +420,7 @@ namespace armarx
         settings->setValue("autoScaleActive", ui.BTNAutoScale->isChecked());
     }
 
-    void ArmarXPlotter::loadSettings(QSettings * settings)
+    void ArmarXPlotter::loadSettings(QSettings* settings)
     {
         ScopedLock lock(dataMutex);
         updateInterval = settings->value("updateInterval", 100).toInt();
@@ -380,12 +432,12 @@ namespace armarx
         ARMARX_VERBOSE << "Settings loaded" << flush;
     }
 
-    QwtPlotCurve * ArmarXPlotter::createCurve(const QString& label)
+    QwtPlotCurve* ArmarXPlotter::createCurve(const QString& label)
     {
         QwtPlotCurve* curve = new QwtPlotCurve(label);
 
-        curve->setPen( QColor( Qt::GlobalColor((curves.size()+7)%15) ) );
-        curve->setStyle( QwtPlotCurve::Lines );
+        curve->setPen(QColor(Qt::GlobalColor((curves.size() + 7) % 15)));
+        curve->setStyle(QwtPlotCurve::Lines);
 
         curve->attach(ui.qwtPlot);
         showCurve(curve, true);
@@ -397,112 +449,138 @@ namespace armarx
     {
         {
             ScopedLock lock(dataMutex);
-            for(int i = 0; i < selectedChannels.size(); i++){
+
+            for (int i = 0; i < selectedChannels.size(); i++)
+            {
                 ARMARX_VERBOSE << "Channel: " << selectedChannels.at(i).toStdString() << flush;
-                DataFieldIdentifierPtr identifier = new DataFieldIdentifier( selectedChannels.at(i).toStdString());
+                DataFieldIdentifierPtr identifier = new DataFieldIdentifier(selectedChannels.at(i).toStdString());
                 auto prx = getProxy<ObserverInterfacePrx>(identifier->observerName);
 
                 VariantPtr var = VariantPtr::dynamicCast(prx->getDataField(identifier));
-                if(VariantType::IsBasicType(var->getType()))
+
+                if (VariantType::IsBasicType(var->getType()))
                 {
                     QwtPlotCurve* curve = createCurve(selectedChannels.at(i));
-                    curves[selectedChannels.at(i).toStdString()]=curve;
+                    curves[selectedChannels.at(i).toStdString()] = curve;
                 }
                 else
                 {
                     auto id = identifier->getIdentifierStr();
                     ARMARX_IMPORTANT << id;
                     auto dict = JSONObject::ConvertToBasicVariantMap(json, var);
-                    for(auto e : dict)
+
+                    for (auto e : dict)
                     {
                         VariantTypeId type = e.second->getType();
-                        if(type == VariantType::Double
-                                || type == VariantType::Float
-                                || type == VariantType::Int)
+
+                        if (type == VariantType::Double
+                            || type == VariantType::Float
+                            || type == VariantType::Int)
                         {
                             std::string key = id + "." + e.first;
                             ARMARX_INFO << key << ": " << *VariantPtr::dynamicCast(e.second);
                             QwtPlotCurve* curve = createCurve(QString::fromStdString(key));
-                            curves[key]=curve;
+                            curves[key] = curve;
                         }
                     }
                 }
             }
+
             ui.qwtPlot->replot();
         }
         timer->start(updateInterval);
 
-        if(pollingTask)
+        if (pollingTask)
+        {
             pollingTask->stop();
+        }
+
         pollingTask = new PeriodicTask<ArmarXPlotter>(this, & ArmarXPlotter::pollingExec, pollingInterval, false, "DataPollingTask");
         pollingTask->start();
     }
 
-    std::map<string, VariantPtr> ArmarXPlotter::getData(const QStringList &channels, GraphDataMap &dataMaptoAppend)
+    std::map<string, VariantPtr> ArmarXPlotter::getData(const QStringList& channels, GraphDataMap& dataMaptoAppend)
     {
         map< std::string, DataFieldIdentifierBaseList > channelsSplittedByObserver;
         foreach(QString channel, channels)
         {
             DataFieldIdentifierPtr identifier = new DataFieldIdentifier(channel.toStdString());
             channelsSplittedByObserver[identifier->getObserverName()].push_back(identifier);
-//            ARMARX_INFO << identifier;
+            //            ARMARX_INFO << identifier;
         }
         std::map<std::string, VariantPtr> newData;
 
         // first clear to old entries
         auto now = IceUtil::Time::now();
         GraphDataMap::iterator itmap = dataMaptoAppend.begin();
-        for(; itmap != dataMaptoAppend.end(); ++itmap)
+
+        for (; itmap != dataMaptoAppend.end(); ++itmap)
         {
             std::vector<TimeData>& dataVec = itmap->second;
             int stepSize = dataVec.size() * 0.01;
             int thresholdIndex = -1;
-            for(unsigned int i=0; dataVec.size(); i+=stepSize)
+
+            for (unsigned int i = 0; dataVec.size(); i += stepSize)
             {
                 // only delete if entries are older than 2*showninterval
                 // and delete then all entries that are older than showninterval.
                 // otherwise it would delete items on every call, which would be very slow
 
-                if((now - dataVec[i].time).toMilliSecondsDouble() > shownInterval*2*1000
-                        || (thresholdIndex != -1 && (now - dataVec[i].time ).toMilliSecondsDouble() > shownInterval*1000)
-                        )
+                if ((now - dataVec[i].time).toMilliSecondsDouble() > shownInterval * 2 * 1000
+                    || (thresholdIndex != -1 && (now - dataVec[i].time).toMilliSecondsDouble() > shownInterval * 1000)
+                   )
                 {
                     thresholdIndex = i;
-                }else
+                }
+                else
+                {
                     break;
+                }
             }
-            if(thresholdIndex!=-1)
+
+            if (thresholdIndex != -1)
             {
-                unsigned int offset = std::min((int)dataVec.size(),thresholdIndex);
-//                ARMARX_IMPORTANT << "Erasing " << offset << " fields";
-                if(offset>dataVec.size())
+                unsigned int offset = std::min((int)dataVec.size(), thresholdIndex);
+
+                //                ARMARX_IMPORTANT << "Erasing " << offset << " fields";
+                if (offset > dataVec.size())
+                {
                     dataVec.clear();
+                }
                 else
-                    dataVec.erase(dataVec.begin(), dataVec.begin()+offset);
+                {
+                    dataVec.erase(dataVec.begin(), dataVec.begin() + offset);
+                }
             }
-//            ARMARX_IMPORTANT << deactivateSpam(5) << "size: " << dataVec.size();
+
+            //            ARMARX_IMPORTANT << deactivateSpam(5) << "size: " << dataVec.size();
         }
+
         // now get new data
         IceUtil::Time time = IceUtil::Time::now();
         map<string, DataFieldIdentifierBaseList >::iterator it = channelsSplittedByObserver.begin();
+
         try
         {
-            for(; it != channelsSplittedByObserver.end(); ++it)
+            for (; it != channelsSplittedByObserver.end(); ++it)
             {
                 std::string observerName = it->first;
 
-                if(proxyMap.find(observerName) == proxyMap.end())
+                if (proxyMap.find(observerName) == proxyMap.end())
                 {
                     proxyMap[observerName] = getProxy<ObserverInterfacePrx>(observerName);
                 }
+
                 //            QDateTime time(QDateTime::currentDateTime());
                 VariantBaseList variants = proxyMap[observerName]->getDataFields(it->second);
-//                ARMARX_IMPORTANT << "data from observer: " << observerName;
-                for(unsigned int i = 0; i < variants.size(); ++i)
+
+                //                ARMARX_IMPORTANT << "data from observer: " << observerName;
+                for (unsigned int i = 0; i < variants.size(); ++i)
                 {
-//                    ARMARX_IMPORTANT << "Variant: " << VariantPtr::dynamicCast(variants[i]);
+                    //                    ARMARX_IMPORTANT << "Variant: " << VariantPtr::dynamicCast(variants[i]);
                     VariantPtr var = VariantPtr::dynamicCast(variants[i]);
-                    if(VariantType::IsBasicType(var->getType()))
+
+                    if (VariantType::IsBasicType(var->getType()))
                     {
                         dataMaptoAppend[DataFieldIdentifierPtr::dynamicCast(it->second[i])->getIdentifierStr()].push_back(TimeData(time, var));
                         newData[DataFieldIdentifierPtr::dynamicCast(it->second[i])->getIdentifierStr()] = var;
@@ -510,13 +588,14 @@ namespace armarx
                     else
                     {
                         auto id = DataFieldIdentifierPtr::dynamicCast(it->second[i])->getIdentifierStr();
-//                        ARMARX_IMPORTANT << id;
+                        //                        ARMARX_IMPORTANT << id;
                         auto dict = JSONObject::ConvertToBasicVariantMap(json, var);
-                        for(const auto &e : dict)
+
+                        for (const auto& e : dict)
                         {
                             std::string key = id + "." + e.first;
-//                            ARMARX_INFO << key << ": " << *VariantPtr::dynamicCast(e.second);
-                            dataMaptoAppend[key].push_back(TimeData(time,VariantPtr::dynamicCast(e.second)));
+                            //                            ARMARX_INFO << key << ": " << *VariantPtr::dynamicCast(e.second);
+                            dataMaptoAppend[key].push_back(TimeData(time, VariantPtr::dynamicCast(e.second)));
                             newData[key] = VariantPtr::dynamicCast(e.second);
                         }
                     }
@@ -525,16 +604,19 @@ namespace armarx
 
             }
         }
-        catch(Ice::NotRegisteredException &e){
+        catch (Ice::NotRegisteredException& e)
+        {
             ARMARX_WARNING << deactivateSpam(3) << "Caught Ice::NotRegisteredException: " << e.what();
         }
-        catch(exceptions::local::InvalidDataFieldException &e){
+        catch (exceptions::local::InvalidDataFieldException& e)
+        {
             ARMARX_WARNING << deactivateSpam(5) << "Caught InvalidDataFieldException: " << e.what();
         }
-        catch(exceptions::local::InvalidChannelException &e){
+        catch (exceptions::local::InvalidChannelException& e)
+        {
             ARMARX_WARNING << deactivateSpam(5) << "Caught InvalidChannelException: " << e.what();
         }
-        catch(...)
+        catch (...)
         {
             handleExceptions();
         }
@@ -542,16 +624,18 @@ namespace armarx
         return newData;
     }
 
-    void ArmarXPlotter::logToFile(const IceUtil::Time &time, const std::map<std::string, VariantPtr> &dataMaptoAppend)
+    void ArmarXPlotter::logToFile(const IceUtil::Time& time, const std::map<std::string, VariantPtr>& dataMaptoAppend)
     {
 
-        if(logstream.is_open() && dataMaptoAppend.size() > 0)
+        if (logstream.is_open() && dataMaptoAppend.size() > 0)
         {
-            logstream << (time-logStartTime).toMilliSecondsDouble();
-            for(const auto& elem : dataMaptoAppend)
+            logstream << (time - logStartTime).toMilliSecondsDouble();
+
+            for (const auto& elem : dataMaptoAppend)
             {
                 logstream  << "," /*<< elem.first << ","*/ << elem.second->getOutputValueOnly();
             }
+
             logstream  << std::endl;
         }
     }
diff --git a/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotter.h b/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotter.h
index 0feebafb9a3defdd6401acd3b16209fe3e97111e..3a816fa47a186af11a18b4235966c204ba412671 100644
--- a/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotter.h
+++ b/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotter.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::Gui
 * @author     Mirko Waechter ( mirko.waechter at kit dot edu)
 * @date       2012
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -27,17 +26,17 @@
 #include "ui_ArmarXPlotter.h"
 
 // ArmarX
-#include <Gui/libraries/ArmarXGuiBase/ArmarXComponentWidgetController.h>
-#include <Gui/gui-plugins/ObserverPropertiesPlugin/ObserverItemModel.h>
-
-#include <Core/core/Component.h>
-#include <Core/core/system/ImportExportComponent.h>
-#include <Core/core/system/AbstractFactoryMethod.h>
-#include <Core/interface/observers/ConditionHandlerInterface.h>
-#include <Core/observers/variant/DataFieldIdentifier.h>
-#include <Core/observers/variant/Variant.h>
-#include <Core/util/json/JSONObject.h>
-#include <Core/core/services/tasks/PeriodicTask.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXComponentWidgetController.h>
+#include <ArmarXGui/gui-plugins/ObserverPropertiesPlugin/ObserverItemModel.h>
+
+#include <ArmarXCore/core/Component.h>
+#include <ArmarXCore/core/system/ImportExportComponent.h>
+#include <ArmarXCore/core/system/AbstractFactoryMethod.h>
+#include <ArmarXCore/interface/observers/ConditionHandlerInterface.h>
+#include <ArmarXCore/observers/variant/DataFieldIdentifier.h>
+#include <ArmarXCore/observers/variant/Variant.h>
+#include <ArmarXCore/util/json/JSONObject.h>
+#include <ArmarXCore/core/services/tasks/PeriodicTask.h>
 
 // QT
 #include <QWidget>
@@ -52,8 +51,9 @@ class QwtPlotCurve;
 
 namespace armarx
 {
-    struct TimeData{
-        TimeData(const IceUtil::Time &time, const VariantPtr &data): time(time), data(data){}
+    struct TimeData
+    {
+        TimeData(const IceUtil::Time& time, const VariantPtr& data): time(time), data(data) {}
 
         IceUtil::Time time;
         VariantPtr data;
@@ -64,24 +64,24 @@ namespace armarx
 
     class ArmarXPlotterDialog;
     /*!
-     * \class ArmarXPlotter
+     * \page RobotAPI-GuiPlugins-ArmarXPlotter ArmarXPlotter
      * \brief The plotter widget allows the user to plot any sensor channel.
      * \image html PlotterGUI.png
      * A sensor channel can be selected for plotting by clicking the wrench button at the bottom.
      * \ingroup RobotAPI-ArmarXGuiPlugins ArmarXGuiPlugins
       */
     class ARMARXCOMPONENT_IMPORT_EXPORT
-    ArmarXPlotter:
-            public ArmarXComponentWidgetController
+        ArmarXPlotter:
+        public ArmarXComponentWidgetController
     {
         Q_OBJECT
     public:
 
 
-        std::map<std::string, QwtPlotCurve *> curves;
+        std::map<std::string, QwtPlotCurve*> curves;
         Ui::ArmarXPlotter ui;
         QPointer<ArmarXPlotterDialog> dialog;
-        QTimer * timer;
+        QTimer* timer;
         ConditionHandlerInterfacePrx handler;
 
         // Configuration Parameters
@@ -93,9 +93,12 @@ namespace armarx
         explicit ArmarXPlotter();
         ~ArmarXPlotter();
         //inherited from ArmarXWidget
-        virtual QString getWidgetName() const { return "Observers.Plotter";}
-        void loadSettings(QSettings * settings);
-        void saveSettings(QSettings * settings);
+        virtual QString getWidgetName() const
+        {
+            return "Observers.Plotter";
+        }
+        void loadSettings(QSettings* settings);
+        void saveSettings(QSettings* settings);
         //for AbstractFactoryMethod class
 
 
@@ -109,15 +112,15 @@ namespace armarx
         /**
         * emits the closeRequest signal
         */
-        void onCloseWidget(QCloseEvent *event);
-        QwtPlotCurve * createCurve(const QString &label);
+        void onCloseWidget(QCloseEvent* event);
+        QwtPlotCurve* createCurve(const QString& label);
     signals:
 
     public slots:
         void ButtonAddSensorChannelClicked();
         void configDialog();
         void updateGraph();
-        void showCurve(QwtPlotItem *item, bool on);
+        void showCurve(QwtPlotItem* item, bool on);
         void autoScale(bool toggled);
         void plottingPaused(bool toggled);
         void configDone();
@@ -137,8 +140,8 @@ namespace armarx
         JSONObjectPtr json;
 
 
-        std::map<std::string, VariantPtr> getData(const QStringList &channels, GraphDataMap &dataMaptoAppend);
-        void logToFile(const IceUtil::Time &time,const std::map<std::string, VariantPtr> &dataMaptoAppend);
+        std::map<std::string, VariantPtr> getData(const QStringList& channels, GraphDataMap& dataMaptoAppend);
+        void logToFile(const IceUtil::Time& time, const std::map<std::string, VariantPtr>& dataMaptoAppend);
 
         Mutex dataMutex;
         PeriodicTask<ArmarXPlotter>::pointer_type pollingTask;
diff --git a/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotterDialog.cpp b/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotterDialog.cpp
index 9ec9e79858fa043994e6cd3a0c832f68a208d62a..30a7d58446425fd5044e3b6835a68f90cbe05380 100644
--- a/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotterDialog.cpp
+++ b/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotterDialog.cpp
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::Gui
 * @author     Mirko Waechter ( mirko.waechter at kit dot edu)
 * @date       2012
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -34,7 +33,7 @@ using namespace armarx;
 using namespace std;
 
 
-ArmarXPlotterDialog::ArmarXPlotterDialog(QWidget *parent, IceManagerPtr iceManager) :
+ArmarXPlotterDialog::ArmarXPlotterDialog(QWidget* parent, IceManagerPtr iceManager) :
     QDialog(parent),
     uuid(IceUtil::generateUUID()),
     iceManager(iceManager)
@@ -54,7 +53,7 @@ ArmarXPlotterDialog::ArmarXPlotterDialog(QWidget *parent, IceManagerPtr iceManag
 
 ArmarXPlotterDialog::~ArmarXPlotterDialog()
 {
-//    ARMARX_INFO << "~ArmarXPlotterDialog" ;
+    //    ARMARX_INFO << "~ArmarXPlotterDialog" ;
 }
 
 void ArmarXPlotterDialog::setIceManager(IceManagerPtr iceManager)
@@ -90,32 +89,32 @@ void ArmarXPlotterDialog::setIceManager(IceManagerPtr iceManager)
 
 //}
 
-void ArmarXPlotterDialog::onCloseWidget(QCloseEvent *event)
+void ArmarXPlotterDialog::onCloseWidget(QCloseEvent* event)
 {
 
 }
 
 void ArmarXPlotterDialog::updateObservers()
 {
-    if(!model)
+    if (!model)
     {
         model = new ObserverItemModel(iceManager);
         ui.treeViewObservers->setModel(model);
 
     }
 
-        model->updateObservers();
+    model->updateObservers();
 
-//    if(!iceManager)
-//        return;
-//    ObserverList observerList = iceManager->getIceGridSession()->getRegisteredObjectNames<ObserverInterfacePrx>("*Observer");
-//    ObserverList::iterator iter = observerList.begin();
+    //    if(!iceManager)
+    //        return;
+    //    ObserverList observerList = iceManager->getIceGridSession()->getRegisteredObjectNames<ObserverInterfacePrx>("*Observer");
+    //    ObserverList::iterator iter = observerList.begin();
 
-//    while(iter != observerList.end())
-//    {
-//        model->updateModel(*iter, iceManager->getProxy<ObserverInterfacePrx>(*iter)->getAvailableChannels(), StringConditionCheckMap());
-//        iter++;
-//    }
+    //    while(iter != observerList.end())
+    //    {
+    //        model->updateModel(*iter, iceManager->getProxy<ObserverInterfacePrx>(*iter)->getAvailableChannels(), StringConditionCheckMap());
+    //        iter++;
+    //    }
 }
 
 
@@ -125,20 +124,23 @@ void ArmarXPlotterDialog::updateObservers()
 
 void ArmarXPlotterDialog::ButtonAddSelectedChannelClicked()
 {
-     QItemSelectionModel* selectionModel = ui.treeViewObservers->selectionModel();
-     for(int i = 0; i < selectionModel->selectedIndexes().size(); ++i)
-     {
-         QModelIndex index = selectionModel->selectedIndexes().at(i);
-         treeView_doubleClick(index);
-     }
-     ui.treeViewObservers->clearSelection();
+    QItemSelectionModel* selectionModel = ui.treeViewObservers->selectionModel();
+
+    for (int i = 0; i < selectionModel->selectedIndexes().size(); ++i)
+    {
+        QModelIndex index = selectionModel->selectedIndexes().at(i);
+        treeView_doubleClick(index);
+    }
+
+    ui.treeViewObservers->clearSelection();
 
 }
 
 void ArmarXPlotterDialog::ButtonRemoveChannelClicked()
 {
     QList<QListWidgetItem*> selectedItems = ui.listWidget->selectedItems();
-    for(int i=0; i < selectedItems.size(); ++i)
+
+    for (int i = 0; i < selectedItems.size(); ++i)
     {
         delete selectedItems.at(i);
     }
@@ -146,15 +148,15 @@ void ArmarXPlotterDialog::ButtonRemoveChannelClicked()
 
 void ArmarXPlotterDialog::ButtonRemoveChannelClicked(QModelIndex index)
 {
-     delete ui.listWidget->item(index.row());
+    delete ui.listWidget->item(index.row());
 }
 
 QStringList ArmarXPlotterDialog::getSelectedChannels()
 {
     QStringList result;
     QList <QListWidgetItem*> items = ui.listWidget->findItems(QString("*"), Qt::MatchWrap | Qt::MatchWildcard);
-    foreach(QListWidgetItem *item, items)
-      result.append(item->text());
+    foreach(QListWidgetItem * item, items)
+    result.append(item->text());
 
     return result;
 }
@@ -163,27 +165,31 @@ void ArmarXPlotterDialog::treeView_selected(const QItemSelection& selected, cons
 {
 }
 
-void ArmarXPlotterDialog::treeView_doubleClick(const QModelIndex &index)
+void ArmarXPlotterDialog::treeView_doubleClick(const QModelIndex& index)
 {
 
-        QStandardItem* item = model->itemFromIndex(index);
-        QVariant id = item->data(OBSERVER_ITEM_ID);
-        switch(item->data(OBSERVER_ITEM_TYPE).toInt())
-        {
+    QStandardItem* item = model->itemFromIndex(index);
+    QVariant id = item->data(OBSERVER_ITEM_ID);
+
+    switch (item->data(OBSERVER_ITEM_TYPE).toInt())
+    {
         case eDataFieldItem:
-            if(ui.listWidget->findItems(id.toString(),Qt::MatchExactly).size() == 0)
+            if (ui.listWidget->findItems(id.toString(), Qt::MatchExactly).size() == 0)
+            {
                 ui.listWidget->addItem(id.toString());
+            }
+
             break;
 
-        }
+    }
 }
 
-void ArmarXPlotterDialog::destroyed(QObject *)
+void ArmarXPlotterDialog::destroyed(QObject*)
 {
     setParent(0);
 }
 
-void ArmarXPlotterDialog::showEvent(QShowEvent *)
+void ArmarXPlotterDialog::showEvent(QShowEvent*)
 {
     updateObservers();
 }
@@ -192,8 +198,9 @@ void ArmarXPlotterDialog::showEvent(QShowEvent *)
 void armarx::ArmarXPlotterDialog::on_btnSelectLoggingDir_clicked()
 {
     QString newLoggingDir = QFileDialog::getExistingDirectory(this, "Select a directory to which data should be logged",
-                                                              ui.editLoggingDirectory->text());
-    if(!newLoggingDir.isEmpty())
+                            ui.editLoggingDirectory->text());
+
+    if (!newLoggingDir.isEmpty())
     {
         ui.editLoggingDirectory->setText(newLoggingDir);
     }
diff --git a/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotterDialog.h b/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotterDialog.h
index d00f727f7498525a0a46b646a1b80278626b94dc..b912d58f87489648f888fe40ee6e94a099536571 100644
--- a/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotterDialog.h
+++ b/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotterDialog.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::Gui
 * @author     Mirko Waechter ( mirko.waechter at kit dot edu)
 * @date       2012
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -28,10 +27,10 @@
 // QT
 #include "ui_ArmarXPlotterDialog.h"
 
-#include <Gui/gui-plugins/ObserverPropertiesPlugin/ObserverItemModel.h>
+#include <ArmarXGui/gui-plugins/ObserverPropertiesPlugin/ObserverItemModel.h>
 
-#include <Core/core/IceManager.h>
-#include <Core/interface/observers/ConditionHandlerInterface.h>
+#include <ArmarXCore/core/IceManager.h>
+#include <ArmarXCore/interface/observers/ConditionHandlerInterface.h>
 
 #include <QDialog>
 #include <QComboBox>
@@ -48,24 +47,25 @@ namespace armarx
 {
     class ArmarXPlotter;
     class ArmarXPlotterDialog:
-            public QDialog
+        public QDialog
     {
         Q_OBJECT
         QStringList availableChannelsList;
-        ObserverItemModel *model;
+        ObserverItemModel* model;
         std::string uuid;
         IceManagerPtr iceManager;
         int mdiId;
 
 
     public:
-        ArmarXPlotterDialog(QWidget *parent, IceManagerPtr iceManager);
+        ArmarXPlotterDialog(QWidget* parent, IceManagerPtr iceManager);
         ~ArmarXPlotterDialog();
         ConditionHandlerInterfacePrx handler;
-        struct ChannelWidgetsEntry{
+        struct ChannelWidgetsEntry
+        {
             QComboBox* comboBox;
-            QLabel *label;
-            QPushButton *deleteButton;
+            QLabel* label;
+            QPushButton* deleteButton;
         };
 
         void setIceManager(IceManagerPtr iceManager);
@@ -75,24 +75,24 @@ namespace armarx
         QStringList getSelectedChannels();
 
 
-//        // inherited from Component
-//        std::string getDefaultName() const;
-//        virtual void onInitComponent();
-//        virtual void onConnectComponent();
-//        void onExitComponent();
+        //        // inherited from Component
+        //        std::string getDefaultName() const;
+        //        virtual void onInitComponent();
+        //        virtual void onConnectComponent();
+        //        void onExitComponent();
         /**
         * emits the closeRequest signal
         */
-        void onCloseWidget(QCloseEvent *event);
+        void onCloseWidget(QCloseEvent* event);
     public slots:
         void ButtonAddSelectedChannelClicked();
         void ButtonRemoveChannelClicked();
         void ButtonRemoveChannelClicked(QModelIndex index);
         void updateObservers();
         void treeView_selected(const QItemSelection& selected, const QItemSelection& deselected);
-        void treeView_doubleClick(const QModelIndex &index);
-        void destroyed(QObject *);
-        void showEvent(QShowEvent *);
+        void treeView_doubleClick(const QModelIndex& index);
+        void destroyed(QObject*);
+        void showEvent(QShowEvent*);
     private slots:
         void on_btnSelectLoggingDir_clicked();
     };
diff --git a/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotterDialog.ui b/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotterDialog.ui
index 62c86008dda2fa7387acecb86720ed205d32444c..4a739efbff645b4943a9e3b245516f36c695245d 100644
--- a/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotterDialog.ui
+++ b/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotterDialog.ui
@@ -254,7 +254,7 @@
   <customwidget>
    <class>FilterableTreeView</class>
    <extends>QTreeView</extends>
-   <header location="global">Gui/libraries/ArmarXGuiBase/widgets/FilterableTreeView.h</header>
+   <header location="global">ArmarXGui/libraries/ArmarXGuiBase/widgets/FilterableTreeView.h</header>
   </customwidget>
  </customwidgets>
  <resources/>
diff --git a/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMover.cpp b/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMover.cpp
index 44dcd92fdae74b5b70699cbfb595d0c08948aae9..80b861c28d248f67d375eb5b4e3860f354d660f5 100644
--- a/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMover.cpp
+++ b/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMover.cpp
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::
 * @author     Mirko Waechter ( mirko.waechter at kit dot edu)
 * @date       2012
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -47,8 +46,8 @@ TCPMover::TCPMover() :
 
 {
 
-//    handData[selectedTCP][0] = handData[selectedTCP][1] = handData[selectedTCP][2] = 0.0f;
-//    handData[selectedTCP][3] = handData[selectedTCP][4] = handData[selectedTCP][5] = 0.0f;
+    //    handData[selectedTCP][0] = handData[selectedTCP][1] = handData[selectedTCP][2] = 0.0f;
+    //    handData[selectedTCP][3] = handData[selectedTCP][4] = handData[selectedTCP][5] = 0.0f;
     ui.setupUi(getWidget());
     ui.gridLayout->setEnabled(false);
     // SIGNALS AND SLOTS CONNECTIONS
@@ -80,20 +79,23 @@ TCPMover::~TCPMover()
 
 
 
-void armarx::TCPMover::loadSettings(QSettings *settings)
+void armarx::TCPMover::loadSettings(QSettings* settings)
 {
     tcpMoverUnitName = settings->value("TCPControlUnitName", "TCPControlUnit").toString().toStdString();
 }
 
-void armarx::TCPMover::saveSettings(QSettings *settings)
+void armarx::TCPMover::saveSettings(QSettings* settings)
 {
     settings->setValue("TCPControlUnitName", tcpMoverUnitName.c_str());
 }
 
-QPointer<QDialog> TCPMover::getConfigDialog(QWidget *parent)
+QPointer<QDialog> TCPMover::getConfigDialog(QWidget* parent)
 {
-    if(!configDialog)
+    if (!configDialog)
+    {
         configDialog = new TCPMoverConfigDialog(parent);
+    }
+
     return qobject_cast<TCPMoverConfigDialog*>(configDialog);
 }
 
@@ -107,19 +109,19 @@ void TCPMover::configured()
 
 void armarx::TCPMover::onInitComponent()
 {
-//    kinematicUnitFile = getProperty<std::string>("RobotFileName", KINEMATIC_UNIT_FILE_DEFAULT).getValueOrDefault();
-//    kinematicUnitName = getProperty<std::string>("RobotNodeSetName",KINEMATIC_UNIT_NAME_DEFAULT).getValueOrDefault();
+    //    kinematicUnitFile = getProperty<std::string>("RobotFileName", KINEMATIC_UNIT_FILE_DEFAULT).getValueOrDefault();
+    //    kinematicUnitName = getProperty<std::string>("RobotNodeSetName",KINEMATIC_UNIT_NAME_DEFAULT).getValueOrDefault();
 
-//    // Load Robot
-//    ARMARX_VERBOSE << ": Loading KinematicUnit " << kinematicUnitName << " from '" << kinematicUnitFile << "' ..." << flush;
-//    robot = RobotIO::loadRobot(kinematicUnitFile);
-//    if (!robot)
-//    {
-//        ARMARX_ERROR << "Could not find Robot XML file with name '" << kinematicUnitFile << "'" << flush;
-//    }
+    //    // Load Robot
+    //    ARMARX_VERBOSE << ": Loading KinematicUnit " << kinematicUnitName << " from '" << kinematicUnitFile << "' ..." << flush;
+    //    robot = RobotIO::loadRobot(kinematicUnitFile);
+    //    if (!robot)
+    //    {
+    //        ARMARX_ERROR << "Could not find Robot XML file with name '" << kinematicUnitFile << "'" << flush;
+    //    }
 
 
-//    usingProxy(kinematicUnitName);
+    //    usingProxy(kinematicUnitName);
     usingProxy(tcpMoverUnitName);
     usingProxy("RobotStateComponent");
 
@@ -134,53 +136,59 @@ void armarx::TCPMover::onConnectComponent()
     robotPrx = robotStateComponentPrx->getSynchronizedRobot();
     NameList nodeSets = robotPrx->getRobotNodeSets();
     QStringList nodeSetsQStr;
-    for(unsigned int i=0; i < nodeSets.size(); i++)
+
+    for (unsigned int i = 0; i < nodeSets.size(); i++)
     {
-        if(!robotPrx->getRobotNodeSet(nodeSets.at(i))->tcpName.empty())
+        if (!robotPrx->getRobotNodeSet(nodeSets.at(i))->tcpName.empty())
         {
             tcpData[nodeSets.at(i)].resize(6, 0.f);
             nodeSetsQStr << QString::fromStdString(nodeSets.at(i));
         }
     }
+
     QString selected = ui.cbselectedTCP->currentText();
     ui.cbselectedTCP->clear();
     ui.cbselectedTCP->addItems(nodeSetsQStr);
     int index = ui.cbselectedTCP->findText(selected);
-    if(index != -1)
+
+    if (index != -1)
+    {
         ui.cbselectedTCP->setCurrentIndex(index);
+    }
+
     refFrame = robotStateComponentPrx->getSynchronizedRobot()->getRootNode()->getName();
 
-//    kinematicUnitPrx = getProxy<KinematicUnitInterfacePrx>(kinematicUnitName);
-
-//    tcpNodeSetName = "LARM";
-//    tcpNodeSet = robot->getRobotNodeSet(tcpNodeSetName);
-//    NameControlModeMap modeMap;
-//    for(unsigned int i = 0; i < tcpNodeSet->getSize(); i++)
-//    {
-//        modeMap[tcpNodeSet->getNode(i)->getName()] = eVelocityControl;
-//    }
-//    kinematicUnitPrx->switchControlMode(modeMap);
-//    ik = DifferentialIKPtr(new DifferentialIK(tcpNodeSet));
+    //    kinematicUnitPrx = getProxy<KinematicUnitInterfacePrx>(kinematicUnitName);
+
+    //    tcpNodeSetName = "LARM";
+    //    tcpNodeSet = robot->getRobotNodeSet(tcpNodeSetName);
+    //    NameControlModeMap modeMap;
+    //    for(unsigned int i = 0; i < tcpNodeSet->getSize(); i++)
+    //    {
+    //        modeMap[tcpNodeSet->getNode(i)->getName()] = eVelocityControl;
+    //    }
+    //    kinematicUnitPrx->switchControlMode(modeMap);
+    //    ik = DifferentialIKPtr(new DifferentialIK(tcpNodeSet));
     ui.gridLayout->setEnabled(false);
 }
 
 void TCPMover::onExitComponent()
 {
 
-//    if(robotRequested)
-//        kinematicUnitPrx->release();
+    //    if(robotRequested)
+    //        kinematicUnitPrx->release();
 }
 
 void TCPMover::moveUp()
 {
-//    moveRelative(-1,0,0);
+    //    moveRelative(-1,0,0);
     tcpData[selectedTCP][0]++;
     execMove();
 }
 
 void TCPMover::moveDown()
 {
-//    moveRelative(1,0,0);
+    //    moveRelative(1,0,0);
     tcpData[selectedTCP][0]--;
     execMove();
 }
@@ -199,7 +207,7 @@ void TCPMover::moveZDown()
 
 void TCPMover::moveLeft()
 {
-//    moveRelative(0,1,0);
+    //    moveRelative(0,1,0);
     tcpData[selectedTCP][1] ++;
     execMove();
 
@@ -258,35 +266,35 @@ void TCPMover::stopMoving()
 
 void TCPMover::reset()
 {
-     tcpData[selectedTCP][0] = tcpData[selectedTCP][1] = tcpData[selectedTCP][2] = 0.0f;
-     tcpData[selectedTCP].at(3) = tcpData[selectedTCP].at(4) = tcpData[selectedTCP].at(5) = 0.0f;
-     execMove();
-     tcpMoverUnitPrx->release();
-//     tcpMoverUnitPrx->resetArmToHomePosition(eLeftHand);
+    tcpData[selectedTCP][0] = tcpData[selectedTCP][1] = tcpData[selectedTCP][2] = 0.0f;
+    tcpData[selectedTCP].at(3) = tcpData[selectedTCP].at(4) = tcpData[selectedTCP].at(5) = 0.0f;
+    execMove();
+    tcpMoverUnitPrx->release();
+    //     tcpMoverUnitPrx->resetArmToHomePosition(eLeftHand);
 
 }
 
 void TCPMover::robotControl(bool request)
 {
     tcpMoverUnitPrx->request();
-//    try{
-//        if(request)
-//            kinematicUnitPrx->request();
-//        else
-//            kinematicUnitPrx->release();
-//    }catch(ResourceUnavailableException &e){
-//        ui.BtnRequestControl->setChecked(false);
-
-//    }catch(ResourceNotOwnedException &e){
-//        ui.BtnRequestControl->setChecked(true);
-//    }
-//    robotRequested = ui.BtnRequestControl->isChecked();
+    //    try{
+    //        if(request)
+    //            kinematicUnitPrx->request();
+    //        else
+    //            kinematicUnitPrx->release();
+    //    }catch(ResourceUnavailableException &e){
+    //        ui.BtnRequestControl->setChecked(false);
+
+    //    }catch(ResourceNotOwnedException &e){
+    //        ui.BtnRequestControl->setChecked(true);
+    //    }
+    //    robotRequested = ui.BtnRequestControl->isChecked();
 
 }
 
 void TCPMover::selectHand(int index)
 {
-    selectedTCP = ui.cbselectedTCP->itemText(index).toStdString();    
+    selectedTCP = ui.cbselectedTCP->itemText(index).toStdString();
 }
 
 void TCPMover::execMove()
@@ -305,55 +313,61 @@ void TCPMover::execMove()
     const auto agentName = robotPrx->getName();
     FramedDirectionPtr tcpVel = new FramedDirection(vec, refFrame, agentName);
     Eigen::Vector3f vecOri;
-    vecOri << tcpData[selectedTCP].at(3)/180.f*3.145f, tcpData[selectedTCP].at(4)/180.f*3.145f, tcpData[selectedTCP].at(5)/180.f*3.145f;
+    vecOri << tcpData[selectedTCP].at(3) / 180.f * 3.145f, tcpData[selectedTCP].at(4) / 180.f * 3.145f, tcpData[selectedTCP].at(5) / 180.f * 3.145f;
     vecOri *= ui.sbFactor->value();
     FramedDirectionPtr tcpOri = new FramedDirection(vecOri, refFrame, agentName);
 
-    if(!ui.cbTranslation->isChecked() )
+    if (!ui.cbTranslation->isChecked())
+    {
         tcpVel = NULL;
-    if(!ui.cbOrientation->isChecked() )
+    }
+
+    if (!ui.cbOrientation->isChecked())
+    {
         tcpOri = NULL;
-    tcpMoverUnitPrx->begin_setTCPVelocity(selectedTCP,ui.edtTCPName->text().toStdString(), tcpVel,tcpOri);
+    }
+
+    tcpMoverUnitPrx->begin_setTCPVelocity(selectedTCP, ui.edtTCPName->text().toStdString(), tcpVel, tcpOri);
 
-//    tcpMoverUnitPrx->setCartesianTCPVelocity(selectedTCP, handData[selectedTCP][0], handData[selectedTCP][1], handData[selectedTCP][2], ui.sbFactor->value());
-//    tcpMoverUnitPrx->setTCPOrientation(selectedTCP, handData[selectedTCP].at(3)/180.f*3.145f, handData[selectedTCP].at(4)/180.f*3.145f, handData[selectedTCP].at(5)/180.f*3.145f);
+    //    tcpMoverUnitPrx->setCartesianTCPVelocity(selectedTCP, handData[selectedTCP][0], handData[selectedTCP][1], handData[selectedTCP][2], ui.sbFactor->value());
+    //    tcpMoverUnitPrx->setTCPOrientation(selectedTCP, handData[selectedTCP].at(3)/180.f*3.145f, handData[selectedTCP].at(4)/180.f*3.145f, handData[selectedTCP].at(5)/180.f*3.145f);
 }
 
 void TCPMover::moveRelative(float x, float y, float z)
 {
-//    RobotNodePtr tcpNode = tcpNodeSet->getTCP();
-//    // calculate cartesian error
-//    Eigen::Matrix4f newPosRelative;
-//    newPosRelative
-//            << 1, 0, 0, 10*ui.sbFactor->value(),
-//               0, 1, 0, 0,
-//               0, 0, 1, 0,
-//               0, 0, 0, 1;
-//    Eigen::VectorXf errorCartVec(3);
-//    errorCartVec << x*ui.sbFactor->value(),y*ui.sbFactor->value(),z*ui.sbFactor->value();
-////    errorCartVec.segment(0,3) = newPosRelative.block(0,3,3,1);
-
-
-
-
-//    Eigen::MatrixXf Ji = ik->getPseudoInverseJacobianMatrix(tcpNode, IKSolver::Position);
-//    // calculat joint error
-//    Eigen::VectorXf errorJoint(tcpNodeSet->getSize());
-//    errorJoint = Ji * errorCartVec;
-//    std::vector<float> angles = tcpNodeSet->getJointValues();
-//    std::vector<float> targetAngles(tcpNodeSet->getSize());
-//    NameValueMap targetAnglesMap;
-
-//    for(unsigned int i = 0; i < tcpNodeSet->getSize(); i++)
-//    {
-////        float newAngle = angles[i] + errorJoint(i);
-//        float newAngle = errorJoint(i);
-//        targetAngles[i] = newAngle;
-//        targetAnglesMap[tcpNodeSet->getNode(i)->getName()] = newAngle;
-//        //ARMARX_VERBOSE << tcpNodeSet->getNode(i)->getName() << ": " << newAngle;
-//    }
-//    tcpNodeSet->setJointValues(targetAngles);
-//    kinematicUnitPrx->setJointVelocities(targetAnglesMap);
+    //    RobotNodePtr tcpNode = tcpNodeSet->getTCP();
+    //    // calculate cartesian error
+    //    Eigen::Matrix4f newPosRelative;
+    //    newPosRelative
+    //            << 1, 0, 0, 10*ui.sbFactor->value(),
+    //               0, 1, 0, 0,
+    //               0, 0, 1, 0,
+    //               0, 0, 0, 1;
+    //    Eigen::VectorXf errorCartVec(3);
+    //    errorCartVec << x*ui.sbFactor->value(),y*ui.sbFactor->value(),z*ui.sbFactor->value();
+    ////    errorCartVec.segment(0,3) = newPosRelative.block(0,3,3,1);
+
+
+
+
+    //    Eigen::MatrixXf Ji = ik->getPseudoInverseJacobianMatrix(tcpNode, IKSolver::Position);
+    //    // calculat joint error
+    //    Eigen::VectorXf errorJoint(tcpNodeSet->getSize());
+    //    errorJoint = Ji * errorCartVec;
+    //    std::vector<float> angles = tcpNodeSet->getJointValues();
+    //    std::vector<float> targetAngles(tcpNodeSet->getSize());
+    //    NameValueMap targetAnglesMap;
+
+    //    for(unsigned int i = 0; i < tcpNodeSet->getSize(); i++)
+    //    {
+    ////        float newAngle = angles[i] + errorJoint(i);
+    //        float newAngle = errorJoint(i);
+    //        targetAngles[i] = newAngle;
+    //        targetAnglesMap[tcpNodeSet->getNode(i)->getName()] = newAngle;
+    //        //ARMARX_VERBOSE << tcpNodeSet->getNode(i)->getName() << ": " << newAngle;
+    //    }
+    //    tcpNodeSet->setJointValues(targetAngles);
+    //    kinematicUnitPrx->setJointVelocities(targetAnglesMap);
 }
 
 
diff --git a/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMover.h b/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMover.h
index ff30cecd4c941193dc758574dc3525b57d0ffa26..7acdeea5db1393b4f6b7add72aa4a49e4faf7ddc 100644
--- a/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMover.h
+++ b/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMover.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::
 * @author     Mirko Waechter ( mirko.waechter at kit dot edu)
 * @date       2012
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -36,9 +35,9 @@
 #include <VirtualRobot/Nodes/RobotNode.h>
 #include <VirtualRobot/RobotNodeSet.h>
 #include <VirtualRobot/IK/DifferentialIK.h>
-#include <Gui/libraries/ArmarXGuiBase/widgets/IceProxyFinder.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/widgets/IceProxyFinder.h>
 
-#include <Gui/libraries/ArmarXGuiBase/ArmarXComponentWidgetController.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXComponentWidgetController.h>
 
 // Qt includes
 #include <QDialog>
@@ -49,7 +48,8 @@
 
 class QDialogButtonBox;
 
-namespace armarx {
+namespace armarx
+{
 
     /*class TCPMoverConfigDialog : public QDialog
     {
@@ -70,12 +70,14 @@ namespace armarx {
     };*/
 
 
-    /*
-     * @brief The TCPMover widget...
-     * @ingroup RobotAPI-ArmarXGuiPlugins ArmarXGuiPlugins
-    */
+    /**
+     * \page RobotAPI-GuiPlugins-TCPMover TCPMoverPlugin
+     * @brief The TCPMover widget allows direct control of a TCP.
+     *
+     * \image html TCPMoverGUI.png
+     */
     class TCPMover :
-            public ArmarXComponentWidgetController
+        public ArmarXComponentWidgetController
     {
         Q_OBJECT
 
@@ -83,12 +85,21 @@ namespace armarx {
         TCPMover();
         ~TCPMover();
         //inherited from ArmarXMdiWidget
-        void loadSettings(QSettings * settings);
-        void saveSettings(QSettings * settings);
-        virtual QString getWidgetName() const { return "RobotControl.TCPMover"; }
-        virtual QIcon getWidgetIcon() const { return QIcon("://icons/games.ico"); }
-        virtual QIcon getWidgetCategoryIcon() const { return QIcon("://icons/games.ico"); }
-        QPointer<QDialog> getConfigDialog(QWidget *parent = 0);
+        void loadSettings(QSettings* settings);
+        void saveSettings(QSettings* settings);
+        virtual QString getWidgetName() const
+        {
+            return "RobotControl.TCPMover";
+        }
+        virtual QIcon getWidgetIcon() const
+        {
+            return QIcon("://icons/games.ico");
+        }
+        virtual QIcon getWidgetCategoryIcon() const
+        {
+            return QIcon("://icons/games.ico");
+        }
+        QPointer<QDialog> getConfigDialog(QWidget* parent = 0);
         void configured();
 
         // inherited from Component
@@ -123,8 +134,8 @@ namespace armarx {
         std::map<std::string, std::vector<float> > tcpData;
         std::string selectedTCP;
         std::string refFrame;
-//        float velocities[2][3];
-//        float orientation[2][3];
+        //        float velocities[2][3];
+        //        float orientation[2][3];
         NameValueMap velocityMap;
         bool robotRequested;
         VirtualRobot::RobotNodeSetPtr tcpNodeSet;
diff --git a/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMoverConfigDialog.cpp b/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMoverConfigDialog.cpp
index daee4b75e7d688de3711aa444dcbf4509be9fcdc..4ec8ad2b5b6d31bf2091cb013c5d1eadded6e607 100644
--- a/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMoverConfigDialog.cpp
+++ b/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMoverConfigDialog.cpp
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::
 * @author     Nikolaus Vahrenkamp ( vahrenkamp at kit dot edu)
 * @date       2012
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -28,7 +27,7 @@
 
 #include <RobotAPI/interface/units/TCPControlUnit.h>
 
-armarx::TCPMoverConfigDialog::TCPMoverConfigDialog(QWidget *parent) :
+armarx::TCPMoverConfigDialog::TCPMoverConfigDialog(QWidget* parent) :
     QDialog(parent),
     ui(new Ui::TCPMoverConfigDialog),
     uuid(IceUtil::generateUUID())
diff --git a/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMoverConfigDialog.h b/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMoverConfigDialog.h
index 93ee533c9a575d7f3ec2fc9ee051f81b4f140538..c468ac34b4f979311ec5c6cb11d37dc3e70f3b78 100644
--- a/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMoverConfigDialog.h
+++ b/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMoverConfigDialog.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::
 * @author     Nikolaus Vahrenkamp ( vahrenkamp at kit dot edu)
 * @date       2012
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -26,11 +25,12 @@
 
 #include <QDialog>
 
-#include <Core/core/IceManager.h>
+#include <ArmarXCore/core/IceManager.h>
 
-#include <Gui/libraries/ArmarXGuiBase/widgets/IceProxyFinder.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/widgets/IceProxyFinder.h>
 
-namespace Ui {
+namespace Ui
+{
     class TCPMoverConfigDialog;
 }
 
@@ -43,17 +43,20 @@ namespace armarx
         Q_OBJECT
 
     public:
-        explicit TCPMoverConfigDialog(QWidget *parent = 0);
+        explicit TCPMoverConfigDialog(QWidget* parent = 0);
         ~TCPMoverConfigDialog();
 
     protected:
         // ManagedIceObject interface
-        std::string getDefaultName() const { return "TCPMoverConfigDialog" + uuid;}
+        std::string getDefaultName() const
+        {
+            return "TCPMoverConfigDialog" + uuid;
+        }
         void onInitComponent();
         void onConnectComponent();
 
     private:
-        Ui::TCPMoverConfigDialog *ui;
+        Ui::TCPMoverConfigDialog* ui;
 
         IceProxyFinderBase* proxyFinder;
         std::string uuid;
diff --git a/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/CMakeLists.txt b/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/CMakeLists.txt
index 6af60797d179f1179299719dc1c973bee7c2e835..48671d0e8edda743e028eec78bfca31ce88660df 100644
--- a/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/CMakeLists.txt
+++ b/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/CMakeLists.txt
@@ -66,9 +66,9 @@ set(GUI_UIS
 
 set(COMPONENT_LIBS RobotAPIUnits ArmarXCoreObservers ObserverPropertiesGuiPlugin RobotAPIInterfaces ${qwt_LIBRARIES} ${Simox_LIBRARIES} ${QT_LIBRARIES})
 
-set(LIB_VERSION    0.1.0)
-set(LIB_SOVERSION  0)
+
+
 
 if (ArmarXGui_FOUND)
-	armarx_gui_library(SensorActorWidgetsGuiPlugin "${SOURCES}" "${GUI_MOC_HDRS}" "${GUI_UIS}" "" "${COMPONENT_LIBS}" "${LIB_VERSION}" "${LIB_SOVERSION}")
+	armarx_gui_library(SensorActorWidgetsGuiPlugin "${SOURCES}" "${GUI_MOC_HDRS}" "${GUI_UIS}" "" "${COMPONENT_LIBS}" )
 endif()
diff --git a/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/SensorActorWidgetsPlugin.cpp b/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/SensorActorWidgetsPlugin.cpp
index b0b046e1876a7258fdd121917c010da8e9fa7cb8..1845914fcfe5ede4e11b7794aafa219754d02c72 100644
--- a/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/SensorActorWidgetsPlugin.cpp
+++ b/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/SensorActorWidgetsPlugin.cpp
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::Gui::SensorActorWidgetsPlugin
 * @author     ( at kit dot edu)
 * @date
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -29,7 +28,8 @@
 namespace armarx
 {
 
-    SensorActorPlugin::SensorActorPlugin(){
+    SensorActorPlugin::SensorActorPlugin()
+    {
         addWidget<TCPMover>();
         addWidget<ArmarXPlotter>();
     }
diff --git a/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/SensorActorWidgetsPlugin.h b/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/SensorActorWidgetsPlugin.h
index 6a1c3e58fba666f4208d54dab05e6ac8b7e1b1a9..08ed7b53946b5444e3f5c1ceaac8f940e9b88aa3 100644
--- a/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/SensorActorWidgetsPlugin.h
+++ b/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/SensorActorWidgetsPlugin.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,16 +16,16 @@
 * @package    ArmarX::Gui::SensorActorWidgetsPlugin
 * @author     ( at kit dot edu)
 * @date
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
 #ifndef ARMARX_COMPONENT_MDIGUIPLUGIN_H
 #define ARMARX_COMPONENT_MDIGUIPLUGIN_H
 
-#include <Gui/libraries/ArmarXGuiBase/ArmarXGuiPlugin.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXGuiPlugin.h>
 
-#include <Core/core/system/ImportExportComponent.h>
+#include <ArmarXCore/core/system/ImportExportComponent.h>
 
 
 namespace armarx
@@ -38,7 +37,7 @@ namespace armarx
      * @see TCPMover
      */
     class ARMARXCOMPONENT_IMPORT_EXPORT SensorActorPlugin :
-            public ArmarXGuiPlugin
+        public ArmarXGuiPlugin
     {
     public:
         SensorActorPlugin();
diff --git a/source/RobotAPI/gui-plugins/RobotIKPlugin/Backup/RobotViewerConfigDialog.cpp b/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/Backup/RobotViewerConfigDialog.cpp
similarity index 73%
rename from source/RobotAPI/gui-plugins/RobotIKPlugin/Backup/RobotViewerConfigDialog.cpp
rename to source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/Backup/RobotViewerConfigDialog.cpp
index 1a55ec188de066156a7ac55027b9b3f3bda8313e..1b467821f4b5566dea6acd6bc0bc4b483aaf5105 100644
--- a/source/RobotAPI/gui-plugins/RobotIKPlugin/Backup/RobotViewerConfigDialog.cpp
+++ b/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/Backup/RobotViewerConfigDialog.cpp
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::
 * @author     Mirko Waechter ( mirko.waechter at kit dot edu)
 * @date       2012
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -37,7 +36,7 @@
 
 using namespace armarx;
 
-RobotViewerConfigDialog::RobotViewerConfigDialog(QWidget *parent) :
+RobotViewerConfigDialog::RobotViewerConfigDialog(QWidget* parent) :
     QDialog(parent),
     ui(new Ui::RobotViewerConfigDialog),
     uuid(IceUtil::generateUUID())
@@ -45,10 +44,10 @@ RobotViewerConfigDialog::RobotViewerConfigDialog(QWidget *parent) :
     ui->setupUi(this);
 
     connect(this->ui->buttonBox, SIGNAL(accepted()), this, SLOT(verifyConfig()));
-    ui->buttonBox->button( QDialogButtonBox::Ok )->setDefault(true);
+    ui->buttonBox->button(QDialogButtonBox::Ok)->setDefault(true);
     proxyFinder = new IceProxyFinder<RobotStateComponentInterfacePrx>(this);
     proxyFinder->setSearchMask("RobotState*");
-    ui->gridLayout->addWidget(proxyFinder, 2,1,1,2);
+    ui->gridLayout->addWidget(proxyFinder, 2, 1, 1, 2);
 }
 
 RobotViewerConfigDialog::~RobotViewerConfigDialog()
@@ -76,12 +75,14 @@ void RobotViewerConfigDialog::onExitComponent()
 
 void RobotViewerConfigDialog::verifyConfig()
 {
-    if(proxyFinder->getSelectedProxyName().trimmed().length() == 0)
+    if (proxyFinder->getSelectedProxyName().trimmed().length() == 0)
     {
         QMessageBox::critical(this, "Invalid Configuration", "The proxy name must not be empty");
     }
     else
+    {
         this->accept();
+    }
 }
 
 
diff --git a/source/RobotAPI/gui-plugins/RobotIKPlugin/Backup/RobotViewerConfigDialog.h b/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/Backup/RobotViewerConfigDialog.h
similarity index 64%
rename from source/RobotAPI/gui-plugins/RobotIKPlugin/Backup/RobotViewerConfigDialog.h
rename to source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/Backup/RobotViewerConfigDialog.h
index bb60ccb157b8a6f807530b0d12e5052f89a568b0..9c8237d106d6468d725b3304f59310e72ecc0aa1 100644
--- a/source/RobotAPI/gui-plugins/RobotIKPlugin/Backup/RobotViewerConfigDialog.h
+++ b/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/Backup/RobotViewerConfigDialog.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::
 * @author     Nikolaus Vahrenkamp
 * @date       2015
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -27,16 +26,18 @@
 #include <QDialog>
 #include <QFileDialog>
 
-#include <Core/core/services/tasks/RunningTask.h>
-#include <Core/core/IceManager.h>
-#include <Core/core/ManagedIceObject.h>
+#include <ArmarXCore/core/services/tasks/RunningTask.h>
+#include <ArmarXCore/core/IceManager.h>
+#include <ArmarXCore/core/ManagedIceObject.h>
 #include <Gui/ArmarXGuiLib/utility/IceProxyFinder.h>
 
-namespace Ui {
+namespace Ui
+{
     class RobotViewerConfigDialog;
 }
 
-namespace armarx{
+namespace armarx
+{
     class RobotViewerConfigDialog :
         public QDialog,
         virtual public ManagedIceObject
@@ -44,11 +45,14 @@ namespace armarx{
         Q_OBJECT
 
     public:
-        explicit RobotViewerConfigDialog(QWidget *parent = 0);
+        explicit RobotViewerConfigDialog(QWidget* parent = 0);
         ~RobotViewerConfigDialog();
 
         // inherited from ManagedIceObject
-        std::string getDefaultName() const { return "RobotViewerConfigDialog" + uuid;}
+        std::string getDefaultName() const
+        {
+            return "RobotViewerConfigDialog" + uuid;
+        }
         void onInitComponent();
         void onConnectComponent();
         void onExitComponent();
@@ -61,7 +65,7 @@ namespace armarx{
     private:
 
         IceProxyFinderBase* proxyFinder;
-        Ui::RobotViewerConfigDialog *ui;
+        Ui::RobotViewerConfigDialog* ui;
         std::string uuid;
         friend class RobotViewerWidgetController;
     };
diff --git a/source/RobotAPI/gui-plugins/RobotIKPlugin/Backup/RobotViewerConfigDialog.ui b/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/Backup/RobotViewerConfigDialog.ui
similarity index 100%
rename from source/RobotAPI/gui-plugins/RobotIKPlugin/Backup/RobotViewerConfigDialog.ui
rename to source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/Backup/RobotViewerConfigDialog.ui
diff --git a/source/RobotAPI/gui-plugins/RobotIKPlugin/Backup/RobotViewerGuiPlugin.cpp b/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/Backup/RobotViewerGuiPlugin.cpp
similarity index 87%
rename from source/RobotAPI/gui-plugins/RobotIKPlugin/Backup/RobotViewerGuiPlugin.cpp
rename to source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/Backup/RobotViewerGuiPlugin.cpp
index bf65668d6f214f4a2c2b4971a057f639c14c5cbd..77a3673d5536e4b0073aaf4b854b6fca86e213a4 100644
--- a/source/RobotAPI/gui-plugins/RobotIKPlugin/Backup/RobotViewerGuiPlugin.cpp
+++ b/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/Backup/RobotViewerGuiPlugin.cpp
@@ -3,11 +3,11 @@
 
 #include <RobotAPI/gui-plugins/RobotViewerPlugin/ui_RobotViewerConfigDialog.h>
 
-#include <Core/core/system/ArmarXDataPath.h>
-#include <Core/core/ArmarXObjectScheduler.h>
-#include <Core/core/ArmarXManager.h>
-#include <Core/core/system/cmake/CMakePackageFinder.h>
-#include <Core/core/application/Application.h>
+#include <ArmarXCore/core/system/ArmarXDataPath.h>
+#include <ArmarXCore/core/ArmarXObjectScheduler.h>
+#include <ArmarXCore/core/ArmarXManager.h>
+#include <ArmarXCore/core/system/cmake/CMakePackageFinder.h>
+#include <ArmarXCore/core/application/Application.h>
 
 #include <VirtualRobot/XML/RobotIO.h>
 
@@ -83,12 +83,17 @@ void RobotViewerWidgetController::onInitComponent()
     {
         std::string debugDrawerComponentName = "RobotViewerGUIDebugDrawer_" + getName();
         ARMARX_INFO << "Creating component " << debugDrawerComponentName;
-        debugDrawer = Component::create<DebugDrawerComponent>(properties,debugDrawerComponentName);
+        debugDrawer = Component::create<DebugDrawerComponent>(properties, debugDrawerComponentName);
+
         if (mutex3D)
         {
             debugDrawer->setMutex(mutex3D);
-        } else
+        }
+        else
+        {
             ARMARX_ERROR << " No 3d mutex available...";
+        }
+
         ArmarXManagerPtr m = getArmarXManager();
         m->addObject(debugDrawer);
 
@@ -101,6 +106,7 @@ void RobotViewerWidgetController::onInitComponent()
             rootVisu->addChild(debugLayerVisu);
         }
     }
+
     showRoot(true);
 }
 
@@ -112,22 +118,30 @@ void RobotViewerWidgetController::onConnectComponent()
 
 
     if (robotVisu)
+    {
         robotVisu->removeAllChildren();
+    }
+
     robot.reset();
 
     std::string rfile;
     StringList includePaths;
 
     // get robot filename
-    try {
+    try
+    {
 
         StringList packages = robotStateComponentPrx->getArmarXPackages();
         packages.push_back(Application::GetProjectName());
         ARMARX_VERBOSE << "ArmarX packages " << packages;
-        for(const std::string &projectName : packages)
+
+        for (const std::string& projectName : packages)
         {
-            if(projectName.empty())
+            if (projectName.empty())
+            {
                 continue;
+            }
+
             CMakePackageFinder project(projectName);
             StringList projectIncludePaths;
             auto pathsString = project.getDataDir();
@@ -138,28 +152,36 @@ void RobotViewerWidgetController::onConnectComponent()
             includePaths.insert(includePaths.end(), projectIncludePaths.begin(), projectIncludePaths.end());
 
         }
+
         rfile = robotStateComponentPrx->getRobotFilename();
         ARMARX_VERBOSE << "Relative robot file " << rfile;
         ArmarXDataPath::getAbsolutePath(rfile, rfile, includePaths);
         ARMARX_VERBOSE << "Absolute robot file " << rfile;
-    } catch (...)
+    }
+    catch (...)
     {
         ARMARX_ERROR << "Unable to retrieve robot filename";
     }
 
-    try {
+    try
+    {
         ARMARX_INFO << "Loading robot from file " << rfile;
         robot = loadRobotFile(rfile);
-    } catch (...)
+    }
+    catch (...)
     {
         ARMARX_ERROR << "Failed to init robot";
     }
 
-    if(!robot)
+    if (!robot)
     {
         getObjectScheduler()->terminate();
-        if(getWidget()->parentWidget())
+
+        if (getWidget()->parentWidget())
+        {
             getWidget()->parentWidget()->close();
+        }
+
         std::cout << "returning" << std::endl;
         return;
     }
@@ -168,10 +190,12 @@ void RobotViewerWidgetController::onConnectComponent()
         boost::recursive_mutex::scoped_lock lock(*mutex3D);
 
         CoinVisualizationPtr robotViewerVisualization = robot->getVisualization<CoinVisualization>();
+
         if (robotViewerVisualization)
         {
             robotVisu->addChild(robotViewerVisualization->getCoinVisualization());
-        } else
+        }
+        else
         {
             ARMARX_WARNING << "no robot visu available...";
         }
@@ -191,12 +215,14 @@ void RobotViewerWidgetController::onDisconnectComponent()
 {
 
     ARMARX_INFO << "Disconnecting component";
+
     // stop update timer
     if (timerSensor)
     {
         SoSensorManager* sensor_mgr = SoDB::getSensorManager();
         sensor_mgr->removeTimerSensor(timerSensor);
     }
+
     ARMARX_INFO << "Disconnecting component: timer stopped";
 
     robotStateComponentPrx = NULL;
@@ -208,6 +234,7 @@ void RobotViewerWidgetController::onDisconnectComponent()
             ARMARX_INFO << "Disconnecting component: removing visu";
             robotVisu->removeAllChildren();
         }
+
         robot.reset();
     }
     ARMARX_INFO << "Disconnecting component: finished";
@@ -250,17 +277,18 @@ void RobotViewerWidgetController::onExitComponent()
         debugDrawer->getObjectScheduler()->terminate();
         ARMARX_INFO << "Removing DebugDrawer component...done";
     }
-*/
+    */
 }
 
 QPointer<QDialog> RobotViewerWidgetController::getConfigDialog(QWidget* parent)
 {
-    if(!dialog)
+    if (!dialog)
     {
         dialog = new RobotViewerConfigDialog(parent);
         dialog->setName(dialog->getDefaultName());
 
     }
+
     return qobject_cast<RobotViewerConfigDialog*>(dialog);
 }
 
@@ -278,12 +306,12 @@ void RobotViewerWidgetController::configured()
 }
 
 
-void RobotViewerWidgetController::loadSettings(QSettings *settings)
+void RobotViewerWidgetController::loadSettings(QSettings* settings)
 {
     robotStateComponentName = settings->value("RobotStateComponent", QString::fromStdString(ROBOTSTATE_NAME_DEFAULT)).toString().toStdString();
 }
 
-void RobotViewerWidgetController::saveSettings(QSettings *settings)
+void RobotViewerWidgetController::saveSettings(QSettings* settings)
 {
     settings->setValue("RobotStateComponent", QString::fromStdString(robotStateComponentName));
 }
@@ -293,7 +321,7 @@ void RobotViewerWidgetController::showVisuLayers(bool show)
 {
     if (debugDrawer)
     {
-        if(show)
+        if (show)
         {
             debugDrawer->enableAllLayers();
         }
@@ -307,14 +335,17 @@ void RobotViewerWidgetController::showVisuLayers(bool show)
 void RobotViewerWidgetController::showRoot(bool show)
 {
     if (!debugDrawer)
+    {
         return;
+    }
 
     std::string poseName("root");
-    if(show)
+
+    if (show)
     {
         Eigen::Matrix4f gp = Eigen::Matrix4f::Identity();
         PosePtr gpP(new Pose(gp));
-        debugDrawer->setPoseDebugLayerVisu(poseName,gpP);
+        debugDrawer->setPoseDebugLayerVisu(poseName, gpP);
     }
     else
     {
@@ -325,19 +356,22 @@ void RobotViewerWidgetController::showRoot(bool show)
 void RobotViewerWidgetController::showRobot(bool show)
 {
     if (!robotVisu)
+    {
         return;
+    }
+
     boost::recursive_mutex::scoped_lock lock(*mutex3D);
 
-    if(show && rootVisu->findChild(robotVisu)<0)
+    if (show && rootVisu->findChild(robotVisu) < 0)
     {
         rootVisu->addChild(robotVisu);
     }
-    else if (!show && rootVisu->findChild(robotVisu)>=0)
+    else if (!show && rootVisu->findChild(robotVisu) >= 0)
     {
         rootVisu->removeChild(robotVisu);
     }
 }
-SoNode *RobotViewerWidgetController::getScene()
+SoNode* RobotViewerWidgetController::getScene()
 {
     return rootVisu;
 }
@@ -345,8 +379,12 @@ SoNode *RobotViewerWidgetController::getScene()
 void RobotViewerWidgetController::timerCB(void* data, SoSensor* sensor)
 {
     RobotViewerWidgetController* controller = static_cast<RobotViewerWidgetController*>(data);
+
     if (!controller)
+    {
         return;
+    }
+
     controller->updateRobotVisu();
 }
 
@@ -365,11 +403,13 @@ VirtualRobot::RobotPtr RobotViewerWidgetController::loadRobotFile(std::string fi
 {
     VirtualRobot::RobotPtr robot;
 
-    if (!ArmarXDataPath::getAbsolutePath(fileName,fileName))
+    if (!ArmarXDataPath::getAbsolutePath(fileName, fileName))
     {
         ARMARX_INFO << "Could not find Robot XML file with name " << fileName;
     }
+
     robot = RobotIO::loadRobot(fileName);
+
     if (!robot)
     {
         ARMARX_INFO << "Could not find Robot XML file with name " << fileName;
@@ -385,12 +425,15 @@ void RobotViewerWidgetController::updateRobotVisu()
     boost::recursive_mutex::scoped_lock lock(*mutex3D);
 
     if (!robotStateComponentPrx || !robot)
+    {
         return;
+    }
 
     try
     {
-        RemoteRobot::synchronizeLocalClone(robot,robotStateComponentPrx);
-    } catch (...)
+        RemoteRobot::synchronizeLocalClone(robot, robotStateComponentPrx);
+    }
+    catch (...)
     {
         ARMARX_INFO << deactivateSpam(5) << "Robot synchronization failed";
         return;
@@ -398,14 +441,14 @@ void RobotViewerWidgetController::updateRobotVisu()
 
     Eigen::Matrix4f gp = robot->getGlobalPose();
     QString roboInfo("Robot Pose (global): pos: ");
-    roboInfo += QString::number(gp(0,3), 'f', 2);
+    roboInfo += QString::number(gp(0, 3), 'f', 2);
     roboInfo += QString(", ");
-    roboInfo += QString::number(gp(1,3), 'f', 2);
+    roboInfo += QString::number(gp(1, 3), 'f', 2);
     roboInfo += QString(", ");
-    roboInfo += QString::number(gp(2,3), 'f', 2);
+    roboInfo += QString::number(gp(2, 3), 'f', 2);
     roboInfo += QString(", rot:");
     Eigen::Vector3f rpy;
-    VirtualRobot::MathTools::eigen4f2rpy(gp,rpy);
+    VirtualRobot::MathTools::eigen4f2rpy(gp, rpy);
     roboInfo += QString::number(rpy(0), 'f', 2);
     roboInfo += QString(", ");
     roboInfo += QString::number(rpy(1), 'f', 2);
@@ -420,7 +463,7 @@ void RobotViewerWidgetController::solveIK()
 
     ::Ice::AsyncResultPtr asyncResult = robotIKPrx->begin_computeIKGlobalPose("LeftArm", new Pose(), eAll);
 
-    while(!asyncResult->isCompleted())
+    while (!asyncResult->isCompleted())
     {
         qApp->processEvents();
     }
@@ -435,8 +478,11 @@ void RobotViewerWidgetController::setMutex3D(boost::shared_ptr<boost::recursive_
 {
     //ARMARX_IMPORTANT << "set mutex3d :" << mutex3D.get();
     this->mutex3D = mutex3D;
+
     if (debugDrawer)
+    {
         debugDrawer->setMutex(mutex3D);
+    }
 }
 
 
diff --git a/source/RobotAPI/gui-plugins/RobotIKPlugin/Backup/RobotViewerGuiPlugin.h b/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/Backup/RobotViewerGuiPlugin.h
similarity index 88%
rename from source/RobotAPI/gui-plugins/RobotIKPlugin/Backup/RobotViewerGuiPlugin.h
rename to source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/Backup/RobotViewerGuiPlugin.h
index e1d341d0136253b191ff3daef11289f33e78e021..dc38933e61f3cce7055117c04719a4a6d1ab7d00 100644
--- a/source/RobotAPI/gui-plugins/RobotIKPlugin/Backup/RobotViewerGuiPlugin.h
+++ b/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/Backup/RobotViewerGuiPlugin.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::Component::RobotViewerGuiPlugin
 * @author     Nikolaus Vahrenkamp
 * @copyright  2015 KIT
-* @license    http://www.gnu.org/licenses/gpl.txt
+* @license    http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 
 */
@@ -34,7 +33,7 @@
 #include <Gui/ArmarXGuiLib/ArmarXGuiPlugin.h>
 #include <Gui/ArmarXGuiLib/ArmarXComponentWidgetController.h>
 
-#include <Core/core/Component.h>
+#include <ArmarXCore/core/Component.h>
 
 /* Qt headers */
 #include <QtGui/QMainWindow>
@@ -64,7 +63,7 @@ namespace armarx
       \see RobotViewerWidget
       */
     class RobotViewerGuiPlugin :
-            public ArmarXGuiPlugin
+        public ArmarXGuiPlugin
     {
     public:
         RobotViewerGuiPlugin();
@@ -81,7 +80,7 @@ namespace armarx
      Further, DebugDrawer methods are available.
      \image html RobotViewerGUI.png
      When you add the widget to the Gui, you need to specify the following parameters:
-     
+
      Parameter Name   | Example Value     | Required?     | Description
      :----------------  | :-------------:   | :-------------- |:--------------------
      Proxy     | RobotStateComponent   | Yes | The name of the robot state component.
@@ -90,7 +89,7 @@ namespace armarx
      \see RobotViewerGuiPlugin
      */
     class RobotViewerWidgetController :
-            public ArmarXComponentWidgetController
+        public ArmarXComponentWidgetController
     {
         Q_OBJECT
     public:
@@ -110,8 +109,8 @@ namespace armarx
             return "RobotControl.RobotIK";
         }
         QPointer<QDialog> getConfigDialog(QWidget* parent = 0);
-        virtual void loadSettings(QSettings * settings);
-        virtual void saveSettings(QSettings * settings);
+        virtual void loadSettings(QSettings* settings);
+        virtual void saveSettings(QSettings* settings);
         void configured();
 
         SoNode* getScene();
@@ -157,7 +156,7 @@ namespace armarx
         SoSeparator* debugLayerVisu;
         armarx::DebugDrawerComponentPtr debugDrawer;
 
-        static void timerCB(void *data, SoSensor *sensor);
+        static void timerCB(void* data, SoSensor* sensor);
     protected slots:
         void showVisuLayers(bool show);
         void showRoot(bool show);
diff --git a/source/RobotAPI/gui-plugins/RobotIKPlugin/Backup/RobotViewerGuiPlugin.ui b/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/Backup/RobotViewerGuiPlugin.ui
similarity index 100%
rename from source/RobotAPI/gui-plugins/RobotIKPlugin/Backup/RobotViewerGuiPlugin.ui
rename to source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/Backup/RobotViewerGuiPlugin.ui
diff --git a/source/RobotAPI/gui-plugins/RobotIKPlugin/CMakeLists.txt b/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/CMakeLists.txt
similarity index 90%
rename from source/RobotAPI/gui-plugins/RobotIKPlugin/CMakeLists.txt
rename to source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/CMakeLists.txt
index ec3aef199ee042079e54cced1e960b3db51e4f7a..bc97728d165777a835eb6c2c5aff0308e4e6b6d2 100644
--- a/source/RobotAPI/gui-plugins/RobotIKPlugin/CMakeLists.txt
+++ b/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/CMakeLists.txt
@@ -48,9 +48,9 @@ set(GUI_UIS
 
 set(COMPONENT_LIBS RobotAPIUnits DebugDrawer ${Simox_LIBRARIES})
 
-set(LIB_VERSION    0.1.0)
-set(LIB_SOVERSION  0)
+
+
 
 if (ArmarXGui_FOUND)
-	armarx_gui_library(RobotIKGuiPlugin "${SOURCES}" "${GUI_MOC_HDRS}" "${GUI_UIS}" "" "${COMPONENT_LIBS}" "${LIB_VERSION}" "${LIB_SOVERSION}")
+	armarx_gui_library(RobotIKGuiPlugin "${SOURCES}" "${GUI_MOC_HDRS}" "${GUI_UIS}" "" "${COMPONENT_LIBS}" )
 endif()
diff --git a/source/RobotAPI/gui-plugins/RobotIKPlugin/RobotIKConfigDialog.cpp b/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/RobotIKConfigDialog.cpp
similarity index 74%
rename from source/RobotAPI/gui-plugins/RobotIKPlugin/RobotIKConfigDialog.cpp
rename to source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/RobotIKConfigDialog.cpp
index 847ace97c2597f3edf5a2b3493fc6bb0f7f4a1aa..54b438f34feec6310d704fce6d5179e34bd5cb76 100644
--- a/source/RobotAPI/gui-plugins/RobotIKPlugin/RobotIKConfigDialog.cpp
+++ b/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/RobotIKConfigDialog.cpp
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::
 * @author     Philipp Schmidt
 * @date       2015
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -36,7 +35,7 @@
 //Ice includes
 #include <IceUtil/UUID.h>
 
-armarx::RobotIKConfigDialog::RobotIKConfigDialog(QWidget *parent) :
+armarx::RobotIKConfigDialog::RobotIKConfigDialog(QWidget* parent) :
     QDialog(parent),
     ui(new Ui::RobotIKConfigDialog),
     uuid(IceUtil::generateUUID())
@@ -47,20 +46,20 @@ armarx::RobotIKConfigDialog::RobotIKConfigDialog(QWidget *parent) :
     connect(this->ui->buttonBox, SIGNAL(accepted()), this, SLOT(verifyConfiguration()));
 
     //Set OK button as default for convenience
-    ui->buttonBox->button( QDialogButtonBox::Ok )->setDefault(true);
+    ui->buttonBox->button(QDialogButtonBox::Ok)->setDefault(true);
 
     //Initialize proxyFinders for every component
     robotStateComponentProxyFinder = new IceProxyFinder<RobotStateComponentInterfacePrx>(this);
     robotStateComponentProxyFinder->setSearchMask("RobotState*");
-    ui->gridLayout->addWidget(robotStateComponentProxyFinder, 1,1);
+    ui->gridLayout->addWidget(robotStateComponentProxyFinder, 1, 1);
 
     kinematicUnitComponentProxyFinder = new IceProxyFinder<KinematicUnitInterfacePrx>(this);
     kinematicUnitComponentProxyFinder->setSearchMask("Armar3Kinematic*");
-    ui->gridLayout->addWidget(kinematicUnitComponentProxyFinder, 2,1);
+    ui->gridLayout->addWidget(kinematicUnitComponentProxyFinder, 2, 1);
 
     robotIKComponentProxyFinder = new IceProxyFinder<RobotIKInterfacePrx>(this);
     robotIKComponentProxyFinder->setSearchMask("RobotIK*");
-    ui->gridLayout->addWidget(robotIKComponentProxyFinder, 3,1);
+    ui->gridLayout->addWidget(robotIKComponentProxyFinder, 3, 1);
 }
 
 armarx::RobotIKConfigDialog::~RobotIKConfigDialog()
@@ -87,14 +86,14 @@ void armarx::RobotIKConfigDialog::onExitComponent()
 
 void armarx::RobotIKConfigDialog::verifyConfiguration()
 {
-    if(robotStateComponentProxyFinder->getSelectedProxyName().trimmed().length() == 0
-            || kinematicUnitComponentProxyFinder->getSelectedProxyName().trimmed().length() == 0
-            || robotIKComponentProxyFinder->getSelectedProxyName().trimmed().length() == 0)
+    if (robotStateComponentProxyFinder->getSelectedProxyName().trimmed().length() == 0
+        || kinematicUnitComponentProxyFinder->getSelectedProxyName().trimmed().length() == 0
+        || robotIKComponentProxyFinder->getSelectedProxyName().trimmed().length() == 0)
     {
         QMessageBox::critical(this, "Invalid Configuration", "The proxy name must not be empty");
     }
     else
     {
-       this->accept();
+        this->accept();
     }
 }
diff --git a/source/RobotAPI/gui-plugins/RobotIKPlugin/RobotIKConfigDialog.h b/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/RobotIKConfigDialog.h
similarity index 64%
rename from source/RobotAPI/gui-plugins/RobotIKPlugin/RobotIKConfigDialog.h
rename to source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/RobotIKConfigDialog.h
index 5578118bcd0f0ebcd389037152dac855923c661f..3d34f2f6ceace807b0b9c7b85349113209c33765 100644
--- a/source/RobotAPI/gui-plugins/RobotIKPlugin/RobotIKConfigDialog.h
+++ b/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/RobotIKConfigDialog.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::
 * @author     Philipp Schmidt
 * @date       2015
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -25,27 +24,32 @@
 #define RobotIKCONFIGDIALOG_H
 
 //ArmarX includes
-#include <Gui/libraries/ArmarXGuiBase/widgets/IceProxyFinder.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/widgets/IceProxyFinder.h>
 
 //Qt includes
 #include <QDialog>
 
-namespace Ui {
+namespace Ui
+{
     class RobotIKConfigDialog;
 }
 
-namespace armarx {
+namespace armarx
+{
     class RobotIKConfigDialog : public QDialog, virtual public ManagedIceObject
     {
         Q_OBJECT
         friend class RobotIKWidgetController;
 
     public:
-        explicit RobotIKConfigDialog(QWidget *parent = 0);
-                ~RobotIKConfigDialog();
+        explicit RobotIKConfigDialog(QWidget* parent = 0);
+        ~RobotIKConfigDialog();
 
         // inherited from ManagedIceObject
-        std::string getDefaultName() const { return "RobotIKConfigDialog" + uuid;}
+        std::string getDefaultName() const
+        {
+            return "RobotIKConfigDialog" + uuid;
+        }
         void onInitComponent();
         void onConnectComponent();
         void onExitComponent();
@@ -58,7 +62,7 @@ namespace armarx {
         IceProxyFinderBase* kinematicUnitComponentProxyFinder;
         IceProxyFinderBase* robotIKComponentProxyFinder;
 
-        Ui::RobotIKConfigDialog *ui;
+        Ui::RobotIKConfigDialog* ui;
         std::string uuid;
     };
 }
diff --git a/source/RobotAPI/gui-plugins/RobotIKPlugin/RobotIKConfigDialog.ui b/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/RobotIKConfigDialog.ui
similarity index 100%
rename from source/RobotAPI/gui-plugins/RobotIKPlugin/RobotIKConfigDialog.ui
rename to source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/RobotIKConfigDialog.ui
diff --git a/source/RobotAPI/gui-plugins/RobotIKPlugin/RobotIKGuiPlugin.cpp b/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/RobotIKGuiPlugin.cpp
similarity index 82%
rename from source/RobotAPI/gui-plugins/RobotIKPlugin/RobotIKGuiPlugin.cpp
rename to source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/RobotIKGuiPlugin.cpp
index c79999aaaa41dbb5a71b06c9ad8da390a484c505..3e2badc6d74ac6c0b84bb804241a5c7b3711ac93 100644
--- a/source/RobotAPI/gui-plugins/RobotIKPlugin/RobotIKGuiPlugin.cpp
+++ b/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/RobotIKGuiPlugin.cpp
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::
 * @author     Philipp Schmidt
 * @date       2015
-* @license    http://www.gnu.org/licenses/gpl.txt
+* @license    http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 
 */
@@ -26,10 +25,10 @@
 #include "RobotViewer.h"
 
 /* ArmarX includes */
-#include <Core/core/system/ArmarXDataPath.h>
-#include <Core/core/ArmarXObjectScheduler.h>
-#include <Core/core/system/cmake/CMakePackageFinder.h>
-#include <Core/core/application/Application.h>
+#include <ArmarXCore/core/system/ArmarXDataPath.h>
+#include <ArmarXCore/core/ArmarXObjectScheduler.h>
+#include <ArmarXCore/core/system/cmake/CMakePackageFinder.h>
+#include <ArmarXCore/core/application/Application.h>
 
 /* Virtual Robot includes */
 #include <VirtualRobot/XML/RobotIO.h>
@@ -95,13 +94,16 @@ void armarx::RobotIKWidgetController::onConnectComponent()
 
     //Load robot
     robot = loadRobot(getIncludePaths());
-    if(!robot)
+
+    if (!robot)
     {
         getObjectScheduler()->terminate();
-        if(getWidget()->parentWidget())
+
+        if (getWidget()->parentWidget())
         {
             getWidget()->parentWidget()->close();
         }
+
         ARMARX_ERROR << "RobotIKPlugin: Unable to load robot file! Terminating." << std::endl;
         return;
     }
@@ -123,7 +125,9 @@ void armarx::RobotIKWidgetController::onConnectComponent()
 
     //Get all kinematic chain descriptions and add them to the combo box
     auto robotNodeSets = robot->getRobotNodeSets();
-    for(VirtualRobot::RobotNodeSetPtr s : robotNodeSets) {
+
+    for (VirtualRobot::RobotNodeSetPtr s : robotNodeSets)
+    {
         this->ui.comboBox->addItem(QString::fromStdString(s->getName()));
     }
 
@@ -199,21 +203,22 @@ void armarx::RobotIKWidgetController::onExitComponent()
     enableMainWidgetAsync(false);
 }
 
-QPointer<QDialog> armarx::RobotIKWidgetController::getConfigDialog(QWidget *parent)
+QPointer<QDialog> armarx::RobotIKWidgetController::getConfigDialog(QWidget* parent)
 {
-    if(!dialog)
+    if (!dialog)
     {
         dialog = new RobotIKConfigDialog(parent);
     }
+
     return qobject_cast<RobotIKConfigDialog*>(dialog);
 }
 
-void armarx::RobotIKWidgetController::loadSettings(QSettings *settings)
+void armarx::RobotIKWidgetController::loadSettings(QSettings* settings)
 {
 
 }
 
-void armarx::RobotIKWidgetController::saveSettings(QSettings *settings)
+void armarx::RobotIKWidgetController::saveSettings(QSettings* settings)
 {
 
 }
@@ -229,22 +234,25 @@ void armarx::RobotIKWidgetController::solveIK()
 {
     auto targetJointAngles = getIKSolution();
 
-    if(targetJointAngles.isReachable) {
+    if (targetJointAngles.isReachable)
+    {
         //Switch all control modes to ePositionControl
         std::vector<VirtualRobot::RobotNodePtr> rn = robot->getRobotNodeSet(this->ui.comboBox->currentText().toStdString())->getAllRobotNodes();
         NameControlModeMap jointModes;
         NameValueMap jointAngles;
-        for (unsigned int i=0;i<rn.size();i++)
+
+        for (unsigned int i = 0; i < rn.size(); i++)
         {
             jointModes[rn[i]->getName()] = ePositionControl;
-            jointAngles[rn[i]->getName()]=0.0f;
+            jointAngles[rn[i]->getName()] = 0.0f;
         }
+
         kinematicUnitInterfacePrx->switchControlMode(jointModes);
         kinematicUnitInterfacePrx->setJointAngles(targetJointAngles.jointAngles);
     }
 }
 
-void armarx::RobotIKWidgetController::kinematicChainChanged(const QString &arg1)
+void armarx::RobotIKWidgetController::kinematicChainChanged(const QString& arg1)
 {
     //An item has been selected, so we can allow the user to use the ui now
     //The manipulator will be set to the position of the current tcp, so this pose
@@ -263,10 +271,13 @@ void armarx::RobotIKWidgetController::kinematicChainChanged(const QString &arg1)
     this->ui.resetManip->setEnabled(true);
 
     //Remove all current tcp and desired tcp pose visualization if present
-    if(currentSeparator) {
+    if (currentSeparator)
+    {
         this->ui.robotViewer->getRobotViewer()->getRootNode()->removeChild(currentSeparator);
     }
-    if(manipSeparator) {
+
+    if (manipSeparator)
+    {
         this->ui.robotViewer->getRobotViewer()->getRootNode()->removeChild(manipSeparator);
     }
 
@@ -331,10 +342,11 @@ void armarx::RobotIKWidgetController::kinematicChainChanged(const QString &arg1)
     tcpManip->rotation.setValue(SbRotation(VirtualRobot::CoinVisualizationFactory::getSbMatrix(mat)));*/
 }
 
-void armarx::RobotIKWidgetController::caertesianSelectionChanged(const QString &arg1)
+void armarx::RobotIKWidgetController::caertesianSelectionChanged(const QString& arg1)
 {
     //If there is a manip in the scene we pretend it just moved to update color etc.
-    if(tcpManip) {
+    if (tcpManip)
+    {
         manipFinishCallback(this, NULL);
     }
 }
@@ -342,7 +354,7 @@ void armarx::RobotIKWidgetController::caertesianSelectionChanged(const QString &
 void armarx::RobotIKWidgetController::resetManip()
 {
     //Triggers reset of manipulator in kinematicChainChanged
-   kinematicChainChanged(this->ui.comboBox->currentText());
+    kinematicChainChanged(this->ui.comboBox->currentText());
 }
 
 void armarx::RobotIKWidgetController::connectSlots()
@@ -357,13 +369,18 @@ armarx::StringList armarx::RobotIKWidgetController::getIncludePaths()
 {
     StringList includePaths;
 
-    try {
+    try
+    {
         StringList packages = robotStateComponentPrx->getArmarXPackages();
         packages.push_back(Application::GetProjectName());
-        for(const std::string &projectName : packages)
+
+        for (const std::string& projectName : packages)
         {
-            if(projectName.empty())
+            if (projectName.empty())
+            {
                 continue;
+            }
+
             CMakePackageFinder project(projectName);
             StringList projectIncludePaths;
             auto pathsString = project.getDataDir();
@@ -373,7 +390,8 @@ armarx::StringList armarx::RobotIKWidgetController::getIncludePaths()
                          boost::token_compress_on);
             includePaths.insert(includePaths.end(), projectIncludePaths.begin(), projectIncludePaths.end());
         }
-    } catch (...)
+    }
+    catch (...)
     {
         ARMARX_ERROR << "Unable to retrieve robot filename." << std::endl;
     }
@@ -389,25 +407,28 @@ VirtualRobot::RobotPtr armarx::RobotIKWidgetController::loadRobot(StringList inc
         ArmarXDataPath::getAbsolutePath(rfile, rfile, includePaths);
         return VirtualRobot::RobotIO::loadRobot(rfile);
     }
-    catch(...)
+    catch (...)
     {
         ARMARX_ERROR << "Unable to load robot from file" << std::endl;
         return VirtualRobot::RobotPtr();
     }
 }
 
-void armarx::RobotIKWidgetController::manipFinishCallback(void* data, SoDragger* dragger) {
+void armarx::RobotIKWidgetController::manipFinishCallback(void* data, SoDragger* dragger)
+{
     RobotIKWidgetController* controller = static_cast<RobotIKWidgetController*>(data);
 
     auto targetJointAngles = controller->getIKSolution();
 
-    if(targetJointAngles.isReachable) {
+    if (targetJointAngles.isReachable)
+    {
         //Green
         controller->tcpManipColor->ambientColor.setValue(0, 1, 0);
         controller->ui.reachableLabel->setText(QString::fromStdString("Pose reachable!"));
         controller->ui.reachableLabel->setStyleSheet("QLabel { color : green; }");
     }
-    else {
+    else
+    {
         //Red
         controller->tcpManipColor->ambientColor.setValue(1, 0, 0);
         controller->ui.reachableLabel->setText(QString::fromStdString("Pose unreachable!"));
@@ -418,16 +439,21 @@ void armarx::RobotIKWidgetController::manipFinishCallback(void* data, SoDragger*
     controller->ui.errorValue->setText(QString::fromStdString("Calculated error: " + boost::lexical_cast<std::string>(targetJointAngles.error)));
 }
 
-void armarx::RobotIKWidgetController::robotUpdateTimerCB(void *data, SoSensor *sensor)
+void armarx::RobotIKWidgetController::robotUpdateTimerCB(void* data, SoSensor* sensor)
 {
     RobotIKWidgetController* controller = static_cast<RobotIKWidgetController*>(data);
+
     if (!controller || !controller->robotStateComponentPrx || !controller->robot)
+    {
         return;
+    }
+
     try
     {
-        armarx::RemoteRobot::synchronizeLocalClone(controller->robot,controller->robotStateComponentPrx);
+        armarx::RemoteRobot::synchronizeLocalClone(controller->robot, controller->robotStateComponentPrx);
 
-        if(controller->currentSeparator) {
+        if (controller->currentSeparator)
+        {
             Eigen::Matrix4f tcpMatrix = controller->robot->getRobotNodeSet(controller->ui.comboBox->currentText().toStdString())->getTCP()->getGlobalPose();
             //Apply tcp position to indicator
             tcpMatrix(0, 3) /= 1000;
@@ -436,20 +462,26 @@ void armarx::RobotIKWidgetController::robotUpdateTimerCB(void *data, SoSensor *s
             controller->tcpCurrentTransform->setMatrix(VirtualRobot::CoinVisualizationFactory::getSbMatrix(tcpMatrix));
         }
 
-        if(controller->startUpCameraPositioningFlag) {
+        if (controller->startUpCameraPositioningFlag)
+        {
             controller->ui.robotViewer->getRobotViewer()->cameraViewAll();
             controller->startUpCameraPositioningFlag = false;
         }
-    } catch (...){};
+    }
+    catch (...) {};
 }
 
-void armarx::RobotIKWidgetController::textFieldUpdateTimerCB(void *data, SoSensor *sensor)
+void armarx::RobotIKWidgetController::textFieldUpdateTimerCB(void* data, SoSensor* sensor)
 {
     RobotIKWidgetController* controller = static_cast<RobotIKWidgetController*>(data);
+
     if (!controller)
+    {
         return;
+    }
 
-    if(controller->currentSeparator) {
+    if (controller->currentSeparator)
+    {
         Eigen::Matrix4f tcpMatrix = controller->robot->getRobotNodeSet(controller->ui.comboBox->currentText().toStdString())->getTCP()->getGlobalPose();
 
         //Set text label to tcp matrix
@@ -463,8 +495,8 @@ void armarx::RobotIKWidgetController::textFieldUpdateTimerCB(void *data, SoSenso
         SoGetMatrixAction* action = new SoGetMatrixAction(SbViewportRegion());
         SoSearchAction sa;
         sa.setNode(controller->tcpManipSphere);
-        sa.setSearchingAll( TRUE );              // Search all nodes
-        SoBaseKit::setSearchingChildren( TRUE ); // Even inside nodekits
+        sa.setSearchingAll(TRUE);                // Search all nodes
+        SoBaseKit::setSearchingChildren(TRUE);   // Even inside nodekits
         sa.apply(controller->ui.robotViewer->getRobotViewer()->getRootNode());
 
         action->apply(sa.getPath());
@@ -472,25 +504,25 @@ void armarx::RobotIKWidgetController::textFieldUpdateTimerCB(void *data, SoSenso
         SbMatrix matrix = action->getMatrix();
 
         Eigen::Matrix4f mat = Eigen::Matrix4f::Identity();
-        mat (0,0) = matrix[0][0];
-        mat (0,1) = matrix[1][0];
-        mat (0,2) = matrix[2][0];
-        mat (0,3) = matrix[3][0] * 1000;
-
-        mat (1,0) = matrix[0][1];
-        mat (1,1) = matrix[1][1];
-        mat (1,2) = matrix[2][1];
-        mat (1,3) = matrix[3][1] * 1000;
-
-        mat (2,0) = matrix[0][2];
-        mat (2,1) = matrix[1][2];
-        mat (2,2) = matrix[2][2];
-        mat (2,3) = matrix[3][2] * 1000;
-
-        mat (3,0) = matrix[0][3];
-        mat (3,1) = matrix[1][3];
-        mat (3,2) = matrix[2][3];
-        mat (3,3) = matrix[3][3];
+        mat(0, 0) = matrix[0][0];
+        mat(0, 1) = matrix[1][0];
+        mat(0, 2) = matrix[2][0];
+        mat(0, 3) = matrix[3][0] * 1000;
+
+        mat(1, 0) = matrix[0][1];
+        mat(1, 1) = matrix[1][1];
+        mat(1, 2) = matrix[2][1];
+        mat(1, 3) = matrix[3][1] * 1000;
+
+        mat(2, 0) = matrix[0][2];
+        mat(2, 1) = matrix[1][2];
+        mat(2, 2) = matrix[2][2];
+        mat(2, 3) = matrix[3][2] * 1000;
+
+        mat(3, 0) = matrix[0][3];
+        mat(3, 1) = matrix[1][3];
+        mat(3, 2) = matrix[2][3];
+        mat(3, 3) = matrix[3][3];
 
         //Set text label to manip matrix
         std::stringstream buffer2;
@@ -507,8 +539,8 @@ armarx::ExtendedIKResult armarx::RobotIKWidgetController::getIKSolution()
     SoGetMatrixAction* action = new SoGetMatrixAction(SbViewportRegion());
     SoSearchAction sa;
     sa.setNode(tcpManipSphere);
-    sa.setSearchingAll( TRUE );              // Search all nodes
-    SoBaseKit::setSearchingChildren( TRUE ); // Even inside nodekits
+    sa.setSearchingAll(TRUE);                // Search all nodes
+    SoBaseKit::setSearchingChildren(TRUE);   // Even inside nodekits
     sa.apply(this->ui.robotViewer->getRobotViewer()->getRootNode());
 
     action->apply(sa.getPath());
@@ -516,51 +548,58 @@ armarx::ExtendedIKResult armarx::RobotIKWidgetController::getIKSolution()
     SbMatrix matrix = action->getMatrix();
 
     Eigen::Matrix4f mat = Eigen::Matrix4f::Identity();
-    mat (0,0) = matrix[0][0];
-    mat (0,1) = matrix[1][0];
-    mat (0,2) = matrix[2][0];
-    mat (0,3) = matrix[3][0] * 1000;
-
-    mat (1,0) = matrix[0][1];
-    mat (1,1) = matrix[1][1];
-    mat (1,2) = matrix[2][1];
-    mat (1,3) = matrix[3][1] * 1000;
-
-    mat (2,0) = matrix[0][2];
-    mat (2,1) = matrix[1][2];
-    mat (2,2) = matrix[2][2];
-    mat (2,3) = matrix[3][2] * 1000;
-
-    mat (3,0) = matrix[0][3];
-    mat (3,1) = matrix[1][3];
-    mat (3,2) = matrix[2][3];
-    mat (3,3) = matrix[3][3];
-
-//    mat = robot->getRootNode()->toLocalCoordinateSystem(mat);
-    return(robotIKPrx->computeExtendedIKGlobalPose(this->ui.comboBox->currentText().toStdString(),new armarx::Pose(mat),
-                                                   convertOption(this->ui.cartesianselection->currentText().toStdString())));
+    mat(0, 0) = matrix[0][0];
+    mat(0, 1) = matrix[1][0];
+    mat(0, 2) = matrix[2][0];
+    mat(0, 3) = matrix[3][0] * 1000;
+
+    mat(1, 0) = matrix[0][1];
+    mat(1, 1) = matrix[1][1];
+    mat(1, 2) = matrix[2][1];
+    mat(1, 3) = matrix[3][1] * 1000;
+
+    mat(2, 0) = matrix[0][2];
+    mat(2, 1) = matrix[1][2];
+    mat(2, 2) = matrix[2][2];
+    mat(2, 3) = matrix[3][2] * 1000;
+
+    mat(3, 0) = matrix[0][3];
+    mat(3, 1) = matrix[1][3];
+    mat(3, 2) = matrix[2][3];
+    mat(3, 3) = matrix[3][3];
+
+    //    mat = robot->getRootNode()->toLocalCoordinateSystem(mat);
+    return (robotIKPrx->computeExtendedIKGlobalPose(this->ui.comboBox->currentText().toStdString(), new armarx::Pose(mat),
+            convertOption(this->ui.cartesianselection->currentText().toStdString())));
 }
 
 armarx::CartesianSelection armarx::RobotIKWidgetController::convertOption(std::string option)
 {
-    if(option == "Orientation and Position") {
+    if (option == "Orientation and Position")
+    {
         return eAll;
     }
-    else if(option == "Position") {
+    else if (option == "Position")
+    {
         return ePosition;
     }
-    else if(option == "Orientation") {
+    else if (option == "Orientation")
+    {
         return eOrientation;
     }
-    else if(option == "X position") {
+    else if (option == "X position")
+    {
         return eX;
     }
-    else if(option == "Y position") {
+    else if (option == "Y position")
+    {
         return eY;
     }
-    else if(option == "Z position") {
+    else if (option == "Z position")
+    {
         return eZ;
     }
+
     return eAll;
 }
 
diff --git a/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/RobotIKGuiPlugin.h b/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/RobotIKGuiPlugin.h
new file mode 100644
index 0000000000000000000000000000000000000000..3dd135614b0630ccbcca55d254fc9da84c8e3291
--- /dev/null
+++ b/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/RobotIKGuiPlugin.h
@@ -0,0 +1,145 @@
+/*
+* This file is part of ArmarX.
+*
+* ArmarX is free software; you can redistribute it and/or modify
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
+*
+* ArmarX is distributed in the hope that it will be useful, but
+* WITHOUT ANY WARRANTY; without even the implied warranty of
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
+*
+* You should have received a copy of the GNU General Public License
+* along with this program. If not, see <http://www.gnu.org/licenses/>.
+*
+* @package    ArmarX::
+* @author     Philipp Schmidt
+* @date       2015
+* @license    http://www.gnu.org/licenses/gpl-2.0.txt
+*             GNU General Public License
+
+*/
+
+#ifndef RobotIKGUIPLUGIN_H
+#define RobotIKGUIPLUGIN_H
+
+//Gui
+#include "RobotIKConfigDialog.h"
+#include "ui_RobotIKGuiPlugin.h"
+
+//ArmarX includes
+#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXGuiPlugin.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXComponentWidgetController.h>
+#include <RobotAPI/interface/core/RobotIK.h>
+#include <RobotAPI/interface/core/RobotState.h>
+#include <RobotAPI/libraries/core/remoterobot/RemoteRobot.h>
+
+//Qt includes
+#include <QObject>
+
+//VirtualRobot includes
+#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/Visualization/CoinVisualization/CoinVisualization.h>
+
+//Inventor includes
+#include <Inventor/sensors/SoTimerSensor.h>
+#include <Inventor/manips/SoTransformerManip.h>
+#include <Inventor/nodes/SoSphere.h>
+#include <Inventor/nodes/SoMaterial.h>
+
+namespace armarx
+{
+    class RobotIKConfigDialog;
+
+    class RobotIKGuiPlugin : public ArmarXGuiPlugin
+    {
+    public:
+        RobotIKGuiPlugin();
+
+        QString getPluginName()
+        {
+            return "RobotIKGuiPlugin";
+        }
+    };
+
+    class RobotIKWidgetController : public ArmarXComponentWidgetController
+    {
+        Q_OBJECT
+
+    public:
+        RobotIKWidgetController();
+        virtual ~RobotIKWidgetController() {}
+
+        // inherited from Component
+        virtual void onInitComponent();
+        virtual void onConnectComponent();
+        virtual void onDisconnectComponent();
+        virtual void onExitComponent();
+
+        // inherited of ArmarXWidget
+        virtual QString getWidgetName() const
+        {
+            return "RobotControl.RobotIK";
+        }
+        QPointer<QDialog> getConfigDialog(QWidget* parent = 0);
+        virtual void loadSettings(QSettings* settings);
+        virtual void saveSettings(QSettings* settings);
+        void configured();
+
+    public slots:
+        void solveIK();
+        void kinematicChainChanged(const QString& arg1);
+        void caertesianSelectionChanged(const QString& arg1);
+        void resetManip();
+
+    protected:
+        RobotStateComponentInterfacePrx robotStateComponentPrx;
+        KinematicUnitInterfacePrx kinematicUnitInterfacePrx;
+        RobotIKInterfacePrx robotIKPrx;
+
+        Ui::RobotIKGuiPlugin ui;
+
+    private:
+        void connectSlots();
+        std::string robotStateComponentName;
+        std::string kinematicUnitComponentName;
+        std::string robotIKComponentName;
+
+        QPointer<RobotIKConfigDialog> dialog;
+
+        VirtualRobot::RobotPtr robot;
+        StringList getIncludePaths();
+        VirtualRobot::RobotPtr loadRobot(StringList includePaths);
+
+        SoSeparator* manipSeparator;
+        SoSeparator* currentSeparator;
+
+        SoTransformerManip* tcpManip;
+        static void manipFinishCallback(void* data, SoDragger* manip);
+        SoTransform* tcpManipTransform;
+        SoMaterial* tcpManipColor;
+        SoSphere* tcpManipSphere;
+
+        SoTransform* tcpCurrentTransform;
+        SoMaterial* tcpCurrentColor;
+        SoSphere* tcpCurrentSphere;
+
+        SoTimerSensor* robotUpdateSensor;
+        static void robotUpdateTimerCB(void* data, SoSensor* sensor);
+
+        SoTimerSensor* textFieldUpdateSensor;
+        static void textFieldUpdateTimerCB(void* data, SoSensor* sensor);
+
+        ExtendedIKResult getIKSolution();
+
+        CartesianSelection convertOption(std::string option);
+
+        bool startUpCameraPositioningFlag;
+
+    };
+    typedef boost::shared_ptr<RobotIKWidgetController> RobotIKGuiPluginPtr;
+    typedef boost::shared_ptr<VirtualRobot::CoinVisualization> CoinVisualizationPtr;
+}
+
+#endif
diff --git a/source/RobotAPI/gui-plugins/RobotIKPlugin/RobotIKGuiPlugin.ui b/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/RobotIKGuiPlugin.ui
similarity index 100%
rename from source/RobotAPI/gui-plugins/RobotIKPlugin/RobotIKGuiPlugin.ui
rename to source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/RobotIKGuiPlugin.ui
diff --git a/source/RobotAPI/gui-plugins/RobotIKPlugin/RobotViewer.cpp b/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/RobotViewer.cpp
similarity index 99%
rename from source/RobotAPI/gui-plugins/RobotIKPlugin/RobotViewer.cpp
rename to source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/RobotViewer.cpp
index 80f5806649d575bd3d2d26abe16d97ae78acafc8..51827017e3fffe8b6bd2d4016893c395e42c3d54 100644
--- a/source/RobotAPI/gui-plugins/RobotIKPlugin/RobotViewer.cpp
+++ b/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/RobotViewer.cpp
@@ -17,11 +17,11 @@ armarx::RobotViewer::RobotViewer(QWidget* widget) : SoQtExaminerViewer(widget),
     this->setHeadlight(true);
     this->setViewing(false);
     this->setDecoration(false);
-    #ifdef WIN32
-    #ifndef _DEBUG
+#ifdef WIN32
+#ifndef _DEBUG
     this->setAntialiasing(true, 4);
-    #endif
-    #endif
+#endif
+#endif
     this->setTransparencyType(SoGLRenderAction::SORTED_OBJECT_BLEND);
     this->setFeedbackVisibility(true);
 
@@ -177,7 +177,7 @@ armarx::RobotViewer::~RobotViewer()
     sceneRootNode->unref();
 }
 
-SoSeparator *armarx::RobotViewer::getRootNode()
+SoSeparator* armarx::RobotViewer::getRootNode()
 {
     return this->contentRootNode;
 }
diff --git a/source/RobotAPI/gui-plugins/RobotIKPlugin/RobotViewer.h b/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/RobotViewer.h
similarity index 100%
rename from source/RobotAPI/gui-plugins/RobotIKPlugin/RobotViewer.h
rename to source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/RobotViewer.h
diff --git a/source/RobotAPI/gui-plugins/RobotIKPlugin/RobotViewerWidget.cpp b/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/RobotViewerWidget.cpp
similarity index 91%
rename from source/RobotAPI/gui-plugins/RobotIKPlugin/RobotViewerWidget.cpp
rename to source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/RobotViewerWidget.cpp
index 859263a87551708221b3fd479ed3d7df8525e157..dd925f98f4a0807895ab539909826f1806d43854 100644
--- a/source/RobotAPI/gui-plugins/RobotIKPlugin/RobotViewerWidget.cpp
+++ b/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/RobotViewerWidget.cpp
@@ -2,7 +2,7 @@
 
 #include <QGridLayout>
 
-armarx::RobotViewerWidget::RobotViewerWidget(QWidget *parent) : QWidget(parent)
+armarx::RobotViewerWidget::RobotViewerWidget(QWidget* parent) : QWidget(parent)
 {
     this->setContentsMargins(1, 1, 1, 1);
 
diff --git a/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/RobotViewerWidget.h b/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/RobotViewerWidget.h
new file mode 100644
index 0000000000000000000000000000000000000000..ccb8d99796aff9e4fb0d060244361d55b7f59152
--- /dev/null
+++ b/source/RobotAPI/gui-plugins/moved_to_robotcomponents_RobotIKPlugin/RobotViewerWidget.h
@@ -0,0 +1,45 @@
+#ifndef RobotViewerWidget_h
+#define RobotViewerWidget_h
+
+/* Qt headers */
+#include <QWidget>
+
+/* boost headers */
+#include <boost/smart_ptr/shared_ptr.hpp>
+
+#include "RobotViewer.h"
+
+typedef boost::shared_ptr<armarx::RobotViewer> RobotViewerPtr;
+
+namespace armarx
+{
+    class RobotViewerWidget : public QWidget
+    {
+        Q_OBJECT
+
+    public:
+        /**
+        * Constructor.
+        * Constructs a robot viewer widget.
+        * Expects a controller::ControllerPtr.
+        *
+        * @param    control     shared pointer to controller::controller
+        * @param    parent      parent widget
+        *
+        */
+        explicit RobotViewerWidget(QWidget* parent = 0);
+
+        /**
+        * Destructor.
+        *
+        */
+        ~RobotViewerWidget();
+
+        RobotViewerPtr getRobotViewer();
+
+    private:
+        RobotViewerPtr viewer;
+    };
+}
+
+#endif
diff --git a/source/RobotAPI/interface/CMakeLists.txt b/source/RobotAPI/interface/CMakeLists.txt
index 8c1244c8632a6718f128fd6d46a33ecc6739859e..cbfa0be0f10dc4a6467ad8b2902f87b0ac5355ac 100644
--- a/source/RobotAPI/interface/CMakeLists.txt
+++ b/source/RobotAPI/interface/CMakeLists.txt
@@ -15,7 +15,6 @@ set(SLICE_FILES
     core/LinkedPoseBase.ice
     core/FramedPoseBase.ice
     core/RobotState.ice
-    core/RobotIK.ice
     core/RobotStateObserverInterface.ice
 
     selflocalisation/SelfLocalisationProcess.ice
@@ -33,9 +32,11 @@ set(SLICE_FILES
     units/TCPControlUnit.ice
     units/TCPMoverUnitInterface.ice
     units/UnitInterface.ice
+    units/ATINetFTUnit.ice
 
     visualization/DebugDrawerInterface.ice
 )
+    #core/RobotIK.ice
 
 # generate the interface library
-armarx_interfaces_generate_library(RobotAPI 0.1.0 0 "${ROBOTAPI_INTERFACE_DEPEND}")
+armarx_interfaces_generate_library(RobotAPI "${ROBOTAPI_INTERFACE_DEPEND}")
diff --git a/source/RobotAPI/interface/core/FramedPoseBase.ice b/source/RobotAPI/interface/core/FramedPoseBase.ice
index acc1f7b9d4d8330cb10e3efdc72ece0201c279f4..59d50d4c4905ad10da3b0160579a556ee21043a7 100644
--- a/source/RobotAPI/interface/core/FramedPoseBase.ice
+++ b/source/RobotAPI/interface/core/FramedPoseBase.ice
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -24,8 +23,8 @@
 #ifndef _ARMARX_ROBOTAPI_ROBOTSTATE_FRAMED_POSE_SLICE_
 #define _ARMARX_ROBOTAPI_ROBOTSTATE_FRAMED_POSE_SLICE_
 
-#include <Core/interface/observers/VariantBase.ice>
-#include <Core/interface/observers/Filters.ice>
+#include <ArmarXCore/interface/observers/VariantBase.ice>
+#include <ArmarXCore/interface/observers/Filters.ice>
 #include <RobotAPI/interface/core/PoseBase.ice>
 
 module armarx
diff --git a/source/RobotAPI/interface/core/LinkedPoseBase.ice b/source/RobotAPI/interface/core/LinkedPoseBase.ice
index 3f465967c721200bd717266150797b14a5bb3125..b9801d6100b247bf15b8a37e8b9e36a3492cfdb1 100644
--- a/source/RobotAPI/interface/core/LinkedPoseBase.ice
+++ b/source/RobotAPI/interface/core/LinkedPoseBase.ice
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
diff --git a/source/RobotAPI/interface/core/PoseBase.ice b/source/RobotAPI/interface/core/PoseBase.ice
index 7cadb9e161d83712db74606c666e103adabae6a1..f89217ac84d72e6989c388f6a3ee1eb22ba721fc 100644
--- a/source/RobotAPI/interface/core/PoseBase.ice
+++ b/source/RobotAPI/interface/core/PoseBase.ice
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -24,8 +23,8 @@
 #ifndef _ARMARX_ROBOTAPI_POSE_SLICE_
 #define _ARMARX_ROBOTAPI_POSE_SLICE_
 
-#include <Core/interface/observers/VariantBase.ice>
-#include <Core/interface/observers/Filters.ice>
+#include <ArmarXCore/interface/observers/VariantBase.ice>
+#include <ArmarXCore/interface/observers/Filters.ice>
 
 module armarx
 {
diff --git a/source/RobotAPI/interface/core/RobotState.ice b/source/RobotAPI/interface/core/RobotState.ice
index ad1053ae92200087e72817fd57638016bf51a8b7..d37226e2da5b00aedbfc040cc7f48e52a64708d8 100644
--- a/source/RobotAPI/interface/core/RobotState.ice
+++ b/source/RobotAPI/interface/core/RobotState.ice
@@ -4,7 +4,7 @@
 #include <RobotAPI/interface/units/KinematicUnitInterface.ice>
 #include <RobotAPI/interface/units/PlatformUnitInterface.ice>
 #include <RobotAPI/interface/core/FramedPoseBase.ice>
-#include <Core/interface/observers/Timestamp.ice>
+#include <ArmarXCore/interface/observers/Timestamp.ice>
 
 module armarx
 {
diff --git a/source/RobotAPI/interface/core/RobotStateObserverInterface.ice b/source/RobotAPI/interface/core/RobotStateObserverInterface.ice
index 551ddeec6f50ff5b2b7f95787075cbe8463dfbe2..607f0812c9e0d9c175479306ddd5424725907fea 100644
--- a/source/RobotAPI/interface/core/RobotStateObserverInterface.ice
+++ b/source/RobotAPI/interface/core/RobotStateObserverInterface.ice
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -27,7 +26,7 @@
 
 #include <RobotAPI/interface/units/KinematicUnitInterface.ice>
 
-#include <Core/interface/observers/ObserverInterface.ice>
+#include <ArmarXCore/interface/observers/ObserverInterface.ice>
 
 module armarx
 {
diff --git a/source/RobotAPI/interface/core/RobotIK.ice b/source/RobotAPI/interface/core/moved_to_robotcomponents_RobotIK.ice
similarity index 100%
rename from source/RobotAPI/interface/core/RobotIK.ice
rename to source/RobotAPI/interface/core/moved_to_robotcomponents_RobotIK.ice
diff --git a/source/RobotAPI/interface/hardware/BusInspectionInterface.ice b/source/RobotAPI/interface/hardware/BusInspectionInterface.ice
index cc8b22c61b5ade3cc29ba4eb0e1b666c66287a46..321d3dfd7647c7cab4a9de29110c82e5f380ea04 100644
--- a/source/RobotAPI/interface/hardware/BusInspectionInterface.ice
+++ b/source/RobotAPI/interface/hardware/BusInspectionInterface.ice
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -18,7 +17,7 @@
  * @author     Peter Kaiser (peter dot kaiser at kit dot edu)
  * @author     Matthias Hadlich (matthias dot hadlich at student dot kit dot edu)
  * @copyright  2014 Peter Kaiser 
- * @license    http://www.gnu.org/licenses/gpl.txt
+ * @license    http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -27,8 +26,8 @@
 
 #include <RobotAPI/interface/units/KinematicUnitInterface.ice>
 
-#include <Core/interface/core/UserException.ice>
-#include <Core/interface/core/BasicTypes.ice>
+#include <ArmarXCore/interface/core/UserException.ice>
+#include <ArmarXCore/interface/core/BasicTypes.ice>
 
 module armarx
 {
diff --git a/source/RobotAPI/interface/observers/KinematicUnitObserverInterface.ice b/source/RobotAPI/interface/observers/KinematicUnitObserverInterface.ice
index 681dfbac68f7b8bee247c5887b56febd8ebb605d..6dbefd25992f6b1b6b3c141a0a78443d63a0efb7 100644
--- a/source/RobotAPI/interface/observers/KinematicUnitObserverInterface.ice
+++ b/source/RobotAPI/interface/observers/KinematicUnitObserverInterface.ice
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -26,7 +25,7 @@
 
 #include <RobotAPI/interface/units/KinematicUnitInterface.ice>
 
-#include <Core/interface/observers/ObserverInterface.ice>
+#include <ArmarXCore/interface/observers/ObserverInterface.ice>
 
 module armarx
 {
diff --git a/source/RobotAPI/interface/observers/ObserverFilters.ice b/source/RobotAPI/interface/observers/ObserverFilters.ice
index b668c374f15836a31a72c8120f7afde299913004..4ba2872954735fb187543b25a80ec028112dc8a1 100644
--- a/source/RobotAPI/interface/observers/ObserverFilters.ice
+++ b/source/RobotAPI/interface/observers/ObserverFilters.ice
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -24,8 +23,8 @@
 #ifndef _ARMARX_ROBOTAPI_OBSERVER_FILTERS_SLICE_
 #define _ARMARX_ROBOTAPI_OBSERVER_FILTERS_SLICE_
 
-#include <Core/interface/observers/VariantBase.ice>
-#include <Core/interface/observers/Filters.ice>
+#include <ArmarXCore/interface/observers/VariantBase.ice>
+#include <ArmarXCore/interface/observers/Filters.ice>
 
 module armarx
 {
diff --git a/source/RobotAPI/interface/observers/PlatformUnitObserverInterface.ice b/source/RobotAPI/interface/observers/PlatformUnitObserverInterface.ice
index ee1e69ba9bc7dd2190fbae7fde938b6961fcb6b4..73db196ecc19f00d2ac3b413310df5a2bf65304b 100644
--- a/source/RobotAPI/interface/observers/PlatformUnitObserverInterface.ice
+++ b/source/RobotAPI/interface/observers/PlatformUnitObserverInterface.ice
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -26,7 +25,7 @@
 
 #include <RobotAPI/interface/units/PlatformUnitInterface.ice>
 
-#include <Core/interface/observers/ObserverInterface.ice>
+#include <ArmarXCore/interface/observers/ObserverInterface.ice>
 
 module armarx
 {
diff --git a/source/RobotAPI/interface/selflocalisation/SelfLocalisationProcess.ice b/source/RobotAPI/interface/selflocalisation/SelfLocalisationProcess.ice
index 0a7f47958914e87b86b4ef80040f7374b519064b..7fb058b50fead45e5a7d702e0365dd9cd722da85 100644
--- a/source/RobotAPI/interface/selflocalisation/SelfLocalisationProcess.ice
+++ b/source/RobotAPI/interface/selflocalisation/SelfLocalisationProcess.ice
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    RobotAPI
  * @author     Thomas von der Heyde <tvh242 at hotmail dot com>
  * @copyright  2014
- * @license    http://www.gnu.org/licenses/gpl.txt
+ * @license    http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
diff --git a/source/RobotAPI/interface/speech/SpeechInterface.ice b/source/RobotAPI/interface/speech/SpeechInterface.ice
index 9f37056c7797535a5e47c9c871c59961923aba20..d9df885c189f5fae6c2ae7538248d3e5ece2694c 100644
--- a/source/RobotAPI/interface/speech/SpeechInterface.ice
+++ b/source/RobotAPI/interface/speech/SpeechInterface.ice
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
diff --git a/source/RobotAPI/interface/units/ATINetFTUnit.ice b/source/RobotAPI/interface/units/ATINetFTUnit.ice
new file mode 100644
index 0000000000000000000000000000000000000000..6fdcce5c60de26dd79e45f62d0586748bfcdc359
--- /dev/null
+++ b/source/RobotAPI/interface/units/ATINetFTUnit.ice
@@ -0,0 +1,57 @@
+/*
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @package    RobotAPI
+ * @author     Martin Do ( martin dot do at kit dot edu )
+ * @date       2015
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#ifndef _ARMARX_ROBOTAPI_UNITS_ATINetFTUnitInterface_SLICE_
+#define _ARMARX_ROBOTAPI_UNITS_ATINetFTUnitInterface_SLICE_
+
+#include <RobotAPI/interface/core/PoseBase.ice>
+#include <RobotAPI/interface/units/UnitInterface.ice>
+#include <ArmarXCore/interface/core/UserException.ice>
+
+module armarx
+{
+    /**
+     * Will be thrown, if a ATINetFT error occurs.
+     */
+    exception ATINetFTException extends UserException
+    {
+        /**
+         * The ATINetFT error code as defined in the ATINetFTDataStreamSDK.
+         * Note that "no error" or "success" is represented with the
+         * result code 2. The other result codes are error codes.
+         */
+        int errorCode;
+    };
+
+
+    interface ATINetFTUnitInterface extends SensorActorUnitInterface
+    {
+
+        void startRecording(string customName);
+
+        void stopRecording();
+
+        bool isComponentOnline();
+    };
+};
+
+#endif
diff --git a/source/RobotAPI/interface/units/ForceTorqueUnit.ice b/source/RobotAPI/interface/units/ForceTorqueUnit.ice
index 5e09c93abec1ddb3256c0dceb62bee6e80f65f5c..b9924aca5a68932fa40685fe5260ece392f5cff0 100644
--- a/source/RobotAPI/interface/units/ForceTorqueUnit.ice
+++ b/source/RobotAPI/interface/units/ForceTorqueUnit.ice
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    RobotAPI
  * @author     Mirko Waechter <waechter at kit dot edu>
  * @copyright  2013 Mirko Waechter
- * @license    http://www.gnu.org/licenses/gpl.txt
+ * @license    http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  **/
 
@@ -28,10 +27,10 @@
 #include <RobotAPI/interface/core/RobotState.ice>
 #include <RobotAPI/interface/core/FramedPoseBase.ice>
 
-#include <Core/interface/core/UserException.ice>
-#include <Core/interface/core/BasicTypes.ice>
-#include <Core/interface/observers/VariantBase.ice>
-#include <Core/interface/observers/ObserverInterface.ice>
+#include <ArmarXCore/interface/core/UserException.ice>
+#include <ArmarXCore/interface/core/BasicTypes.ice>
+#include <ArmarXCore/interface/observers/VariantBase.ice>
+#include <ArmarXCore/interface/observers/ObserverInterface.ice>
 
 module armarx
 {    
diff --git a/source/RobotAPI/interface/units/HandUnitInterface.ice b/source/RobotAPI/interface/units/HandUnitInterface.ice
index 0f6d1a861cd015ecaf0d8064ef9e493530a5ec36..f3df38d6289ac39d3d8a93f5f63da3f0a8be4ab9 100644
--- a/source/RobotAPI/interface/units/HandUnitInterface.ice
+++ b/source/RobotAPI/interface/units/HandUnitInterface.ice
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    ArmarX::Core
  * @author     Manfred Kroehnert (manfred dot kroehnert at kit dot edu)
  * @copyright  2013 Manfred Kroehnert
- * @license    http://www.gnu.org/licenses/gpl.txt
+ * @license    http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -27,10 +26,10 @@
 #include <RobotAPI/interface/units/UnitInterface.ice>
 #include <RobotAPI/interface/units/KinematicUnitInterface.ice>
 
-#include <Core/interface/core/UserException.ice>
-#include <Core/interface/core/BasicTypes.ice>
-#include <Core/interface/observers/VariantContainers.ice>
-#include <Core/interface/observers/ObserverInterface.ice>
+#include <ArmarXCore/interface/core/UserException.ice>
+#include <ArmarXCore/interface/core/BasicTypes.ice>
+#include <ArmarXCore/interface/observers/VariantContainers.ice>
+#include <ArmarXCore/interface/observers/ObserverInterface.ice>
 
 
 module armarx
diff --git a/source/RobotAPI/interface/units/HapticUnit.ice b/source/RobotAPI/interface/units/HapticUnit.ice
index 8afe57f9e7f90be40b84be195245216b8b3c800c..d24d5a5c30b171fd0b1b0d309f6a13056d0e9973 100644
--- a/source/RobotAPI/interface/units/HapticUnit.ice
+++ b/source/RobotAPI/interface/units/HapticUnit.ice
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -27,12 +26,12 @@
 #include <RobotAPI/interface/units/UnitInterface.ice>
 #include <RobotAPI/interface/core/RobotState.ice>
 
-#include <Core/interface/core/UserException.ice>
-#include <Core/interface/core/BasicTypes.ice>
-#include <Core/interface/observers/VariantBase.ice>
-#include <Core/interface/observers/Matrix.ice>
-#include <Core/interface/observers/Timestamp.ice>
-#include <Core/interface/observers/ObserverInterface.ice>
+#include <ArmarXCore/interface/core/UserException.ice>
+#include <ArmarXCore/interface/core/BasicTypes.ice>
+#include <ArmarXCore/interface/observers/VariantBase.ice>
+#include <ArmarXCore/interface/observers/Matrix.ice>
+#include <ArmarXCore/interface/observers/Timestamp.ice>
+#include <ArmarXCore/interface/observers/ObserverInterface.ice>
 
 module armarx
 {
diff --git a/source/RobotAPI/interface/units/HeadIKUnit.ice b/source/RobotAPI/interface/units/HeadIKUnit.ice
index 48ebc04eb7fe43c6cc1a6229b294a8c8a5a17d75..fec56ec4aaef6f80a1d40f0970550e49a87d5899 100644
--- a/source/RobotAPI/interface/units/HeadIKUnit.ice
+++ b/source/RobotAPI/interface/units/HeadIKUnit.ice
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    RobotAPI
  * @author     David Schiebener <schiebener at kit dot edu>
  * @copyright  2014 David Schiebener
- * @license    http://www.gnu.org/licenses/gpl.txt
+ * @license    http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -28,10 +27,10 @@
 #include <RobotAPI/interface/core/RobotState.ice>
 #include <RobotAPI/interface/core/FramedPoseBase.ice>
 
-#include <Core/interface/core/UserException.ice>
-#include <Core/interface/core/BasicTypes.ice>
-#include <Core/interface/observers/VariantBase.ice>
-#include <Core/interface/observers/ObserverInterface.ice>
+#include <ArmarXCore/interface/core/UserException.ice>
+#include <ArmarXCore/interface/core/BasicTypes.ice>
+#include <ArmarXCore/interface/observers/VariantBase.ice>
+#include <ArmarXCore/interface/observers/ObserverInterface.ice>
 
 module armarx
 {
diff --git a/source/RobotAPI/interface/units/InertialMeasurementUnit.ice b/source/RobotAPI/interface/units/InertialMeasurementUnit.ice
index 834e077298ff469edd84ec284070b2dbe86e2242..642f1b1ea2188209974b52ec700579bf625afa56 100644
--- a/source/RobotAPI/interface/units/InertialMeasurementUnit.ice
+++ b/source/RobotAPI/interface/units/InertialMeasurementUnit.ice
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -28,12 +27,12 @@
 #include <RobotAPI/interface/units/UnitInterface.ice>
 #include <RobotAPI/interface/core/RobotState.ice>
 
-#include <Core/interface/core/UserException.ice>
-#include <Core/interface/core/BasicTypes.ice>
-#include <Core/interface/observers/VariantBase.ice>
-#include <Core/interface/observers/Matrix.ice>
-#include <Core/interface/observers/Timestamp.ice>
-#include <Core/interface/observers/ObserverInterface.ice>
+#include <ArmarXCore/interface/core/UserException.ice>
+#include <ArmarXCore/interface/core/BasicTypes.ice>
+#include <ArmarXCore/interface/observers/VariantBase.ice>
+#include <ArmarXCore/interface/observers/Matrix.ice>
+#include <ArmarXCore/interface/observers/Timestamp.ice>
+#include <ArmarXCore/interface/observers/ObserverInterface.ice>
 
 
 
diff --git a/source/RobotAPI/interface/units/KinematicUnitInterface.ice b/source/RobotAPI/interface/units/KinematicUnitInterface.ice
index c1700c113728826bea9d7ae1be259528b0673cde..ff0f432537e411f343463a6de9b61aed9a93bedd 100644
--- a/source/RobotAPI/interface/units/KinematicUnitInterface.ice
+++ b/source/RobotAPI/interface/units/KinematicUnitInterface.ice
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    ArmarX::Core
  * @author     Christian Boege (boege at kit dot edu)
  * @copyright  2011 Christian Boege
- * @license    http://www.gnu.org/licenses/gpl.txt
+ * @license    http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -26,8 +25,8 @@
 
 #include <RobotAPI/interface/units/UnitInterface.ice>
 
-#include <Core/interface/core/UserException.ice>
-#include <Core/interface/core/BasicTypes.ice>
+#include <ArmarXCore/interface/core/UserException.ice>
+#include <ArmarXCore/interface/core/BasicTypes.ice>
 
 module armarx
 {
diff --git a/source/RobotAPI/interface/units/PlatformUnitInterface.ice b/source/RobotAPI/interface/units/PlatformUnitInterface.ice
index b7bde4e0880519b4011cd88ab3b3766899f94d5a..4c275ee00424da8c82467c206ccf8f596eca38cb 100644
--- a/source/RobotAPI/interface/units/PlatformUnitInterface.ice
+++ b/source/RobotAPI/interface/units/PlatformUnitInterface.ice
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    ArmarX::Core
  * @author     Manfred Kroehnert (manfred dot kroehnert at kit dot edu)
  * @copyright  2013 Manfred Kroehnert
- * @license    http://www.gnu.org/licenses/gpl.txt
+ * @license    http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -26,8 +25,8 @@
 
 #include <RobotAPI/interface/units/UnitInterface.ice>
 
-#include <Core/interface/core/UserException.ice>
-#include <Core/interface/core/BasicTypes.ice>
+#include <ArmarXCore/interface/core/UserException.ice>
+#include <ArmarXCore/interface/core/BasicTypes.ice>
 
 module armarx
 {	
diff --git a/source/RobotAPI/interface/units/TCPControlUnit.ice b/source/RobotAPI/interface/units/TCPControlUnit.ice
index a8adef62e2774e6880cf3e8063383fd745be8896..33117e380a73d620f0ba9755b5709881bc8d1993 100644
--- a/source/RobotAPI/interface/units/TCPControlUnit.ice
+++ b/source/RobotAPI/interface/units/TCPControlUnit.ice
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    RobotAPI
  * @author     Mirko Waechter <waechter at kit dot edu>
  * @copyright  2013 Mirko Waechter
- * @license    http://www.gnu.org/licenses/gpl.txt
+ * @license    http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -28,10 +27,10 @@
 #include <RobotAPI/interface/core/RobotState.ice>
 #include <RobotAPI/interface/core/FramedPoseBase.ice>
 
-#include <Core/interface/core/UserException.ice>
-#include <Core/interface/core/BasicTypes.ice>
-#include <Core/interface/observers/VariantBase.ice>
-#include <Core/interface/observers/ObserverInterface.ice>
+#include <ArmarXCore/interface/core/UserException.ice>
+#include <ArmarXCore/interface/core/BasicTypes.ice>
+#include <ArmarXCore/interface/observers/VariantBase.ice>
+#include <ArmarXCore/interface/observers/ObserverInterface.ice>
 
 module armarx
 {
diff --git a/source/RobotAPI/interface/units/TCPMoverUnitInterface.ice b/source/RobotAPI/interface/units/TCPMoverUnitInterface.ice
index 727676476cfebe1e1bb980cb2611b0a6cf9fb3e0..11d93b2ea51ae59b23a7ec31f4b81043a0bc82d5 100644
--- a/source/RobotAPI/interface/units/TCPMoverUnitInterface.ice
+++ b/source/RobotAPI/interface/units/TCPMoverUnitInterface.ice
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    ArmarX::Core
  * @author     Christian Boege (boege at kit dot edu)
  * @copyright  2011 Christian Boege
- * @license    http://www.gnu.org/licenses/gpl.txt
+ * @license    http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -26,7 +25,7 @@
 
 #include <RobotAPI/interface/units/KinematicUnitInterface.ice>
 
-#include <Core/interface/core/UserException.ice>
+#include <ArmarXCore/interface/core/UserException.ice>
 
 module armarx
 {
diff --git a/source/RobotAPI/interface/units/UnitInterface.ice b/source/RobotAPI/interface/units/UnitInterface.ice
index 5cc9073ae4ba23476177d5604b08420ebf6862bc..916c31d58a2d8e149bd4bba4602b0e31587d816a 100644
--- a/source/RobotAPI/interface/units/UnitInterface.ice
+++ b/source/RobotAPI/interface/units/UnitInterface.ice
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -24,7 +23,7 @@
 #ifndef _ARMARX_CORE_UNITS_UNITINTERFACE_SLICE_
 #define _ARMARX_CORE_UNITS_UNITINTERFACE_SLICE_
 
-#include <Core/interface/core/UserException.ice>
+#include <ArmarXCore/interface/core/UserException.ice>
 
 module armarx
 {
diff --git a/source/RobotAPI/interface/units/WeissHapticUnit.ice b/source/RobotAPI/interface/units/WeissHapticUnit.ice
index 414a1aae8cead59d120307ccdc336d12928232b9..bc43d8da8b44fc9285bdaac74ca5546c9fdf9e70 100644
--- a/source/RobotAPI/interface/units/WeissHapticUnit.ice
+++ b/source/RobotAPI/interface/units/WeissHapticUnit.ice
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
diff --git a/source/RobotAPI/interface/visualization/DebugDrawerInterface.ice b/source/RobotAPI/interface/visualization/DebugDrawerInterface.ice
index 41db91bd7cdf32a5725d40601e64051c1b08de5c..9f025f5239a831a8958babd77a354a53dee82237 100644
--- a/source/RobotAPI/interface/visualization/DebugDrawerInterface.ice
+++ b/source/RobotAPI/interface/visualization/DebugDrawerInterface.ice
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,15 +16,15 @@
  * @package    ArmarX::RobotAPI
  * @author     Nikolaus Vahrenkamp
  * @copyright  2014
- * @license    http://www.gnu.org/licenses/gpl.txt
+ * @license    http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 #ifndef _ARMARX_API_DEBUGDRAWERLAYER_SLICE_
 #define _ARMARX_API_DEBUGDRAWERLAYER_SLICE_
 
-#include <Core/interface/core/UserException.ice>
-#include <Core/interface/core/BasicTypes.ice>
+#include <ArmarXCore/interface/core/UserException.ice>
+#include <ArmarXCore/interface/core/BasicTypes.ice>
 #include <RobotAPI/interface/core/PoseBase.ice>
 #include <RobotAPI/interface/units/KinematicUnitInterface.ice>
 
diff --git a/source/RobotAPI/libraries/CMakeLists.txt b/source/RobotAPI/libraries/CMakeLists.txt
index 3be572965d724b6b91e0af11d7266aa5b78afbfb..c3d725373ed3d4a44f2cc629f1775fe3e7be8e43 100644
--- a/source/RobotAPI/libraries/CMakeLists.txt
+++ b/source/RobotAPI/libraries/CMakeLists.txt
@@ -1,2 +1,4 @@
 add_subdirectory(drivers)
 add_subdirectory(core)
+add_subdirectory(widgets)
+
diff --git a/source/RobotAPI/libraries/core/CMakeLists.txt b/source/RobotAPI/libraries/core/CMakeLists.txt
index 53a0b23239a54fb90016c8d0786afd331f3df2a9..cb77eb2914b2d3e9fa4a9cec9f7de08c673e0101 100644
--- a/source/RobotAPI/libraries/core/CMakeLists.txt
+++ b/source/RobotAPI/libraries/core/CMakeLists.txt
@@ -14,8 +14,8 @@ if (Eigen3_FOUND AND Simox_FOUND)
 endif()
 
 set(LIB_NAME       RobotAPICore)
-set(LIB_VERSION    0.1.0)
-set(LIB_SOVERSION  0)
+
+
 
 set(LIBS RobotAPIInterfaces ArmarXCoreObservers ArmarXCoreStatechart ArmarXCoreEigen3Variants ${Simox_LIBRARIES})
 
@@ -57,4 +57,4 @@ set(LIB_HEADERS
 )
 
 
-armarx_add_library("${LIB_NAME}" "${LIB_VERSION}" "${LIB_SOVERSION}" "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
+armarx_add_library("${LIB_NAME}"  "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
diff --git a/source/RobotAPI/libraries/core/FramedPose.cpp b/source/RobotAPI/libraries/core/FramedPose.cpp
index 1f972824fa2c71ce7f87b1e97357c2bf4cd00725..de30cd40ab4a64109dd778e54447236f3ebf1137 100644
--- a/source/RobotAPI/libraries/core/FramedPose.cpp
+++ b/source/RobotAPI/libraries/core/FramedPose.cpp
@@ -23,7 +23,7 @@ namespace armarx
     {
     }
 
-    FramedDirection::FramedDirection(const FramedDirection &source) :
+    FramedDirection::FramedDirection(const FramedDirection& source) :
         IceUtil::Shared(source),
         Vector3Base(source),
         FramedDirectionBase(source),
@@ -31,7 +31,7 @@ namespace armarx
     {
     }
 
-    FramedDirection::FramedDirection(const Eigen::Vector3f &vec, const string &frame, const string &agent) :
+    FramedDirection::FramedDirection(const Eigen::Vector3f& vec, const string& frame, const string& agent) :
         Vector3(vec)
     {
         this->frame = frame;
@@ -39,7 +39,7 @@ namespace armarx
 
     }
 
-    FramedDirection::FramedDirection(Ice::Float x, ::Ice::Float y, ::Ice::Float z, const std::string &frame) :
+    FramedDirection::FramedDirection(Ice::Float x, ::Ice::Float y, ::Ice::Float z, const std::string& frame) :
         Vector3(x, y, z)
     {
         this->frame = frame;
@@ -50,18 +50,23 @@ namespace armarx
         return frame;
     }
 
-    FramedDirectionPtr FramedDirection::ChangeFrame(const VirtualRobot::RobotPtr robot, const FramedDirection &framedVec, const string &newFrame)
+    FramedDirectionPtr FramedDirection::ChangeFrame(const VirtualRobot::RobotPtr robot, const FramedDirection& framedVec, const string& newFrame)
     {
-        if(framedVec.getFrame() == newFrame)
+        if (framedVec.getFrame() == newFrame)
+        {
             return FramedDirectionPtr::dynamicCast(framedVec.clone());
-        if(!robot->hasRobotNode(newFrame))
+        }
+
+        if (!robot->hasRobotNode(newFrame))
+        {
             throw LocalException() << "The requested frame '" << newFrame << "' does not exists in the robot " << robot->getName();
+        }
 
         Eigen::Matrix4f rotToNewFrame = __GetRotationBetweenFrames(framedVec.frame, newFrame, robot);
 
         Eigen::Vector3f vecOldFrame = framedVec.Vector3::toEigen();
 
-        Eigen::Vector3f newVec = rotToNewFrame.block(0,0,3,3).inverse() * vecOldFrame;
+        Eigen::Vector3f newVec = rotToNewFrame.block(0, 0, 3, 3).inverse() * vecOldFrame;
 
         FramedDirectionPtr result = new FramedDirection();
         result->x = newVec(0);
@@ -71,22 +76,29 @@ namespace armarx
         return result;
     }
 
-    void FramedDirection::changeFrame(const VirtualRobot::RobotPtr robot, const string &newFrame)
+    void FramedDirection::changeFrame(const VirtualRobot::RobotPtr robot, const string& newFrame)
     {
-        if(getFrame() == newFrame)
+        if (getFrame() == newFrame)
+        {
             return;
-        if(newFrame == GlobalFrame)
+        }
+
+        if (newFrame == GlobalFrame)
         {
             changeToGlobal(robot);
             return;
         }
-        if(!robot->hasRobotNode(newFrame))
+
+        if (!robot->hasRobotNode(newFrame))
+        {
             throw LocalException() << "The requested frame '" << newFrame << "' does not exists in the robot " << robot->getName();
+        }
+
         Eigen::Matrix4f rotToNewFrame = __GetRotationBetweenFrames(frame, newFrame, robot);
 
         Eigen::Vector3f vecOldFrame = Vector3::toEigen();
 
-        Eigen::Vector3f newVec = rotToNewFrame.block(0,0,3,3).inverse() * vecOldFrame;
+        Eigen::Vector3f newVec = rotToNewFrame.block(0, 0, 3, 3).inverse() * vecOldFrame;
 
 
         x = newVec(0);
@@ -95,18 +107,21 @@ namespace armarx
         frame = newFrame;
     }
 
-    void FramedDirection::changeToGlobal(const SharedRobotInterfacePrx &referenceRobot)
+    void FramedDirection::changeToGlobal(const SharedRobotInterfacePrx& referenceRobot)
     {
         VirtualRobot::RobotPtr sharedRobot(new RemoteRobot(referenceRobot));
         changeToGlobal(sharedRobot);
     }
 
-    void FramedDirection::changeToGlobal(const VirtualRobot::RobotPtr &referenceRobot)
+    void FramedDirection::changeToGlobal(const VirtualRobot::RobotPtr& referenceRobot)
     {
-        if(frame == GlobalFrame)
+        if (frame == GlobalFrame)
+        {
             return;
+        }
+
         changeFrame(referenceRobot, referenceRobot->getRootNode()->getName());
-        Eigen::Vector3f pos = referenceRobot->getRootNode()->getGlobalPose().block<3,3>(0,0) * toEigen();
+        Eigen::Vector3f pos = referenceRobot->getRootNode()->getGlobalPose().block<3, 3>(0, 0) * toEigen();
         x = pos[0];
         y = pos[1];
         z = pos[2];
@@ -114,41 +129,47 @@ namespace armarx
         agent = "";
     }
 
-    FramedDirectionPtr FramedDirection::toGlobal(const SharedRobotInterfacePrx &referenceRobot) const
+    FramedDirectionPtr FramedDirection::toGlobal(const SharedRobotInterfacePrx& referenceRobot) const
     {
         VirtualRobot::RobotPtr sharedRobot(new RemoteRobot(referenceRobot));
         return toGlobal(sharedRobot);
     }
 
-    FramedDirectionPtr FramedDirection::toGlobal(const VirtualRobot::RobotPtr &referenceRobot) const
+    FramedDirectionPtr FramedDirection::toGlobal(const VirtualRobot::RobotPtr& referenceRobot) const
     {
         FramedDirectionPtr newPos = FramedDirectionPtr::dynamicCast(this->clone());
         newPos->changeToGlobal(referenceRobot);
         return newPos;
     }
 
-    string FramedDirection::output(const Ice::Current &c) const
+    string FramedDirection::output(const Ice::Current& c) const
     {
         std::stringstream s;
-        s << toEigen() << std::endl << "frame: " << getFrame() << (agent.empty()?"": (" agent: " + agent));
+        s << toEigen() << std::endl << "frame: " << getFrame() << (agent.empty() ? "" : (" agent: " + agent));
         return s.str();
     }
 
-    Eigen::Matrix4f FramedDirection::__GetRotationBetweenFrames(const std::string &oldFrame, const std::string &newFrame, VirtualRobot::RobotPtr robotState)
+    Eigen::Matrix4f FramedDirection::__GetRotationBetweenFrames(const std::string& oldFrame, const std::string& newFrame, VirtualRobot::RobotPtr robotState)
     {
         Eigen::Matrix4f toNewFrame;
+
         if (oldFrame.compare(GlobalFrame) == 0)
+        {
             toNewFrame = robotState->getRobotNode(newFrame)->getGlobalPose();
+        }
         else
+        {
             toNewFrame = robotState->getRobotNode(oldFrame)->getTransformationTo(robotState->getRobotNode(newFrame));
-        toNewFrame(0,3) = 0;
-        toNewFrame(1,3) = 0;
-        toNewFrame(2,3) = 0;
+        }
+
+        toNewFrame(0, 3) = 0;
+        toNewFrame(1, 3) = 0;
+        toNewFrame(2, 3) = 0;
 
         return toNewFrame;
     }
 
-    int FramedDirection::readFromXML(const string &xmlData, const Ice::Current &c)
+    int FramedDirection::readFromXML(const string& xmlData, const Ice::Current& c)
     {
         int result = Vector3::readFromXML(xmlData);
 
@@ -159,17 +180,17 @@ namespace armarx
         return result;
     }
 
-    string FramedDirection::writeAsXML(const Ice::Current &c)
+    string FramedDirection::writeAsXML(const Ice::Current& c)
     {
         using namespace boost::property_tree;
         ptree pt = Variant::GetPropertyTree(Vector3::writeAsXML());
         pt.add("frame", frame);
 
-        #if BOOST_VERSION >= 105600
-            boost::property_tree::xml_parser::xml_writer_settings<std::string> settings('\t', 1);
-        #else
-            boost::property_tree::xml_parser::xml_writer_settings<char> settings('\t', 1);
-        #endif
+#if BOOST_VERSION >= 105600
+        boost::property_tree::xml_parser::xml_writer_settings<std::string> settings('\t', 1);
+#else
+        boost::property_tree::xml_parser::xml_writer_settings<char> settings('\t', 1);
+#endif
 
         std::stringstream stream;
         xml_parser::write_xml(stream, pt, settings);
@@ -177,7 +198,7 @@ namespace armarx
         return stream.str();
     }
 
-    void FramedDirection::serialize(const ObjectSerializerBasePtr &serializer, const Ice::Current &) const
+    void FramedDirection::serialize(const ObjectSerializerBasePtr& serializer, const Ice::Current&) const
     {
         AbstractObjectSerializerPtr obj = AbstractObjectSerializerPtr::dynamicCast(serializer);
         Vector3::serialize(serializer);
@@ -186,13 +207,16 @@ namespace armarx
 
     }
 
-    void FramedDirection::deserialize(const ObjectSerializerBasePtr &serializer, const Ice::Current &)
+    void FramedDirection::deserialize(const ObjectSerializerBasePtr& serializer, const Ice::Current&)
     {
         AbstractObjectSerializerPtr obj = AbstractObjectSerializerPtr::dynamicCast(serializer);
         Vector3::deserialize(serializer);
         frame = obj->getString("frame");
-        if(obj->hasElement("agent"))
+
+        if (obj->hasElement("agent"))
+        {
             agent = obj->getString("agent");
+        }
     }
 
 
@@ -203,7 +227,7 @@ namespace armarx
         frame = "";
     }
 
-    FramedPose::FramedPose(const FramedPose &pose) :
+    FramedPose::FramedPose(const FramedPose& pose) :
         IceUtil::Shared(pose),
         PoseBase(pose),
         FramedPoseBase(pose),
@@ -212,21 +236,21 @@ namespace armarx
 
     }
 
-    FramedPose::FramedPose(const Eigen::Matrix3f& m, const Eigen::Vector3f& v, const std::string& s, const string &agent) :
+    FramedPose::FramedPose(const Eigen::Matrix3f& m, const Eigen::Vector3f& v, const std::string& s, const string& agent) :
         Pose(m, v)
     {
         frame = s;
         this->agent = agent;
     }
 
-    FramedPose::FramedPose(const Eigen::Matrix4f& m, const std::string& s, const string &agent) :
+    FramedPose::FramedPose(const Eigen::Matrix4f& m, const std::string& s, const string& agent) :
         Pose(m)
     {
         frame = s;
         this->agent = agent;
     }
 
-    FramedPose::FramedPose(const armarx::Vector3BasePtr pos, const armarx::QuaternionBasePtr ori, const std::string& frame, const string &agent) :
+    FramedPose::FramedPose(const armarx::Vector3BasePtr pos, const armarx::QuaternionBasePtr ori, const std::string& frame, const string& agent) :
         Pose(pos, ori)
     {
         this->frame = frame;
@@ -238,34 +262,44 @@ namespace armarx
         return frame;
     }
 
-    string FramedPose::output(const Ice::Current &c) const
+    string FramedPose::output(const Ice::Current& c) const
     {
         std::stringstream s;
-        s << toEigen() << std::endl << "frame: " << getFrame() << (agent.empty()?"": (" agent: " + agent));
+        s << toEigen() << std::endl << "frame: " << getFrame() << (agent.empty() ? "" : (" agent: " + agent));
         return s.str();
     }
 
-    void FramedPose::changeFrame(const SharedRobotInterfacePrx &referenceRobot, const string &newFrame)
+    void FramedPose::changeFrame(const SharedRobotInterfacePrx& referenceRobot, const string& newFrame)
     {
-        if(newFrame == frame)
+        if (newFrame == frame)
+        {
             return;
+        }
 
         VirtualRobot::RobotPtr sharedRobot(new RemoteRobot(referenceRobot));
         changeFrame(sharedRobot, newFrame);
-     }
+    }
 
-    void FramedPose::changeFrame(const VirtualRobot::RobotPtr &referenceRobot, const string &newFrame)
+    void FramedPose::changeFrame(const VirtualRobot::RobotPtr& referenceRobot, const string& newFrame)
     {
-        if(newFrame == frame)
+        if (newFrame == frame)
+        {
             return;
-        if(newFrame == GlobalFrame)
+        }
+
+        if (newFrame == GlobalFrame)
         {
             changeToGlobal(referenceRobot);
             return;
         }
+
         Eigen::Matrix4f oldFrameTransformation = Eigen::Matrix4f::Identity();
-        if(!referenceRobot->hasRobotNode(newFrame))
+
+        if (!referenceRobot->hasRobotNode(newFrame))
+        {
             throw LocalException() << "The requested frame '" << newFrame << "' does not exists in the robot " << referenceRobot->getName();
+        }
+
         if (frame != GlobalFrame)
         {
             oldFrameTransformation = referenceRobot->getRobotNode(frame)->getPoseInRootFrame();
@@ -274,34 +308,38 @@ namespace armarx
         {
             oldFrameTransformation = referenceRobot->getRootNode()->getGlobalPose().inverse();
         }
+
         Eigen::Matrix4f newPose =
-        (referenceRobot->getRobotNode(newFrame)->getPoseInRootFrame().inverse() * oldFrameTransformation) * toEigen();
+            (referenceRobot->getRobotNode(newFrame)->getPoseInRootFrame().inverse() * oldFrameTransformation) * toEigen();
 
         orientation = new Quaternion(newPose);
-        Eigen::Vector3f pos = newPose.block<3,1>(0,3);
+        Eigen::Vector3f pos = newPose.block<3, 1>(0, 3);
         position = new Vector3(pos);
         frame = newFrame;
         init();
     }
 
-    void FramedPose::changeToGlobal(const SharedRobotInterfacePrx &referenceRobot)
+    void FramedPose::changeToGlobal(const SharedRobotInterfacePrx& referenceRobot)
     {
         VirtualRobot::RobotPtr sharedRobot(new RemoteRobot(referenceRobot));
         changeToGlobal(sharedRobot);
 
     }
 
-    void FramedPose::changeToGlobal(const VirtualRobot::RobotPtr &referenceRobot)
+    void FramedPose::changeToGlobal(const VirtualRobot::RobotPtr& referenceRobot)
     {
-        if(frame == GlobalFrame)
+        if (frame == GlobalFrame)
+        {
             return;
+        }
+
         changeFrame(referenceRobot, referenceRobot->getRootNode()->getName());
         Eigen::Matrix4f global = referenceRobot->getRootNode()->getGlobalPose();
         const Eigen::Matrix4f pose = global * toEigen();
-        position->x = pose(0,3);
-        position->y = pose(1,3);
-        position->z = pose(2,3);
-        Eigen::Quaternionf q(pose.block<3,3>(0,0));
+        position->x = pose(0, 3);
+        position->y = pose(1, 3);
+        position->z = pose(2, 3);
+        Eigen::Quaternionf q(pose.block<3, 3>(0, 0));
         orientation->qw = q.w();
         orientation->qx = q.x();
         orientation->qy = q.y();
@@ -310,20 +348,21 @@ namespace armarx
         agent = "";
     }
 
-    FramedPosePtr FramedPose::toGlobal(const SharedRobotInterfacePrx &referenceRobot) const
+    FramedPosePtr FramedPose::toGlobal(const SharedRobotInterfacePrx& referenceRobot) const
     {
         VirtualRobot::RobotPtr sharedRobot(new RemoteRobot(referenceRobot));
         return toGlobal(sharedRobot);
     }
 
-    FramedPosePtr FramedPose::toGlobal(const VirtualRobot::RobotPtr &referenceRobot) const
+    FramedPosePtr FramedPose::toGlobal(const VirtualRobot::RobotPtr& referenceRobot) const
     {
         FramedPosePtr newPose = FramedPosePtr::dynamicCast(this->clone());
         newPose->changeToGlobal(referenceRobot);
         return newPose;
     }
 
-    int FramedPose::readFromXML(const string &xmlData, const Ice::Current &c){
+    int FramedPose::readFromXML(const string& xmlData, const Ice::Current& c)
+    {
         boost::property_tree::ptree pt = Variant::GetPropertyTree(xmlData);
 
 
@@ -333,12 +372,12 @@ namespace armarx
         return 1;
     }
 
-    string FramedPose::writeAsXML(const Ice::Current &)
+    string FramedPose::writeAsXML(const Ice::Current&)
     {
         using namespace boost::property_tree;
         std::stringstream stream;
         stream << Pose::writeAsXML()
-               << "<frame>"<<frame<<"</frame>";
+               << "<frame>" << frame << "</frame>";
         return stream.str();
     }
 
@@ -369,8 +408,11 @@ namespace armarx
 
         Pose::deserialize(obj);
         frame = obj->getString("frame");
-        if(obj->hasElement("agent"))
+
+        if (obj->hasElement("agent"))
+        {
             agent = obj->getString("agent");
+        }
     }
 
     FramedPosition::FramedPosition() :
@@ -379,14 +421,14 @@ namespace armarx
         frame = "";
     }
 
-    FramedPosition::FramedPosition(const Eigen::Vector3f &v, const std::string &s, const string &agent) :
+    FramedPosition::FramedPosition(const Eigen::Vector3f& v, const std::string& s, const string& agent) :
         Vector3(v)
     {
         frame = s;
         this->agent = agent;
     }
 
-    FramedPosition::FramedPosition(const Eigen::Matrix4f &m, const std::string &s, const string &agent) :
+    FramedPosition::FramedPosition(const Eigen::Matrix4f& m, const std::string& s, const string& agent) :
         Vector3(m)
     {
         frame = s;
@@ -394,44 +436,55 @@ namespace armarx
     }
 
     // this doesnt work for unknown reasons
-//    FramedPosition::FramedPosition(const Vector3BasePtr pos, const std::string &frame )
-//    {
-//        this->x = pos->x;
-//        this->y = pos->y;
-//        this->z = pos->z;
-//        this->frame = frame;
-//    }
+    //    FramedPosition::FramedPosition(const Vector3BasePtr pos, const std::string &frame )
+    //    {
+    //        this->x = pos->x;
+    //        this->y = pos->y;
+    //        this->z = pos->z;
+    //        this->frame = frame;
+    //    }
 
     std::string FramedPosition::getFrame() const
     {
         return this->frame;
     }
 
-    void FramedPosition::changeFrame(const SharedRobotInterfacePrx &referenceRobot, const string &newFrame)
+    void FramedPosition::changeFrame(const SharedRobotInterfacePrx& referenceRobot, const string& newFrame)
     {
-        if(newFrame == frame)
+        if (newFrame == frame)
+        {
             return;
+        }
 
-        if(!referenceRobot->hasRobotNode(newFrame))
+        if (!referenceRobot->hasRobotNode(newFrame))
+        {
             throw LocalException() << "The requested frame '" << newFrame << "' does not exists in the robot " << referenceRobot->getName();
+        }
+
         VirtualRobot::RobotPtr sharedRobot(new RemoteRobot(referenceRobot));
         changeFrame(sharedRobot, newFrame);
     }
 
-    void FramedPosition::changeFrame(const VirtualRobot::RobotPtr &referenceRobot, const string &newFrame)
+    void FramedPosition::changeFrame(const VirtualRobot::RobotPtr& referenceRobot, const string& newFrame)
     {
-        if(newFrame == frame)
+        if (newFrame == frame)
+        {
             return;
+        }
 
-        if(newFrame == GlobalFrame)
+        if (newFrame == GlobalFrame)
         {
             changeToGlobal(referenceRobot);
             return;
         }
 
         Eigen::Matrix4f oldFrameTransformation = Eigen::Matrix4f::Identity();
-        if(!referenceRobot->hasRobotNode(newFrame))
+
+        if (!referenceRobot->hasRobotNode(newFrame))
+        {
             throw LocalException() << "The requested frame '" << newFrame << "' does not exists in the robot " << referenceRobot->getName();
+        }
+
         if (frame != GlobalFrame)
         {
             oldFrameTransformation = referenceRobot->getRobotNode(frame)->getPoseInRootFrame();
@@ -440,31 +493,35 @@ namespace armarx
         {
             oldFrameTransformation = referenceRobot->getRootNode()->getGlobalPose().inverse();
         }
+
         Eigen::Matrix4f oldPose = Eigen::Matrix4f::Identity();
-        oldPose.block<3,1>(0,3) = toEigen();
+        oldPose.block<3, 1>(0, 3) = toEigen();
         Eigen::Matrix4f newPose =
-        (referenceRobot->getRobotNode(newFrame)->getPoseInRootFrame().inverse() * oldFrameTransformation) * oldPose;
+            (referenceRobot->getRobotNode(newFrame)->getPoseInRootFrame().inverse() * oldFrameTransformation) * oldPose;
 
-        Eigen::Vector3f pos = newPose.block<3,1>(0,3);
+        Eigen::Vector3f pos = newPose.block<3, 1>(0, 3);
         x = pos[0];
         y = pos[1];
         z = pos[2];
         frame = newFrame;
     }
 
-    void FramedPosition::changeToGlobal(const SharedRobotInterfacePrx &referenceRobot)
+    void FramedPosition::changeToGlobal(const SharedRobotInterfacePrx& referenceRobot)
     {
         VirtualRobot::RobotPtr sharedRobot(new RemoteRobot(referenceRobot));
         changeToGlobal(sharedRobot);
     }
 
-    void FramedPosition::changeToGlobal(const VirtualRobot::RobotPtr &referenceRobot)
+    void FramedPosition::changeToGlobal(const VirtualRobot::RobotPtr& referenceRobot)
     {
-        if(frame == GlobalFrame)
+        if (frame == GlobalFrame)
+        {
             return;
+        }
+
         changeFrame(referenceRobot, referenceRobot->getRootNode()->getName());
-        Eigen::Vector3f pos = referenceRobot->getRootNode()->getGlobalPose().block<3,3>(0,0) * toEigen()
-                + referenceRobot->getRootNode()->getGlobalPose().block<3,1>(0,3);
+        Eigen::Vector3f pos = referenceRobot->getRootNode()->getGlobalPose().block<3, 3>(0, 0) * toEigen()
+                              + referenceRobot->getRootNode()->getGlobalPose().block<3, 1>(0, 3);
         x = pos[0];
         y = pos[1];
         z = pos[2];
@@ -472,27 +529,28 @@ namespace armarx
         agent = "";
     }
 
-    FramedPositionPtr FramedPosition::toGlobal(const SharedRobotInterfacePrx &referenceRobot) const
+    FramedPositionPtr FramedPosition::toGlobal(const SharedRobotInterfacePrx& referenceRobot) const
     {
         VirtualRobot::RobotPtr sharedRobot(new RemoteRobot(referenceRobot));
         return toGlobal(sharedRobot);
     }
 
-    FramedPositionPtr FramedPosition::toGlobal(const VirtualRobot::RobotPtr &referenceRobot) const
+    FramedPositionPtr FramedPosition::toGlobal(const VirtualRobot::RobotPtr& referenceRobot) const
     {
         FramedPositionPtr newPos = FramedPositionPtr::dynamicCast(this->clone());
         newPos->changeToGlobal(referenceRobot);
         return newPos;
     }
 
-    string FramedPosition::output(const Ice::Current &c) const
+    string FramedPosition::output(const Ice::Current& c) const
     {
         std::stringstream s;
-        s << toEigen() << std::endl << "frame: " << getFrame() << (agent.empty()?"": (" agent: " + agent));
+        s << toEigen() << std::endl << "frame: " << getFrame() << (agent.empty() ? "" : (" agent: " + agent));
         return s.str();
     }
 
-    int FramedPosition::readFromXML(const string &xmlData, const Ice::Current &c){
+    int FramedPosition::readFromXML(const string& xmlData, const Ice::Current& c)
+    {
         using namespace boost::property_tree;
         ptree pt;
         std::stringstream stream;
@@ -506,13 +564,13 @@ namespace armarx
         return 1;
     }
 
-    string FramedPosition::writeAsXML(const Ice::Current &)
+    string FramedPosition::writeAsXML(const Ice::Current&)
     {
         using namespace boost::property_tree;
         std::stringstream stream;
         stream << Vector3::writeAsXML() <<
-                  "<frame>"<<frame<<"</frame>"<<
-                  "<agent>"<<agent<<"</agent>";
+               "<frame>" << frame << "</frame>" <<
+               "<agent>" << agent << "</agent>";
         return stream.str();
     }
 
@@ -531,8 +589,11 @@ namespace armarx
 
         Vector3::deserialize(obj);
         frame = obj->getString("frame");
-        if(obj->hasElement("agent"))
+
+        if (obj->hasElement("agent"))
+        {
             agent = obj->getString("agent");
+        }
     }
 
 
@@ -542,14 +603,14 @@ namespace armarx
         frame = "";
     }
 
-    FramedOrientation::FramedOrientation(const Eigen::Matrix3f &m, const std::string &s, const string &agent) :
+    FramedOrientation::FramedOrientation(const Eigen::Matrix3f& m, const std::string& s, const string& agent) :
         Quaternion(m)
     {
         frame = s;
         this->agent = agent;
     }
 
-    FramedOrientation::FramedOrientation(const Eigen::Matrix4f &m, const std::string &s, const std::string &agent) :
+    FramedOrientation::FramedOrientation(const Eigen::Matrix4f& m, const std::string& s, const std::string& agent) :
         Quaternion(m)
     {
         frame = s;
@@ -557,48 +618,57 @@ namespace armarx
     }
 
     // this doesnt work for an unknown reason
-//    FramedOrientation::FramedOrientation(const QuaternionBasePtr ori, const std::string &frame )
-//    {
-//        Matrix3f rot;
-//        rot = Quaternionf(ori->qw, ori->qx, ori->qy, ori->qz);
-//        FramedOrientation(rot, frame);
-//    }
+    //    FramedOrientation::FramedOrientation(const QuaternionBasePtr ori, const std::string &frame )
+    //    {
+    //        Matrix3f rot;
+    //        rot = Quaternionf(ori->qw, ori->qx, ori->qy, ori->qz);
+    //        FramedOrientation(rot, frame);
+    //    }
 
     std::string FramedOrientation::getFrame() const
     {
         return this->frame;
     }
 
-    string FramedOrientation::output(const Ice::Current &c) const
+    string FramedOrientation::output(const Ice::Current& c) const
     {
         std::stringstream s;
-        s << toEigen() << std::endl << "frame: " << getFrame() << (agent.empty()?"": (" agent: " + agent));
+        s << toEigen() << std::endl << "frame: " << getFrame() << (agent.empty() ? "" : (" agent: " + agent));
         return s.str();
     }
 
-    void FramedOrientation::changeFrame(const SharedRobotInterfacePrx &referenceRobot, const string &newFrame)
+    void FramedOrientation::changeFrame(const SharedRobotInterfacePrx& referenceRobot, const string& newFrame)
     {
-        if(newFrame == frame)
+        if (newFrame == frame)
+        {
             return;
+        }
 
         VirtualRobot::RobotPtr sharedRobot(new RemoteRobot(referenceRobot));
 
         changeFrame(sharedRobot, newFrame);
     }
 
-    void FramedOrientation::changeFrame(const VirtualRobot::RobotPtr &referenceRobot, const string &newFrame)
+    void FramedOrientation::changeFrame(const VirtualRobot::RobotPtr& referenceRobot, const string& newFrame)
     {
-        if(newFrame == frame)
+        if (newFrame == frame)
+        {
             return;
-        if(newFrame == GlobalFrame)
+        }
+
+        if (newFrame == GlobalFrame)
         {
             changeToGlobal(referenceRobot);
             return;
         }
 
         Eigen::Matrix4f oldFrameTransformation = Eigen::Matrix4f::Identity();
-        if(!referenceRobot->hasRobotNode(newFrame))
+
+        if (!referenceRobot->hasRobotNode(newFrame))
+        {
             throw LocalException() << "The requested frame '" << newFrame << "' does not exists in the robot " << referenceRobot->getName();
+        }
+
         if (frame != GlobalFrame)
         {
             oldFrameTransformation = referenceRobot->getRobotNode(frame)->getPoseInRootFrame();
@@ -609,12 +679,12 @@ namespace armarx
         }
 
         Eigen::Matrix4f oldPose = Eigen::Matrix4f::Identity();
-        oldPose.block<3,3>(0,0) = toEigen();
+        oldPose.block<3, 3>(0, 0) = toEigen();
 
         Eigen::Matrix4f newPose =
-        (referenceRobot->getRobotNode(newFrame)->getPoseInRootFrame().inverse() * oldFrameTransformation) * oldPose;
+            (referenceRobot->getRobotNode(newFrame)->getPoseInRootFrame().inverse() * oldFrameTransformation) * oldPose;
 
-        Eigen::Quaternionf quat(newPose.block<3,3>(0,0));
+        Eigen::Quaternionf quat(newPose.block<3, 3>(0, 0));
         qw = quat.w();
         qx = quat.x();
         qy = quat.y();
@@ -622,18 +692,21 @@ namespace armarx
         frame = newFrame;
     }
 
-    void FramedOrientation::changeToGlobal(const SharedRobotInterfacePrx &referenceRobot)
+    void FramedOrientation::changeToGlobal(const SharedRobotInterfacePrx& referenceRobot)
     {
         VirtualRobot::RobotPtr sharedRobot(new RemoteRobot(referenceRobot));
         changeToGlobal(sharedRobot);
     }
 
-    void FramedOrientation::changeToGlobal(const VirtualRobot::RobotPtr &referenceRobot)
+    void FramedOrientation::changeToGlobal(const VirtualRobot::RobotPtr& referenceRobot)
     {
-        if(frame == GlobalFrame)
+        if (frame == GlobalFrame)
+        {
             return;
+        }
+
         changeFrame(referenceRobot, referenceRobot->getRootNode()->getName());
-        Eigen::Matrix3f rot = referenceRobot->getRootNode()->getGlobalPose().block<3,3>(0,0) * toEigen();
+        Eigen::Matrix3f rot = referenceRobot->getRootNode()->getGlobalPose().block<3, 3>(0, 0) * toEigen();
         Eigen::Quaternionf quat(rot);
         qw = quat.w();
         qx = quat.x();
@@ -643,20 +716,20 @@ namespace armarx
         agent = "";
     }
 
-    FramedOrientationPtr FramedOrientation::toGlobal(const SharedRobotInterfacePrx &referenceRobot) const
+    FramedOrientationPtr FramedOrientation::toGlobal(const SharedRobotInterfacePrx& referenceRobot) const
     {
         VirtualRobot::RobotPtr sharedRobot(new RemoteRobot(referenceRobot));
         return toGlobal(sharedRobot);
     }
 
-    FramedOrientationPtr FramedOrientation::toGlobal(const VirtualRobot::RobotPtr &referenceRobot) const
+    FramedOrientationPtr FramedOrientation::toGlobal(const VirtualRobot::RobotPtr& referenceRobot) const
     {
         FramedOrientationPtr newPos = FramedOrientationPtr::dynamicCast(this->clone());
         newPos->changeToGlobal(referenceRobot);
         return newPos;
     }
 
-    int FramedOrientation::readFromXML(const string &xmlData, const Ice::Current &c)
+    int FramedOrientation::readFromXML(const string& xmlData, const Ice::Current& c)
     {
         using namespace boost::property_tree;
         ptree pt;
@@ -671,13 +744,13 @@ namespace armarx
         return 1;
     }
 
-    string FramedOrientation::writeAsXML(const Ice::Current &)
+    string FramedOrientation::writeAsXML(const Ice::Current&)
     {
         using namespace boost::property_tree;
         std::stringstream stream;
         stream << Quaternion::writeAsXML() <<
-                  "<frame>" << frame << "</frame>" <<
-                  "<agent>" << agent << "</agent>";
+               "<frame>" << frame << "</frame>" <<
+               "<agent>" << agent << "</agent>";
         return stream.str();
     }
 
@@ -696,22 +769,26 @@ namespace armarx
 
         Quaternion::deserialize(obj);
         frame = obj->getString("frame");
-        if(obj->hasElement("agent"))
+
+        if (obj->hasElement("agent"))
+        {
             agent = obj->getString("agent");
+        }
     }
 
 
-    VirtualRobot::LinkedCoordinate FramedPose::createLinkedCoordinate(const VirtualRobot::RobotPtr &virtualRobot, const FramedPositionPtr& position, const FramedOrientationPtr& orientation)
+    VirtualRobot::LinkedCoordinate FramedPose::createLinkedCoordinate(const VirtualRobot::RobotPtr& virtualRobot, const FramedPositionPtr& position, const FramedOrientationPtr& orientation)
     {
         VirtualRobot::LinkedCoordinate c(virtualRobot);
         std::string frame;
+
         if (position)
         {
             frame = position->getFrame();
 
             if (orientation)
             {
-                if(!frame.empty() && frame != orientation->getFrame())
+                if (!frame.empty() && frame != orientation->getFrame())
                 {
                     throw armarx::UserException("Error: frames mismatch");
                 }
@@ -720,17 +797,26 @@ namespace armarx
         else
         {
             if (!orientation)
+            {
                 armarx::UserException("createLinkedCoordinate: orientation and position are both NULL");
+            }
             else
+            {
                 frame = orientation->getFrame();
+            }
         }
 
         Eigen::Matrix4f pose = Eigen::Matrix4f::Identity();
 
-        if(orientation)
-            pose.block<3,3>(0,0) = orientation->toEigen();
-        if(position)
-            pose.block<3,1>(0,3) = position->toEigen();
+        if (orientation)
+        {
+            pose.block<3, 3>(0, 0) = orientation->toEigen();
+        }
+
+        if (position)
+        {
+            pose.block<3, 1>(0, 3) = position->toEigen();
+        }
 
         c.set(frame, pose);
 
diff --git a/source/RobotAPI/libraries/core/FramedPose.h b/source/RobotAPI/libraries/core/FramedPose.h
index 423a50c322fba6b0578e10297534a8558370ff0e..b247d8aaa8534175a05f089bfc9a55bdfaf6e443 100644
--- a/source/RobotAPI/libraries/core/FramedPose.h
+++ b/source/RobotAPI/libraries/core/FramedPose.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    RobotAPI::RobotStateComponent::
  * @author     ( stefan dot ulbrich at kit dot edu)
  * @date
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -30,10 +29,10 @@
 
 #include <RobotAPI/interface/core/FramedPoseBase.h>
 #include <RobotAPI/interface/core/RobotState.h>
-#include <Core/observers/variant/Variant.h>
-#include <Core/observers/AbstractObjectSerializer.h>
+#include <ArmarXCore/observers/variant/Variant.h>
+#include <ArmarXCore/observers/AbstractObjectSerializer.h>
 
-#include <Core/core/exceptions/local/ExpressionException.h>
+#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 
 #include <RobotAPI/libraries/core/Pose.h>
 
@@ -63,7 +62,7 @@ namespace armarx
     /**
      * @class FramedDirection
      * @ingroup RobotAPI-FramedPose
-     * @ingroup Variants
+     * @ingroup VariantsGrp
      * @brief FramedDirection is a 3 dimensional @b direction vector with a reference frame.
      * The reference frame can be used to change the coordinate system to which
      * the vector relates. The difference to a FramedPosition is, that on frame
@@ -77,18 +76,18 @@ namespace armarx
     typedef IceInternal::Handle<FramedDirection> FramedDirectionPtr;
 
     class FramedDirection :
-            virtual public FramedDirectionBase,
-            virtual public Vector3
+        virtual public FramedDirectionBase,
+        virtual public Vector3
     {
     public:
         FramedDirection();
         FramedDirection(const FramedDirection& source);
-        FramedDirection(const Eigen::Vector3f & vec, const std::string &frame, const std::string& agent );
-        FramedDirection(Ice::Float x, ::Ice::Float y, ::Ice::Float z, const std::string &frame);
+        FramedDirection(const Eigen::Vector3f& vec, const std::string& frame, const std::string& agent);
+        FramedDirection(Ice::Float x, ::Ice::Float y, ::Ice::Float z, const std::string& frame);
 
         std::string getFrame() const;
-        static FramedDirectionPtr ChangeFrame(const VirtualRobot::RobotPtr robot, const FramedDirection& framedVec, const std::string &newFrame);
-        void changeFrame(const VirtualRobot::RobotPtr robot, const std::string &newFrame);
+        static FramedDirectionPtr ChangeFrame(const VirtualRobot::RobotPtr robot, const FramedDirection& framedVec, const std::string& newFrame);
+        void changeFrame(const VirtualRobot::RobotPtr robot, const std::string& newFrame);
 
         void changeToGlobal(const SharedRobotInterfacePrx& referenceRobot);
         void changeToGlobal(const VirtualRobot::RobotPtr& referenceRobot);
@@ -128,10 +127,10 @@ namespace armarx
              * @return ErrorCode, 1 on Success
              * @deprecated
              */
-        int readFromXML(const std::string &xmlData, const Ice::Current &c = ::Ice::Current());
-        std::string writeAsXML(const Ice::Current &c = ::Ice::Current());
+        int readFromXML(const std::string& xmlData, const Ice::Current& c = ::Ice::Current());
+        std::string writeAsXML(const Ice::Current& c = ::Ice::Current());
 
-        friend std::ostream &operator<<(std::ostream &stream, const FramedDirection& rhs)
+        friend std::ostream& operator<<(std::ostream& stream, const FramedDirection& rhs)
         {
             stream << "FramedDirection: " << std::endl << rhs.output() << std::endl;
             return stream;
@@ -142,7 +141,7 @@ namespace armarx
         virtual void deserialize(const armarx::ObjectSerializerBasePtr& serializer, const ::Ice::Current& = ::Ice::Current());
     private:
 
-        static Eigen::Matrix4f __GetRotationBetweenFrames(const std::string &oldFrame, const std::string &newFrame, VirtualRobot::RobotPtr robotState);
+        static Eigen::Matrix4f __GetRotationBetweenFrames(const std::string& oldFrame, const std::string& newFrame, VirtualRobot::RobotPtr robotState);
     };
 
     class FramedPosition;
@@ -150,23 +149,23 @@ namespace armarx
 
     /**
      * @class FramedPosition
-     * @ingroup Variants
+     * @ingroup VariantsGrp
      * @ingroup RobotAPI-FramedPose
      * @brief The FramedPosition class
      */
     class FramedPosition :
-            virtual public FramedPositionBase,
-            virtual public Vector3
+        virtual public FramedPositionBase,
+        virtual public Vector3
     {
     public:
-        FramedPosition( );
-        FramedPosition(const Eigen::Vector3f &, const std::string &frame, const std::string &agent);
-        FramedPosition(const Eigen::Matrix4f &, const std::string &frame, const std::string &agent);
+        FramedPosition();
+        FramedPosition(const Eigen::Vector3f&, const std::string& frame, const std::string& agent);
+        FramedPosition(const Eigen::Matrix4f&, const std::string& frame, const std::string& agent);
         //FramedPosition(const Vector3BasePtr pos, const std::string &frame ); // this doesnt work for unknown reasons
         std::string getFrame() const;
 
-        void changeFrame(const SharedRobotInterfacePrx& referenceRobot, const std::string &newFrame);
-        void changeFrame(const VirtualRobot::RobotPtr& referenceRobot, const std::string &newFrame);
+        void changeFrame(const SharedRobotInterfacePrx& referenceRobot, const std::string& newFrame);
+        void changeFrame(const VirtualRobot::RobotPtr& referenceRobot, const std::string& newFrame);
         void changeToGlobal(const SharedRobotInterfacePrx& referenceRobot);
         void changeToGlobal(const VirtualRobot::RobotPtr& referenceRobot);
         FramedPositionPtr toGlobal(const SharedRobotInterfacePrx& referenceRobot) const;
@@ -206,10 +205,10 @@ namespace armarx
              * @return ErrorCode, 1 on Success
              * @deprecated
              */
-        int readFromXML(const std::string &xmlData, const Ice::Current &c = ::Ice::Current());
-        std::string writeAsXML(const Ice::Current &c = ::Ice::Current());
+        int readFromXML(const std::string& xmlData, const Ice::Current& c = ::Ice::Current());
+        std::string writeAsXML(const Ice::Current& c = ::Ice::Current());
 
-        friend std::ostream &operator<<(std::ostream &stream, const FramedPosition& rhs)
+        friend std::ostream& operator<<(std::ostream& stream, const FramedPosition& rhs)
         {
             stream << "FramedPosition: " << std::endl << rhs.output() << std::endl;
             return stream;
@@ -225,18 +224,18 @@ namespace armarx
 
     /**
      * @class FramedOrientation
-     * @ingroup Variants
+     * @ingroup VariantsGrp
      * @ingroup RobotAPI-FramedPose
      * @brief The FramedOrientation class
      */
     class FramedOrientation :
-            virtual public FramedOrientationBase,
-            virtual public Quaternion
+        virtual public FramedOrientationBase,
+        virtual public Quaternion
     {
     public:
         FramedOrientation();
-        FramedOrientation(const Eigen::Matrix4f &, const std::string &frame, const std::string &agent );
-        FramedOrientation(const Eigen::Matrix3f &, const std::string &frame, const std::string &agent );
+        FramedOrientation(const Eigen::Matrix4f&, const std::string& frame, const std::string& agent);
+        FramedOrientation(const Eigen::Matrix3f&, const std::string& frame, const std::string& agent);
         // this doesnt work for an unknown reason
         //FramedOrientation(const QuaternionBasePtr ori, const std::string &frame );
         std::string getFrame()const ;
@@ -260,8 +259,8 @@ namespace armarx
             return true;
         }
 
-        void changeFrame(const SharedRobotInterfacePrx& referenceRobot, const std::string &newFrame);
-        void changeFrame(const VirtualRobot::RobotPtr& referenceRobot, const std::string &newFrame);
+        void changeFrame(const SharedRobotInterfacePrx& referenceRobot, const std::string& newFrame);
+        void changeFrame(const VirtualRobot::RobotPtr& referenceRobot, const std::string& newFrame);
         void changeToGlobal(const SharedRobotInterfacePrx& referenceRobot);
         void changeToGlobal(const VirtualRobot::RobotPtr& referenceRobot);
         FramedOrientationPtr toGlobal(const SharedRobotInterfacePrx& referenceRobot) const;
@@ -282,10 +281,10 @@ namespace armarx
              * @return ErrorCode, 1 on Success
              * @deprecated
              */
-        int readFromXML(const std::string &xmlData, const Ice::Current &c = ::Ice::Current());
-        std::string writeAsXML(const Ice::Current &c = ::Ice::Current());
+        int readFromXML(const std::string& xmlData, const Ice::Current& c = ::Ice::Current());
+        std::string writeAsXML(const Ice::Current& c = ::Ice::Current());
 
-        friend std::ostream &operator<<(std::ostream &stream, const FramedOrientation& rhs)
+        friend std::ostream& operator<<(std::ostream& stream, const FramedOrientation& rhs)
         {
             stream << "FramedOrientation: " << std::endl << rhs.output() << std::endl;
             return stream;
@@ -303,13 +302,13 @@ namespace armarx
 
     /**
      * @class FramedPose
-     * @ingroup Variants
+     * @ingroup VariantsGrp
      * @ingroup RobotAPI-FramedPose
      * @brief The FramedPose class
      */
     class FramedPose :
-            virtual public FramedPoseBase,
-            virtual public Pose
+        virtual public FramedPoseBase,
+        virtual public Pose
     {
     public:
         FramedPose();
@@ -343,8 +342,8 @@ namespace armarx
             return true;
         }
 
-        void changeFrame(const SharedRobotInterfacePrx& referenceRobot, const std::string &newFrame);
-        void changeFrame(const VirtualRobot::RobotPtr &referenceRobot, const std::string &newFrame);
+        void changeFrame(const SharedRobotInterfacePrx& referenceRobot, const std::string& newFrame);
+        void changeFrame(const VirtualRobot::RobotPtr& referenceRobot, const std::string& newFrame);
         void changeToGlobal(const SharedRobotInterfacePrx& referenceRobot);
         void changeToGlobal(const VirtualRobot::RobotPtr& referenceRobot);
         FramedPosePtr toGlobal(const SharedRobotInterfacePrx& referenceRobot) const;
@@ -366,10 +365,10 @@ namespace armarx
              * @return ErrorCode, 1 on Success
              * @deprecated
              */
-        int readFromXML(const std::string &xmlData, const Ice::Current &c = ::Ice::Current());
-        std::string writeAsXML(const Ice::Current &c = ::Ice::Current());
+        int readFromXML(const std::string& xmlData, const Ice::Current& c = ::Ice::Current());
+        std::string writeAsXML(const Ice::Current& c = ::Ice::Current());
 
-        friend std::ostream &operator<<(std::ostream &stream, const FramedPose& rhs)
+        friend std::ostream& operator<<(std::ostream& stream, const FramedPose& rhs)
         {
             stream << "FramedPose: " << std::endl << rhs.output() << std::endl;
             return stream;
@@ -377,7 +376,7 @@ namespace armarx
         FramedPositionPtr getPosition() const;
         FramedOrientationPtr getOrientation() const;
 
-        static VirtualRobot::LinkedCoordinate createLinkedCoordinate(const VirtualRobot::RobotPtr &virtualRobot, const FramedPositionPtr& position, const FramedOrientationPtr& orientation);
+        static VirtualRobot::LinkedCoordinate createLinkedCoordinate(const VirtualRobot::RobotPtr& virtualRobot, const FramedPositionPtr& position, const FramedOrientationPtr& orientation);
 
     public:
         virtual void serialize(const armarx::ObjectSerializerBasePtr& serializer, const ::Ice::Current& = ::Ice::Current()) const;
diff --git a/source/RobotAPI/libraries/core/LinkedPose.cpp b/source/RobotAPI/libraries/core/LinkedPose.cpp
index d7089a5691008e10abe32cfa14f7657db5e2d0e1..ea4ebcb674a323ed0c2dd1083608ec9f1d0e462f 100644
--- a/source/RobotAPI/libraries/core/LinkedPose.cpp
+++ b/source/RobotAPI/libraries/core/LinkedPose.cpp
@@ -3,7 +3,7 @@
 #include <RobotAPI/libraries/core/remoterobot/RemoteRobot.h>
 //#include "SharedRobotServants.h"
 
-#include <Core/core/logging/Logging.h>
+#include <ArmarXCore/core/logging/Logging.h>
 
 #include <boost/property_tree/ptree.hpp>
 #include <boost/property_tree/xml_parser.hpp>
@@ -16,7 +16,8 @@
 #include <Ice/ObjectAdapter.h>
 
 
-namespace armarx {
+namespace armarx
+{
 
     LinkedPose::LinkedPose() :
         Pose(),
@@ -25,7 +26,7 @@ namespace armarx {
         this->referenceRobot = NULL;
     }
 
-    LinkedPose::LinkedPose(const LinkedPose &other) :
+    LinkedPose::LinkedPose(const LinkedPose& other) :
         IceUtil::Shared(other),
         PoseBase(other),
         FramedPoseBase(other),
@@ -33,14 +34,14 @@ namespace armarx {
         Pose(other),
         FramedPose(other)
     {
-        if(referenceRobot)
+        if (referenceRobot)
         {
             //ARMARX_WARNING_S << "Calling referenceRobot->ref() in cctor of LinkedPose";
             referenceRobot->ref();
         }
     }
 
-    LinkedPose::LinkedPose(const FramedPose &other, const SharedRobotInterfacePrx &referenceRobot) :
+    LinkedPose::LinkedPose(const FramedPose& other, const SharedRobotInterfacePrx& referenceRobot) :
         IceUtil::Shared(other),
         PoseBase(other),
         FramedPoseBase(other),
@@ -49,7 +50,8 @@ namespace armarx {
     {
         ARMARX_CHECK_EXPRESSION_W_HINT(referenceRobot, "The robot proxy must not be zero");
         this->referenceRobot = referenceRobot;
-        if(referenceRobot)
+
+        if (referenceRobot)
         {
             //ARMARX_WARNING_S << "Calling referenceRobot->ref() in cctor of LinkedPose";
             referenceRobot->ref();
@@ -63,7 +65,7 @@ namespace armarx {
     {
         ARMARX_CHECK_EXPRESSION_W_HINT(referenceRobot, "The robot proxy must not be zero");
         referenceRobot->ref();
-        this->referenceRobot = referenceRobot;        
+        this->referenceRobot = referenceRobot;
     }
 
     LinkedPose::LinkedPose(const Eigen::Matrix4f& m, const std::string& s, const SharedRobotInterfacePrx& referenceRobot) :
@@ -77,13 +79,14 @@ namespace armarx {
 
     LinkedPose::~LinkedPose()
     {
-        try{
-            if(referenceRobot)
+        try
+        {
+            if (referenceRobot)
             {
                 referenceRobot->unref();
             }
         }
-        catch(...)
+        catch (...)
         {
             handleExceptions();
         }
@@ -98,8 +101,8 @@ namespace armarx {
 
         Eigen::Matrix4f pose = Eigen::Matrix4f::Identity();
 
-        pose.block<3,3>(0,0) = QuaternionPtr::dynamicCast(orientation)->toEigen();
-        pose.block<3,1>(0,3) = Vector3Ptr::dynamicCast(position)->toEigen();
+        pose.block<3, 3>(0, 0) = QuaternionPtr::dynamicCast(orientation)->toEigen();
+        pose.block<3, 1>(0, 3) = Vector3Ptr::dynamicCast(position)->toEigen();
 
         c.set(frame, pose);
 
@@ -111,29 +114,29 @@ namespace armarx {
         return this->clone();
     }
 
-    VariantDataClassPtr LinkedPose::clone(const Ice::Current &c) const
+    VariantDataClassPtr LinkedPose::clone(const Ice::Current& c) const
     {
         return new LinkedPose(*this);
     }
 
-    std::string LinkedPose::output(const Ice::Current &c) const
+    std::string LinkedPose::output(const Ice::Current& c) const
     {
         std::stringstream s;
         s << FramedPose::output() << std::endl << "reference robot: " << referenceRobot->ice_toString();
         return s.str();
     }
 
-    VariantTypeId LinkedPose::getType(const Ice::Current &c) const
+    VariantTypeId LinkedPose::getType(const Ice::Current& c) const
     {
         return VariantType::LinkedPose;
     }
 
-    bool LinkedPose::validate(const Ice::Current &c)
+    bool LinkedPose::validate(const Ice::Current& c)
     {
         return true;
     }
 
-    void LinkedPose::changeFrame(const std::string &newFrame, const Ice::Current &c)
+    void LinkedPose::changeFrame(const std::string& newFrame, const Ice::Current& c)
     {
         FramedPose::changeFrame(referenceRobot, newFrame);
     }
@@ -151,7 +154,8 @@ namespace armarx {
     }
 
 
-    int LinkedPose::readFromXML(const std::string &xmlData, const Ice::Current &c){
+    int LinkedPose::readFromXML(const std::string& xmlData, const Ice::Current& c)
+    {
         using namespace boost::property_tree;
         ptree pt;
         std::stringstream stream;
@@ -163,7 +167,8 @@ namespace armarx {
 
         std::string remoteRobotId = pt.get<std::string>("referenceRobot");
         referenceRobot = SharedRobotInterfacePrx::uncheckedCast(c.adapter->getCommunicator()->stringToProxy(remoteRobotId));
-        if(!referenceRobot)
+
+        if (!referenceRobot)
         {
             ARMARX_ERROR_S << "ReferenceRobot for LinkedPose not registered: " << remoteRobotId << flush;
             return 0;
@@ -177,7 +182,7 @@ namespace armarx {
         using namespace boost::property_tree;
         std::stringstream stream;
         stream << FramedPose::writeAsXML()
-               << "<referenceRobot>" << "Not serializable" <<"</referenceRobot>";
+               << "<referenceRobot>" << "Not serializable" << "</referenceRobot>";
         return stream.str();
     }
 
@@ -197,7 +202,8 @@ namespace armarx {
 
         std::string remoteRobotId = obj->getString("referenceRobot");
         referenceRobot = SharedRobotInterfacePrx::uncheckedCast(c.adapter->getCommunicator()->stringToProxy(remoteRobotId));
-        if(!referenceRobot)
+
+        if (!referenceRobot)
         {
             ARMARX_ERROR_S << "ReferenceRobot for LinkedPose not registered: " << remoteRobotId << flush;
         }
@@ -205,11 +211,12 @@ namespace armarx {
 
     void LinkedPose::ice_postUnmarshal()
     {
-        if(referenceRobot)
+        if (referenceRobot)
         {
             //ARMARX_WARNING_S << "Calling referenceRobot->ref() in __read(IceInternal::BasicStream *__is, bool __rid) of LinkedPose";
             referenceRobot->ref();
         }
+
         FramedPose::ice_postUnmarshal();
     }
 
@@ -218,7 +225,7 @@ namespace armarx {
     {
     }
 
-    LinkedDirection::LinkedDirection(const LinkedDirection &source) :
+    LinkedDirection::LinkedDirection(const LinkedDirection& source) :
         IceUtil::Shared(source),
         Vector3Base(source),
         FramedDirectionBase(source),
@@ -227,14 +234,15 @@ namespace armarx {
         FramedDirection(source)
     {
         referenceRobot = source.referenceRobot;
-        if(referenceRobot)
+
+        if (referenceRobot)
         {
             //ARMARX_WARNING_S << "Calling referenceRobot->ref() in cctor of LinkedPose";
             referenceRobot->ref();
         }
     }
 
-    LinkedDirection::LinkedDirection(const Eigen::Vector3f &v, const std::string &frame, const SharedRobotInterfacePrx &referenceRobot) :
+    LinkedDirection::LinkedDirection(const Eigen::Vector3f& v, const std::string& frame, const SharedRobotInterfacePrx& referenceRobot) :
         FramedDirection(v, frame, referenceRobot->getName())
     {
         referenceRobot->ref();
@@ -243,22 +251,25 @@ namespace armarx {
 
     LinkedDirection::~LinkedDirection()
     {
-        try{
-            if(referenceRobot)
+        try
+        {
+            if (referenceRobot)
             {
                 referenceRobot->unref();
             }
         }
-        catch(...)
+        catch (...)
         {
             handleExceptions();
         }
     }
 
-    void LinkedDirection::changeFrame(const std::string &newFrame, const Ice::Current &c)
+    void LinkedDirection::changeFrame(const std::string& newFrame, const Ice::Current& c)
     {
-        if(newFrame == frame)
+        if (newFrame == frame)
+        {
             return;
+        }
 
         VirtualRobot::RobotPtr sharedRobot(new RemoteRobot(referenceRobot));
 
@@ -269,35 +280,36 @@ namespace armarx {
         frame = frVec->frame;
     }
 
-    int LinkedDirection::readFromXML(const std::string &xmlData, const Ice::Current &c)
+    int LinkedDirection::readFromXML(const std::string& xmlData, const Ice::Current& c)
     {
         throw LocalException("LinkedDirection cannot be serialized! Serialize FramedDirection");
 
     }
 
-    std::string LinkedDirection::writeAsXML(const Ice::Current &c)
+    std::string LinkedDirection::writeAsXML(const Ice::Current& c)
     {
         throw LocalException("LinkedDirection cannot be deserialized! Serialize FramedDirection");
 
     }
 
-    void LinkedDirection::serialize(const ObjectSerializerBasePtr &serializer, const Ice::Current &) const
+    void LinkedDirection::serialize(const ObjectSerializerBasePtr& serializer, const Ice::Current&) const
     {
         throw LocalException("LinkedDirection cannot be serialized! Serialize FramedDirection");
     }
 
-    void LinkedDirection::deserialize(const ObjectSerializerBasePtr &serializer, const Ice::Current &)
+    void LinkedDirection::deserialize(const ObjectSerializerBasePtr& serializer, const Ice::Current&)
     {
         throw LocalException("LinkedDirection cannot be deserialized! Deserialize FramedDirection");
     }
 
     void LinkedDirection::ice_postUnmarshal()
     {
-        if(referenceRobot)
+        if (referenceRobot)
         {
-//            ARMARX_WARNING_S << "Calling referenceRobot->ref() in __read(IceInternal::BasicStream *__is, bool __rid) of LinkedPose";
+            //            ARMARX_WARNING_S << "Calling referenceRobot->ref() in __read(IceInternal::BasicStream *__is, bool __rid) of LinkedPose";
             referenceRobot->ref();
         }
+
         FramedDirection::ice_postUnmarshal();
     }
 
diff --git a/source/RobotAPI/libraries/core/LinkedPose.h b/source/RobotAPI/libraries/core/LinkedPose.h
index 58a2ef675ae520ef52703a7452eeaae49c284509..0ccf2b21043908ad6969065f4a53823adec6741a 100644
--- a/source/RobotAPI/libraries/core/LinkedPose.h
+++ b/source/RobotAPI/libraries/core/LinkedPose.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    RobotStateComponent::
  * @author     ( stefan dot ulbrich at kit dot edu)
  * @date
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -29,8 +28,8 @@
 #include <RobotAPI/interface/core/LinkedPoseBase.h>
 #include <RobotAPI/interface/core/RobotState.h>
 
-#include <Core/observers/AbstractObjectSerializer.h>
-#include <Core/observers/variant/Variant.h>
+#include <ArmarXCore/observers/AbstractObjectSerializer.h>
+#include <ArmarXCore/observers/variant/Variant.h>
 
 #include <Eigen/Core>
 #include <Eigen/Geometry>
@@ -55,18 +54,18 @@ namespace armarx
 
     /**
      * @class LinkedPose
-     * @ingroup Variants
+     * @ingroup VariantsGrp
      * @ingroup RobotAPI-FramedPose
      * @brief The LinkedPose class
      */
     class LinkedPose :
-            virtual public LinkedPoseBase,
-            virtual public FramedPose
+        virtual public LinkedPoseBase,
+        virtual public FramedPose
     {
     public:
         LinkedPose();
-        LinkedPose(const LinkedPose &other);
-        LinkedPose(const FramedPose &other, const SharedRobotInterfacePrx& referenceRobot);
+        LinkedPose(const LinkedPose& other);
+        LinkedPose(const FramedPose& other, const SharedRobotInterfacePrx& referenceRobot);
         LinkedPose(const Eigen::Matrix3f& m, const Eigen::Vector3f& v, const std::string& frame, const SharedRobotInterfacePrx& referenceRobot);
         LinkedPose(const Eigen::Matrix4f& m, const std::string& frame, const SharedRobotInterfacePrx& referenceRobot);
 
@@ -104,10 +103,10 @@ namespace armarx
              * @param xmlData Strinconst SharedRobotInterfacePrx& referenceRobotg with xml-data. NOT a file path!
              * @return ErrorCode, 1 on Success
              */
-        int readFromXML(const std::string &xmlData, const Ice::Current &c = ::Ice::Current());
-        std::string writeAsXML(const Ice::Current &c = ::Ice::Current());
+        int readFromXML(const std::string& xmlData, const Ice::Current& c = ::Ice::Current());
+        std::string writeAsXML(const Ice::Current& c = ::Ice::Current());
 
-        friend std::ostream &operator<<(std::ostream &stream, const LinkedPose& rhs)
+        friend std::ostream& operator<<(std::ostream& stream, const LinkedPose& rhs)
         {
             stream << "LinkedPose: " << std::endl << rhs.output() << std::endl;
             return stream;
@@ -125,13 +124,13 @@ namespace armarx
     /**
      * @class LinkedDirection is a direction vector (NOT a position vector) with an attached robotstate proxy
      * for frame changes.
-     * @ingroup Variants
+     * @ingroup VariantsGrp
      * @ingroup RobotAPI-FramedPose
      * @brief The LinkedDirection class
      */
     class LinkedDirection :
-            virtual public LinkedDirectionBase,
-            virtual public FramedDirection
+        virtual public LinkedDirectionBase,
+        virtual public FramedDirection
     {
     public:
         LinkedDirection();
@@ -140,7 +139,7 @@ namespace armarx
 
         virtual ~LinkedDirection();
 
-        void changeFrame(const std::string &newFrame, const Ice::Current &c = Ice::Current());
+        void changeFrame(const std::string& newFrame, const Ice::Current& c = Ice::Current());
 
         // inherited from VariantDataClass
         Ice::ObjectPtr ice_clone() const
@@ -171,10 +170,10 @@ namespace armarx
         }
 
 
-        int readFromXML(const std::string &xmlData, const Ice::Current &c = ::Ice::Current());
-        std::string writeAsXML(const Ice::Current &c = ::Ice::Current());
+        int readFromXML(const std::string& xmlData, const Ice::Current& c = ::Ice::Current());
+        std::string writeAsXML(const Ice::Current& c = ::Ice::Current());
 
-        friend std::ostream &operator<<(std::ostream &stream, const LinkedDirection& rhs)
+        friend std::ostream& operator<<(std::ostream& stream, const LinkedDirection& rhs)
         {
             stream << "LinkedDirection: " << std::endl << rhs.output() << std::endl;
             return stream;
diff --git a/source/RobotAPI/libraries/core/PIDController.cpp b/source/RobotAPI/libraries/core/PIDController.cpp
index c323138a775fd9a6c35380570a869809ff5c2aa9..efaf566195c99e83ea0c25d5629218d4c2a32a74 100644
--- a/source/RobotAPI/libraries/core/PIDController.cpp
+++ b/source/RobotAPI/libraries/core/PIDController.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    RobotAPI::core::PIDController
  * @author     Mirko Waechter ( mirko dot waechter at kit dot edu )
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -54,12 +53,14 @@ void PIDController::update(double measuredValue, double targetValue)
 {
     ScopedRecursiveLock lock(mutex);
     IceUtil::Time now = IceUtil::Time::now();
-    if(firstRun)
+
+    if (firstRun)
     {
         lastUpdateTime = IceUtil::Time::now();
     }
+
     double dt = (now - lastUpdateTime).toSecondsDouble();
-    update(dt,measuredValue,targetValue);
+    update(dt, measuredValue, targetValue);
     lastUpdateTime = now;
 }
 
@@ -70,17 +71,22 @@ void PIDController::update(double deltaSec, double measuredValue, double targetV
     target = targetValue;
 
     double error = target - processValue;
+
     //double dt = (now - lastUpdateTime).toSecondsDouble();
-//    ARMARX_INFO << deactivateSpam() << VAROUT(dt);
-    if(!firstRun)
+    //    ARMARX_INFO << deactivateSpam() << VAROUT(dt);
+    if (!firstRun)
     {
         integral += error * deltaSec;
-        if(deltaSec > 0.0)
+
+        if (deltaSec > 0.0)
+        {
             derivative = (error - previousError) / deltaSec;
+        }
     }
+
     firstRun = false;
     controlValue = Kp * error + Ki * integral + Kd * derivative;
-    ARMARX_DEBUG << deactivateSpam(0.5) << " error: " << error << " cV: " << (controlValue) <<  " i: " << (Ki*integral) << " d: " << (Kd * derivative) << " dt: " << deltaSec;
+    ARMARX_DEBUG << deactivateSpam(0.5) << " error: " << error << " cV: " << (controlValue) <<  " i: " << (Ki * integral) << " d: " << (Kd * derivative) << " dt: " << deltaSec;
 
     previousError = error;
     lastUpdateTime += IceUtil::Time::seconds(deltaSec);
@@ -112,38 +118,51 @@ void MultiDimPIDController::update(const double deltaSec, const Eigen::VectorXf&
     target = targetValue;
 
     double error = (target - processValue).norm();
+
     //double dt = (now - lastUpdateTime).toSecondsDouble();
-//    ARMARX_INFO << deactivateSpam() << VAROUT(dt);
-    if(!firstRun)
+    //    ARMARX_INFO << deactivateSpam() << VAROUT(dt);
+    if (!firstRun)
     {
         integral += error * deltaSec;
-        if(deltaSec > 0.0)
+
+        if (deltaSec > 0.0)
+        {
             derivative = (error - previousError) / deltaSec;
+        }
     }
+
     firstRun = false;
     Eigen::VectorXf direction = targetValue; // copy size
-    if((target - processValue).norm() > 0)
+
+    if ((target - processValue).norm() > 0)
+    {
         direction = (target - processValue).normalized();
+    }
     else
+    {
         direction.setZero();
+    }
+
     controlValue = direction * (Kp * error + Ki * integral + Kd * derivative);
-    ARMARX_DEBUG << deactivateSpam(0.5) << " error: " << error << " cV: " << (controlValue) <<  " i: " << (Ki*integral) << " d: " << (Kd * derivative) << " dt: " << deltaSec;
+    ARMARX_DEBUG << deactivateSpam(0.5) << " error: " << error << " cV: " << (controlValue) <<  " i: " << (Ki * integral) << " d: " << (Kd * derivative) << " dt: " << deltaSec;
 
     previousError = error;
     lastUpdateTime += IceUtil::Time::seconds(deltaSec);
 
 }
 
-void MultiDimPIDController::update(const Eigen::VectorXf &measuredValue, const Eigen::VectorXf &targetValue)
+void MultiDimPIDController::update(const Eigen::VectorXf& measuredValue, const Eigen::VectorXf& targetValue)
 {
     ScopedRecursiveLock lock(mutex);
     IceUtil::Time now = IceUtil::Time::now();
-    if(firstRun)
+
+    if (firstRun)
     {
         lastUpdateTime = IceUtil::Time::now();
     }
+
     double dt = (now - lastUpdateTime).toSecondsDouble();
-    update(dt,measuredValue,targetValue);
+    update(dt, measuredValue, targetValue);
     lastUpdateTime = now;
 }
 
@@ -159,7 +178,7 @@ void MultiDimPIDController::reset()
     previousError = 0;
     integral = 0;
     lastUpdateTime = IceUtil::Time::now();
-//    controlValue.setZero();
-//    processValue.setZero();
-//    target.setZero();
+    //    controlValue.setZero();
+    //    processValue.setZero();
+    //    target.setZero();
 }
diff --git a/source/RobotAPI/libraries/core/PIDController.h b/source/RobotAPI/libraries/core/PIDController.h
index d7e411e4400c6d2fb4b3055c7fcaa72e3963892c..624a4709536db9cde49a501209f7b39024c8caa1 100644
--- a/source/RobotAPI/libraries/core/PIDController.h
+++ b/source/RobotAPI/libraries/core/PIDController.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,21 +16,21 @@
  * @package    RobotAPI::core::PIDController
  * @author     Mirko Waechter ( mirko dot waechter at kit dot edu )
  * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 #ifndef _ARMARX_COMPONENT_RobotAPI_PIDController_H
 #define _ARMARX_COMPONENT_RobotAPI_PIDController_H
 
-#include <Core/core/logging/Logging.h>
+#include <ArmarXCore/core/logging/Logging.h>
 #include <Eigen/Core>
 
 namespace armarx
 {
 
     class PIDController :
-            public Logging
+        public Logging
     {
     public:
         PIDController(float Kp, float Ki, float Kd);
@@ -40,7 +39,7 @@ namespace armarx
         double getControlValue() const;
 
         void reset();
-//    protected:
+        //    protected:
         float Kp, Ki, Kd;
         double integral;
         double derivative;
@@ -55,16 +54,16 @@ namespace armarx
     typedef boost::shared_ptr<PIDController> PIDControllerPtr;
 
     class MultiDimPIDController :
-            public Logging
+        public Logging
     {
     public:
         MultiDimPIDController(float Kp, float Ki, float Kd);
-        void update(const double deltaSec, const Eigen::VectorXf &measuredValue, const Eigen::VectorXf &targetValue);
-        void update(const Eigen::VectorXf &measuredValue, const Eigen::VectorXf &targetValue);
-        const Eigen::VectorXf &getControlValue() const;
+        void update(const double deltaSec, const Eigen::VectorXf& measuredValue, const Eigen::VectorXf& targetValue);
+        void update(const Eigen::VectorXf& measuredValue, const Eigen::VectorXf& targetValue);
+        const Eigen::VectorXf& getControlValue() const;
 
         void reset();
-//    protected:
+        //    protected:
         float Kp, Ki, Kd;
         double integral;
         double derivative;
diff --git a/source/RobotAPI/libraries/core/Pose.cpp b/source/RobotAPI/libraries/core/Pose.cpp
index cc4ba42ef370383cea0a30867de28ff9f3c6a7e0..5ee4cbed2688553a928cd4191b84286935df9d3d 100644
--- a/source/RobotAPI/libraries/core/Pose.cpp
+++ b/source/RobotAPI/libraries/core/Pose.cpp
@@ -23,7 +23,7 @@ namespace armarx
         y = 0;
     }
 
-    Vector2::Vector2(const Vector2f & v)
+    Vector2::Vector2(const Vector2f& v)
     {
         x = v(0);
         y = v(1);
@@ -38,7 +38,7 @@ namespace armarx
     Vector2f Vector2::toEigen() const
     {
         Vector2f v;
-        v << this->x,this->y;
+        v << this->x, this->y;
         return v;
     }
 
@@ -48,14 +48,14 @@ namespace armarx
         y = vec[1];
     }
 
-    string Vector2::output(const Ice::Current &c) const
+    string Vector2::output(const Ice::Current& c) const
     {
         std::stringstream s;
         s << toEigen();
         return s.str();
     }
 
-    int Vector2::readFromXML(const string &xmlData, const Ice::Current &c)
+    int Vector2::readFromXML(const string& xmlData, const Ice::Current& c)
     {
         boost::property_tree::ptree pt = Variant::GetPropertyTree(xmlData);
 
@@ -64,7 +64,7 @@ namespace armarx
         return 1;
     }
 
-    string Vector2::writeAsXML(const Ice::Current &)
+    string Vector2::writeAsXML(const Ice::Current&)
     {
         using namespace boost::property_tree;
         ptree pt;
@@ -99,18 +99,18 @@ namespace armarx
         z = 0;
     }
 
-    Vector3::Vector3(const Vector3f & v)
+    Vector3::Vector3(const Vector3f& v)
     {
         x = v(0);
         y = v(1);
         z = v(2);
     }
 
-    Vector3::Vector3(const Matrix4f & m)
+    Vector3::Vector3(const Matrix4f& m)
     {
-        x = m(0,3);
-        y = m(1,3);
-        z = m(2,3);
+        x = m(0, 3);
+        y = m(1, 3);
+        z = m(2, 3);
     }
 
     Vector3::Vector3(::Ice::Float x, ::Ice::Float y, ::Ice::Float z)
@@ -123,7 +123,7 @@ namespace armarx
     Vector3f Vector3::toEigen() const
     {
         Vector3f v;
-        v << this->x,this->y,this->z;
+        v << this->x, this->y, this->z;
         return v;
     }
 
@@ -134,14 +134,14 @@ namespace armarx
         z = vec[2];
     }
 
-    string Vector3::output(const Ice::Current &c) const
+    string Vector3::output(const Ice::Current& c) const
     {
         std::stringstream s;
         s << toEigen();
         return s.str();
     }
 
-    int Vector3::readFromXML(const string &xmlData, const Ice::Current &c)
+    int Vector3::readFromXML(const string& xmlData, const Ice::Current& c)
     {
         boost::property_tree::ptree pt = Variant::GetPropertyTree(xmlData);
 
@@ -151,7 +151,7 @@ namespace armarx
         return 1;
     }
 
-    string Vector3::writeAsXML(const Ice::Current &)
+    string Vector3::writeAsXML(const Ice::Current&)
     {
         using namespace boost::property_tree;
         ptree pt;
@@ -187,18 +187,18 @@ namespace armarx
     {
     }
 
-    Quaternion::Quaternion(const Matrix4f &m4)
+    Quaternion::Quaternion(const Matrix4f& m4)
     {
-        Matrix3f m3=m4.block<3,3>(0,0);
+        Matrix3f m3 = m4.block<3, 3>(0, 0);
         this->init(m3);
     }
 
-    Quaternion::Quaternion(const Matrix3f &m3)
+    Quaternion::Quaternion(const Matrix3f& m3)
     {
         this->init(m3);
     }
 
-    Quaternion::Quaternion(const Eigen::Quaternionf &q)
+    Quaternion::Quaternion(const Eigen::Quaternionf& q)
     {
         this->init(q);
     }
@@ -215,10 +215,10 @@ namespace armarx
     {
         Matrix3f rot;
         rot = Quaternionf(
-                    this->qw,
-                    this->qx,
-                    this->qy,
-                    this->qz);
+                  this->qw,
+                  this->qx,
+                  this->qy,
+                  this->qz);
         return rot;
     }
 
@@ -227,52 +227,54 @@ namespace armarx
         return Quaternionf(this->qw, this->qx, this->qy, this->qz);
     }
 
-    void Quaternion::init(const Matrix3f &m3)
+    void Quaternion::init(const Matrix3f& m3)
     {
         Quaternionf q;
         q = m3;
         init(q);
     }
 
-    void Quaternion::init(const Eigen::Quaternionf &q)
+    void Quaternion::init(const Eigen::Quaternionf& q)
     {
-        this->qw=q.w();
-        this->qx=q.x();
-        this->qy=q.y();
-        this->qz=q.z();
+        this->qw = q.w();
+        this->qx = q.x();
+        this->qy = q.y();
+        this->qz = q.z();
     }
 
-    Matrix3f Quaternion::slerp(float alpha, const Eigen::Matrix3f &m)
+    Matrix3f Quaternion::slerp(float alpha, const Eigen::Matrix3f& m)
     {
-        return Quaternion::slerp(alpha,this->toEigen(),m);
+        return Quaternion::slerp(alpha, this->toEigen(), m);
     }
 
-    Matrix3f Quaternion::slerp(float alpha, const Eigen::Matrix3f &m1, const Eigen::Matrix3f &m2)
+    Matrix3f Quaternion::slerp(float alpha, const Eigen::Matrix3f& m1, const Eigen::Matrix3f& m2)
     {
         Matrix3f result;
-        Quaternionf q1,q2;
+        Quaternionf q1, q2;
         q1 = m1;
-        q2=m2;
-        result= q1.slerp(alpha,q2);
+        q2 = m2;
+        result = q1.slerp(alpha, q2);
         return result;
     }
 
-    string Quaternion::output(const Ice::Current &c) const
+    string Quaternion::output(const Ice::Current& c) const
     {
         std::stringstream s;
         s << toEigen();
         return s.str();
     }
 
-    int Quaternion::readFromXML(const string &xmlData, const Ice::Current &c)
+    int Quaternion::readFromXML(const string& xmlData, const Ice::Current& c)
     {
         boost::property_tree::ptree pt = Variant::GetPropertyTree(xmlData);
 
         using namespace Eigen;
 
         Quaternionf q;
-        if(pt.get_optional<float>("angle"))
-        {// AxisAngle-Notation
+
+        if (pt.get_optional<float>("angle"))
+        {
+            // AxisAngle-Notation
             float angle = pt.get<float>("angle");
 
             Vector3f axis;
@@ -296,7 +298,7 @@ namespace armarx
         return 1;
     }
 
-    string Quaternion::writeAsXML(const Ice::Current &)
+    string Quaternion::writeAsXML(const Ice::Current&)
     {
         using namespace boost::property_tree;
         ptree pt;
@@ -330,7 +332,7 @@ namespace armarx
         qw = obj->getFloat("qw");
     }
 
-    Pose::Pose(const Eigen::Matrix3f &m, const Eigen::Vector3f &v)
+    Pose::Pose(const Eigen::Matrix3f& m, const Eigen::Vector3f& v)
     {
         this->orientation = new Quaternion(m);
         this->position = new Vector3(v);
@@ -351,7 +353,7 @@ namespace armarx
         init();
     }
 
-    Pose::Pose(const Pose &source) :
+    Pose::Pose(const Pose& source) :
         IceUtil::Shared(source),
         PoseBase(source)
     {
@@ -360,14 +362,14 @@ namespace armarx
         init();
     }
 
-    Pose::Pose(const Matrix4f &m)
+    Pose::Pose(const Matrix4f& m)
     {
         this->orientation = new Quaternion(m);
         this->position = new Vector3(m);
         init();
     }
 
-    void Pose::operator=(const Matrix4f &matrix)
+    void Pose::operator=(const Matrix4f& matrix)
     {
         this->orientation = new Quaternion(matrix);
         this->position = new Vector3(matrix);
@@ -379,19 +381,19 @@ namespace armarx
         Matrix4f m = Matrix4f::Identity();
         ARMARX_CHECK_EXPRESSION(c_orientation);
         ARMARX_CHECK_EXPRESSION(c_position);
-        m.block<3,3>(0,0) = c_orientation->toEigen();
-        m.block<3,1>(0,3) = c_position->toEigen();
+        m.block<3, 3>(0, 0) = c_orientation->toEigen();
+        m.block<3, 1>(0, 3) = c_position->toEigen();
         return m;
     }
 
-    string Pose::output(const Ice::Current &c) const
+    string Pose::output(const Ice::Current& c) const
     {
         std::stringstream s;
         s << toEigen();
         return s.str();
     }
 
-    int Pose::readFromXML(const string &xmlData, const Ice::Current &c)
+    int Pose::readFromXML(const string& xmlData, const Ice::Current& c)
     {
         position->readFromXML(xmlData);
         orientation->readFromXML(xmlData);
@@ -399,13 +401,13 @@ namespace armarx
         return 1;
     }
 
-    string Pose::writeAsXML(const Ice::Current &)
+    string Pose::writeAsXML(const Ice::Current&)
     {
         using namespace boost::property_tree;
         std::stringstream stream;
         stream <<
-                  position->writeAsXML() <<
-                  orientation->writeAsXML();
+               position->writeAsXML() <<
+               orientation->writeAsXML();
         return stream.str();
     }
 
diff --git a/source/RobotAPI/libraries/core/Pose.h b/source/RobotAPI/libraries/core/Pose.h
index 727cac0e2e328f3e04d89030c5c6cbb763655bd2..b5566e1d13eaedd204965369a7423348cfaf7af4 100644
--- a/source/RobotAPI/libraries/core/Pose.h
+++ b/source/RobotAPI/libraries/core/Pose.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    RobotAPI::Core
  * @author     ( stefan dot ulbrich at kit dot edu)
  * @date
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -28,9 +27,9 @@
 #include <Eigen/Core>
 #include <Eigen/Geometry>
 
-#include <Core/observers/variant/Variant.h>
-#include <Core/observers/AbstractObjectSerializer.h>
-#include <Core/core/exceptions/local/ExpressionException.h>
+#include <ArmarXCore/observers/variant/Variant.h>
+#include <ArmarXCore/observers/AbstractObjectSerializer.h>
+#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 #include <RobotAPI/interface/core/PoseBase.h>
 
 
@@ -46,11 +45,15 @@ namespace armarx
         const VariantTypeId Pose = Variant::addTypeName("::armarx::PoseBase");
     }
 
+    /**
+     * @brief The Vector2 class
+     * @ingroup VariantsGrp
+     */
     class Vector2 : virtual public Vector2Base
     {
     public:
         Vector2();
-        Vector2(const Eigen::Vector2f &);
+        Vector2(const Eigen::Vector2f&);
         Vector2(::Ice::Float x, ::Ice::Float y);
 
         void operator=(const Eigen::Vector2f& ves);
@@ -87,10 +90,10 @@ namespace armarx
              * @param xmlData String with xml-data. NOT a file path!
              * @return ErrorCode, 1 on Success
              */
-        int readFromXML(const std::string &xmlData, const Ice::Current &c = ::Ice::Current());
-        std::string writeAsXML(const Ice::Current &c = ::Ice::Current());
+        int readFromXML(const std::string& xmlData, const Ice::Current& c = ::Ice::Current());
+        std::string writeAsXML(const Ice::Current& c = ::Ice::Current());
 
-        friend std::ostream &operator<<(std::ostream &stream, const Vector2& rhs)
+        friend std::ostream& operator<<(std::ostream& stream, const Vector2& rhs)
         {
             stream << "Vector2: " << std::endl << rhs.output() << std::endl;
             return stream;
@@ -106,17 +109,17 @@ namespace armarx
 
     /**
      * @class Vector3
-     * @ingroup Variants
+     * @ingroup VariantsGrp
      * @ingroup RobotAPI-FramedPose
      * @brief The Vector3 class
      */
     class Vector3 :
-            virtual public Vector3Base
+        virtual public Vector3Base
     {
     public:
         Vector3();
-        Vector3(const Eigen::Vector3f &);
-        Vector3(const Eigen::Matrix4f &);
+        Vector3(const Eigen::Vector3f&);
+        Vector3(const Eigen::Matrix4f&);
         Vector3(::Ice::Float x, ::Ice::Float y, ::Ice::Float z);
 
         void operator=(const Eigen::Vector3f& vec);
@@ -154,10 +157,10 @@ namespace armarx
              * @param xmlData String with xml-data. NOT a file path!
              * @return ErrorCode, 1 on Success
              */
-        int readFromXML(const std::string &xmlData, const Ice::Current &c = ::Ice::Current());
-        std::string writeAsXML(const Ice::Current &c = ::Ice::Current());
+        int readFromXML(const std::string& xmlData, const Ice::Current& c = ::Ice::Current());
+        std::string writeAsXML(const Ice::Current& c = ::Ice::Current());
 
-        friend std::ostream &operator<<(std::ostream &stream, const Vector3& rhs)
+        friend std::ostream& operator<<(std::ostream& stream, const Vector3& rhs)
         {
             stream << "Vector3: " << std::endl << rhs.output() << std::endl;
             return stream;
@@ -173,25 +176,25 @@ namespace armarx
 
     /**
      * @class Quaternion
-     * @ingroup Variants
+     * @ingroup VariantsGrp
      * @ingroup RobotAPI-FramedPose
      * @brief The Quaternion class
      */
     class Quaternion :
-            virtual public QuaternionBase
+        virtual public QuaternionBase
     {
     public:
         Quaternion();
-        Quaternion(const Eigen::Matrix4f &);
-        Quaternion(const Eigen::Matrix3f &);
-        Quaternion(const Eigen::Quaternionf &);
+        Quaternion(const Eigen::Matrix4f&);
+        Quaternion(const Eigen::Matrix3f&);
+        Quaternion(const Eigen::Quaternionf&);
         Quaternion(::Ice::Float qw, ::Ice::Float qx, ::Ice::Float qy, ::Ice::Float qz);
 
         Eigen::Matrix3f toEigen() const;
         Eigen::Quaternionf toEigenQuaternion() const;
-        Eigen::Matrix3f slerp(float, const Eigen::Matrix3f &);
+        Eigen::Matrix3f slerp(float, const Eigen::Matrix3f&);
 
-        static Eigen::Matrix3f slerp(float, const Eigen::Matrix3f &, const Eigen::Matrix3f &);
+        static Eigen::Matrix3f slerp(float, const Eigen::Matrix3f&, const Eigen::Matrix3f&);
 
         // inherited from VariantDataClass
         Ice::ObjectPtr ice_clone() const
@@ -235,10 +238,10 @@ namespace armarx
              * @param c
              * @return ErrorCode, 1 on Success
              */
-        int readFromXML(const std::string &xmlData, const Ice::Current &c = ::Ice::Current());
-        std::string writeAsXML(const Ice::Current &c = ::Ice::Current());
+        int readFromXML(const std::string& xmlData, const Ice::Current& c = ::Ice::Current());
+        std::string writeAsXML(const Ice::Current& c = ::Ice::Current());
 
-        friend std::ostream &operator<<(std::ostream &stream, const Quaternion& rhs)
+        friend std::ostream& operator<<(std::ostream& stream, const Quaternion& rhs)
         {
             stream << "Quaternion: " << std::endl << rhs.output() << std::endl;
             return stream;
@@ -249,8 +252,8 @@ namespace armarx
         virtual void deserialize(const armarx::ObjectSerializerBasePtr& serializer, const ::Ice::Current& = ::Ice::Current());
 
     private:
-        void init(const Eigen::Matrix3f &);
-        void init(const Eigen::Quaternionf &);
+        void init(const Eigen::Matrix3f&);
+        void init(const Eigen::Quaternionf&);
     };
 
     typedef IceInternal::Handle<Quaternion> QuaternionPtr;
@@ -258,21 +261,21 @@ namespace armarx
 
     /**
      * @class Pose
-     * @ingroup Variants
+     * @ingroup VariantsGrp
      * @ingroup RobotAPI-FramedPose
      * @brief The Pose class
      */
     class Pose :
-            virtual public PoseBase
+        virtual public PoseBase
     {
     public:
         Pose();
-        Pose(const Pose&source);
-        Pose(const Eigen::Matrix4f &);
-        Pose(const Eigen::Matrix3f &, const Eigen::Vector3f &);
+        Pose(const Pose& source);
+        Pose(const Eigen::Matrix4f&);
+        Pose(const Eigen::Matrix3f&, const Eigen::Vector3f&);
         Pose(const armarx::Vector3BasePtr pos, const armarx::QuaternionBasePtr ori);
 
-        void operator=(const Eigen::Matrix4f &matrix);
+        void operator=(const Eigen::Matrix4f& matrix);
         virtual Eigen::Matrix4f toEigen() const;
 
         // inherited from VariantDataClass
@@ -313,10 +316,10 @@ namespace armarx
              * @return ErrorCode, 1 on Success
              * @see Quaternion::readFromXml() for AxisAngle-Notation
              */
-        int readFromXML(const std::string &xmlData, const Ice::Current &c = ::Ice::Current());
-        std::string writeAsXML(const Ice::Current &c = ::Ice::Current());
+        int readFromXML(const std::string& xmlData, const Ice::Current& c = ::Ice::Current());
+        std::string writeAsXML(const Ice::Current& c = ::Ice::Current());
 
-        friend std::ostream &operator<<(std::ostream &stream, const Pose& rhs)
+        friend std::ostream& operator<<(std::ostream& stream, const Pose& rhs)
         {
             stream << "Pose: " << std::endl << rhs.output() << std::endl;
             return stream;
diff --git a/source/RobotAPI/libraries/core/RobotAPIObjectFactories.cpp b/source/RobotAPI/libraries/core/RobotAPIObjectFactories.cpp
index 2de2300b9c11e3685dcd85f27dffe33422109fd7..3ccdd28bc41ecffe6fc6a3e284fcecdeaad19535 100644
--- a/source/RobotAPI/libraries/core/RobotAPIObjectFactories.cpp
+++ b/source/RobotAPI/libraries/core/RobotAPIObjectFactories.cpp
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::
 * @author     Mirko Waechter ( mirko.waechter at kit dot edu)
 * @date       2014
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
diff --git a/source/RobotAPI/libraries/core/RobotAPIObjectFactories.h b/source/RobotAPI/libraries/core/RobotAPIObjectFactories.h
index f4ded6efc6da2fe1b827fac66fe5d645fefa4fd2..199bfb0d05e6ab2b051c843ba7b999a8b3e05530 100644
--- a/source/RobotAPI/libraries/core/RobotAPIObjectFactories.h
+++ b/source/RobotAPI/libraries/core/RobotAPIObjectFactories.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -24,7 +23,7 @@
 #ifndef _ARMARX_ROBOTAPI_OBJECT_FACTORIES_H
 #define _ARMARX_ROBOTAPI_OBJECT_FACTORIES_H
 
-#include <Core/core/system/FactoryCollectionBase.h>
+#include <ArmarXCore/core/system/FactoryCollectionBase.h>
 #include <RobotAPI/interface/core/PoseBase.h>
 #include <RobotAPI/interface/core/RobotState.h>
 #include <RobotAPI/libraries/core/FramedPose.h>
diff --git a/source/RobotAPI/libraries/core/RobotStatechartContext.cpp b/source/RobotAPI/libraries/core/RobotStatechartContext.cpp
index 9cfc7e123bfeb4d8808e66a94364e28d1f546e0a..7713be5cda5ee55e4f0a6153efe54d3f66116950 100644
--- a/source/RobotAPI/libraries/core/RobotStatechartContext.cpp
+++ b/source/RobotAPI/libraries/core/RobotStatechartContext.cpp
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    Armar4::api
 * @author     Nikolaus Vahrenkamp
 * @date       2012 Nikolaus Vahrenkamp
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -25,9 +24,9 @@
 
 #include <RobotAPI/libraries/core/remoterobot/RemoteRobot.h>
 
-#include <Core/core/Component.h>
-#include <Core/core/system/ImportExportComponent.h>
-#include <Core/statechart/Statechart.h>
+#include <ArmarXCore/core/Component.h>
+#include <ArmarXCore/core/system/ImportExportComponent.h>
+#include <ArmarXCore/statechart/Statechart.h>
 
 namespace armarx
 {
@@ -36,7 +35,7 @@ namespace armarx
     // ****************************************************************
     void RobotStatechartContext::onInitStatechartContext()
     {
-//        StatechartContext::onInitStatechart();
+        //        StatechartContext::onInitStatechart();
         ARMARX_LOG << eINFO << "Init RobotStatechartContext" << flush;
 
         kinematicUnitObserverName = getProperty<std::string>("KinematicUnitObserverName").getValue();
@@ -45,12 +44,13 @@ namespace armarx
         usingProxy("RobotStateComponent");
         usingProxy(kinematicUnitObserverName);
 
-        if(!getProperty<std::string>("HandUnits").getValue().empty())
+        if (!getProperty<std::string>("HandUnits").getValue().empty())
         {
             std::string handUnitsProp = getProperty<std::string>("HandUnits").getValue();
             std::vector<std::string> handUnitList;
             boost::split(handUnitList, handUnitsProp, boost::is_any_of(","));
-            for(size_t i = 0; i < handUnitList.size(); i++)
+
+            for (size_t i = 0; i < handUnitList.size(); i++)
             {
                 boost::algorithm::trim(handUnitList.at(i));
                 usingProxy(handUnitList.at(i));
@@ -60,14 +60,17 @@ namespace armarx
         // headIKUnit
         headIKUnitName = getProperty<std::string>("HeadIKUnitName").getValue();
         headIKKinematicChainName = getProperty<std::string>("HeadIKKinematicChainName").getValue();
+
         if (!headIKUnitName.empty())
+        {
             usingProxy(headIKUnitName);
+        }
     }
 
 
     void RobotStatechartContext::onConnectStatechartContext()
     {
-//        StatechartContext::onConnectStatechart();
+        //        StatechartContext::onConnectStatechart();
         ARMARX_LOG << eINFO << "Starting RobotStatechartContext" << flush;
 
         // retrieve proxies
@@ -86,12 +89,13 @@ namespace armarx
         }
 
 
-        if( !getProperty<std::string>("HandUnits").getValue().empty())
+        if (!getProperty<std::string>("HandUnits").getValue().empty())
         {
             std::string handUnitsProp = getProperty<std::string>("HandUnits").getValue();
             std::vector<std::string> handUnitList;
             boost::split(handUnitList, handUnitsProp, boost::is_any_of(","));
-            for(size_t i = 0; i < handUnitList.size(); i++)
+
+            for (size_t i = 0; i < handUnitList.size(); i++)
             {
                 boost::algorithm::trim(handUnitList.at(i));
                 HandUnitInterfacePrx handPrx = getProxy<HandUnitInterfacePrx>(handUnitList.at(i));
@@ -99,6 +103,7 @@ namespace armarx
                 ARMARX_LOG << eINFO << "Fetched handUnit proxy " << handUnitList.at(i) << ": " << handPrx << flush;
             }
         }
+
         // initialize remote robot
         remoteRobot.reset(new RemoteRobot(robotStateComponent->getSynchronizedRobot()));
         ARMARX_LOG << eINFO << "Created remote robot" << flush;
@@ -110,27 +115,30 @@ namespace armarx
                                           getConfigIdentifier()));
     }
 
-    HandUnitInterfacePrx RobotStatechartContext::getHandUnit(const std::string &handUnitName)
+    HandUnitInterfacePrx RobotStatechartContext::getHandUnit(const std::string& handUnitName)
     {
-        if (handUnits.find(handUnitName)!=handUnits.end())
+        if (handUnits.find(handUnitName) != handUnits.end())
         {
             ARMARX_LOG << eINFO << "Found proxy of hand unit with name  " << handUnitName << flush;
             return handUnits[handUnitName];
         }
+
         ARMARX_LOG << eINFO << "Do not know proxy of hand unit with name  " << handUnitName << flush;
         std::map<std::string, HandUnitInterfacePrx>::iterator it = handUnits.begin();
-        while (it!=handUnits.end())
+
+        while (it != handUnits.end())
         {
             ARMARX_LOG << eINFO << "************ Known hand units: " << it->first << ":" << it->second << flush;
             it++;
         }
+
         return HandUnitInterfacePrx();
     }
 
-   /* const VirtualRobot::RobotPtr armarx::Armar4Context::getRobot()
-    {
-        return remoteRobot;
-    }*/
+    /* const VirtualRobot::RobotPtr armarx::Armar4Context::getRobot()
+     {
+         return remoteRobot;
+     }*/
 
 }
 
diff --git a/source/RobotAPI/libraries/core/RobotStatechartContext.h b/source/RobotAPI/libraries/core/RobotStatechartContext.h
index 8a817dcb30101275236fdc49e4aa8ef3163f47df..81cbdf2529b1d6ee3c5ef7e3c5acb0240c855c38 100644
--- a/source/RobotAPI/libraries/core/RobotStatechartContext.h
+++ b/source/RobotAPI/libraries/core/RobotStatechartContext.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    Armar4::api
 * @author     Nikolaus Vahrenkamp
 * @date       2012 Nikolaus Vahrenkamp
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -32,9 +31,9 @@
 #include <RobotAPI/interface/units/HeadIKUnit.h>
 #include <RobotAPI/interface/observers/KinematicUnitObserverInterface.h>
 
-#include <Core/core/Component.h>
-#include <Core/core/system/ImportExportComponent.h>
-#include <Core/statechart/StatechartContext.h>
+#include <ArmarXCore/core/Component.h>
+#include <ArmarXCore/core/system/ImportExportComponent.h>
+#include <ArmarXCore/statechart/StatechartContext.h>
 
 #include <IceUtil/Time.h>
 
@@ -68,13 +67,16 @@ namespace armarx
     {
     public:
         // inherited from Component
-        virtual std::string getDefaultName() { return "RobotStatechartContext"; }
+        virtual std::string getDefaultName()
+        {
+            return "RobotStatechartContext";
+        }
         virtual void onInitStatechartContext();
         virtual void onConnectStatechartContext();
 
         // todo:read access should only be allowed via const getters ?!
         //const VirtualRobot::RobotPtr getRobot();
-    //private:
+        //private:
 
 
         /**
@@ -82,9 +84,12 @@ namespace armarx
          */
         virtual PropertyDefinitionsPtr createPropertyDefinitions();
 
-        std::string getKinematicUnitObserverName() { return kinematicUnitObserverName; }
+        std::string getKinematicUnitObserverName()
+        {
+            return kinematicUnitObserverName;
+        }
 
-        HandUnitInterfacePrx getHandUnit(const std::string &handUnitName);
+        HandUnitInterfacePrx getHandUnit(const std::string& handUnitName);
 
         //! Prx for the RobotState
         RobotStateComponentInterfacePrx robotStateComponent;
@@ -100,7 +105,7 @@ namespace armarx
     private:
         std::string kinematicUnitObserverName;
         std::string headIKUnitName;
-     };
+    };
 }
 
 #endif
diff --git a/source/RobotAPI/libraries/core/checks/ConditionCheckEqualsPose.h b/source/RobotAPI/libraries/core/checks/ConditionCheckEqualsPose.h
index fec76fafd8aff7ac61532ba3eb04f3f116989111..30e6279ff01253fb967b8b8749f1f5a9141257ad 100644
--- a/source/RobotAPI/libraries/core/checks/ConditionCheckEqualsPose.h
+++ b/source/RobotAPI/libraries/core/checks/ConditionCheckEqualsPose.h
@@ -1,9 +1,9 @@
 #ifndef _ARMARX_ROBOTAPI_CONDITIONCHECKEQUALSPOSE_H
 #define _ARMARX_ROBOTAPI_CONDITIONCHECKEQUALSPOSE_H
 
-#include <Core/core/system/ImportExport.h>
-#include <Core/observers/ConditionCheck.h>
-#include <Core/core/FramedPose.h>
+#include <ArmarXCore/core/system/ImportExport.h>
+#include <ArmarXCore/observers/ConditionCheck.h>
+#include <ArmarXCore/core/FramedPose.h>
 
 namespace armarx
 {
@@ -15,20 +15,20 @@ namespace armarx
         {
             setNumberParameters(1);
             addSupportedType(VariantType::FramedPosition, createParameterTypeList(1, VariantType::FramedPosition);
-            addSupportedType(VariantType::FramedOrientation, createParameterTypeList(1, VariantType::FramedOrientation);
-            addSupportedType(VariantType::Vector3, createParameterTypeList(1, VariantType::Vector3);
-            addSupportedType(VariantType::Quaternion, createParameterTypeList(1, VariantType::Quaternion);
-            addSupportedType(VariantType::Pose, createParameterTypeList(1, VariantType::Pose);
+                             addSupportedType(VariantType::FramedOrientation, createParameterTypeList(1, VariantType::FramedOrientation);
+                                              addSupportedType(VariantType::Vector3, createParameterTypeList(1, VariantType::Vector3);
+                                                      addSupportedType(VariantType::Quaternion, createParameterTypeList(1, VariantType::Quaternion);
+                                                              addSupportedType(VariantType::Pose, createParameterTypeList(1, VariantType::Pose);
         }
 
-        ConditionCheck* clone()
+                                                          ConditionCheck* clone()
         {
             return new ConditionCheckEqualsPose(*this);
         }
 
-        bool evaluate(const StringVariantMap &dataFields)
+        bool evaluate(const StringVariantMap& dataFields)
         {
-            if(dataFields.size() != 1)
+            if (dataFields.size() != 1)
             {
                 printf("Size of dataFields: %d\n", (int)dataFields.size());
                 throw InvalidConditionException("Wrong number of datafields for condition equals ");
@@ -37,36 +37,36 @@ namespace armarx
             Variant& value = dataFields.begin()->second;
             VariantTypeId type = value.getType();
 
-            if(type == VariantType::Vector3)
-                return (sqrt(((value.x-getParameter(0).getClass<Vector3>().x)*(value.x-getParameter(0).getClass<Vector3>().x))+
-                             ((value.y-getParameter(0).getClass<Vector3>().y)*(value.y-getParameter(0).getClass<Vector3>().y))+
-                             ((value.z-getParameter(0).getClass<Vector3>().x)*(value.x-getParameter(0).getClass<Vector3>().z))) == 0);
+            if (type == VariantType::Vector3)
+                return (sqrt(((value.x - getParameter(0).getClass<Vector3>().x) * (value.x - getParameter(0).getClass<Vector3>().x)) +
+                             ((value.y - getParameter(0).getClass<Vector3>().y) * (value.y - getParameter(0).getClass<Vector3>().y)) +
+                             ((value.z - getParameter(0).getClass<Vector3>().x) * (value.x - getParameter(0).getClass<Vector3>().z))) == 0);
 
-            if(type == VariantType::FramedPosition)
-                return (sqrt(((value.x-getParameter(0).getClass<FramedPosition>().x)*(value.x-getParameter(0).getClass<FramedPosition>().x))+
-                             ((value.y-getParameter(0).getClass<FramedPosition>().y)*(value.y-getParameter(0).getClass<FramedPosition>().y))+
-                             ((value.z-getParameter(0).getClass<FramedPosition>().x)*(value.x-getParameter(0).getClass<FramedPosition>().z))) == 0);
+            if (type == VariantType::FramedPosition)
+                return (sqrt(((value.x - getParameter(0).getClass<FramedPosition>().x) * (value.x - getParameter(0).getClass<FramedPosition>().x)) +
+                             ((value.y - getParameter(0).getClass<FramedPosition>().y) * (value.y - getParameter(0).getClass<FramedPosition>().y)) +
+                             ((value.z - getParameter(0).getClass<FramedPosition>().x) * (value.x - getParameter(0).getClass<FramedPosition>().z))) == 0);
 
-            if(type == VariantType::Quaternion)
-                return (sqrt(((value.qw-getParameter(0).getClass<Quaternion>().qw)*(value.qw-getParameter(0).getClass<Quaternion>().qw))+
-                             ((value.qx-getParameter(0).getClass<Quaternion>().qx)*(value.qx-getParameter(0).getClass<Quaternion>().qx))+
-                             ((value.qy-getParameter(0).getClass<Quaternion>().qy)*(value.qy-getParameter(0).getClass<Quaternion>().qy))+
-                             ((value.qz-getParameter(0).getClass<Quaternion>().qx)*(value.qx-getParameter(0).getClass<Quaternion>().qz))) == 0);
+            if (type == VariantType::Quaternion)
+                return (sqrt(((value.qw - getParameter(0).getClass<Quaternion>().qw) * (value.qw - getParameter(0).getClass<Quaternion>().qw)) +
+                             ((value.qx - getParameter(0).getClass<Quaternion>().qx) * (value.qx - getParameter(0).getClass<Quaternion>().qx)) +
+                             ((value.qy - getParameter(0).getClass<Quaternion>().qy) * (value.qy - getParameter(0).getClass<Quaternion>().qy)) +
+                             ((value.qz - getParameter(0).getClass<Quaternion>().qx) * (value.qx - getParameter(0).getClass<Quaternion>().qz))) == 0);
 
-            if(type == VariantType::FramedOrientation)
-                return (sqrt(((value.qw-getParameter(0).getClass<FramedOrientation>().qw)*(value.qw-getParameter(0).getClass<FramedOrientation>().qw))+
-                             ((value.qx-getParameter(0).getClass<FramedOrientation>().qx)*(value.qx-getParameter(0).getClass<FramedOrientation>().qx))+
-                             ((value.qy-getParameter(0).getClass<FramedOrientation>().qy)*(value.qy-getParameter(0).getClass<FramedOrientation>().qy))+
-                             ((value.qz-getParameter(0).getClass<FramedOrientation>().qx)*(value.qx-getParameter(0).getClass<FramedOrientation>().qz))) == 0);
+            if (type == VariantType::FramedOrientation)
+                return (sqrt(((value.qw - getParameter(0).getClass<FramedOrientation>().qw) * (value.qw - getParameter(0).getClass<FramedOrientation>().qw)) +
+                             ((value.qx - getParameter(0).getClass<FramedOrientation>().qx) * (value.qx - getParameter(0).getClass<FramedOrientation>().qx)) +
+                             ((value.qy - getParameter(0).getClass<FramedOrientation>().qy) * (value.qy - getParameter(0).getClass<FramedOrientation>().qy)) +
+                             ((value.qz - getParameter(0).getClass<FramedOrientation>().qx) * (value.qx - getParameter(0).getClass<FramedOrientation>().qz))) == 0);
 
-            if(type == VariantType::Pose)
-                return (sqrt(((value.x-getParameter(0).getClass<Pose>().x)*(value.x-getParameter(0).getClass<Pose>().x))+
-                             ((value.y-getParameter(0).getClass<Pose>().y)*(value.y-getParameter(0).getClass<Pose>().y))+
-                             ((value.z-getParameter(0).getClass<Pose>().x)*(value.x-getParameter(0).getClass<Pose>().z)))+
-                            sqrt(((value.qw-getParameter(0).getClass<Pose>().qw)*(value.qw-getParameter(0).getClass<Pose>().qw))+
-                             ((value.qx-getParameter(0).getClass<Pose>().qx)*(value.qx-getParameter(0).getClass<Pose>().qx))+
-                             ((value.qy-getParameter(0).getClass<Pose>().qy)*(value.qy-getParameter(0).getClass<Pose>().qy))+
-                             ((value.qz-getParameter(0).getClass<Pose>().qx)*(value.qx-getParameter(0).getClass<Pose>().qz))) == 0);
+            if (type == VariantType::Pose)
+                return (sqrt(((value.x - getParameter(0).getClass<Pose>().x) * (value.x - getParameter(0).getClass<Pose>().x)) +
+                             ((value.y - getParameter(0).getClass<Pose>().y) * (value.y - getParameter(0).getClass<Pose>().y)) +
+                             ((value.z - getParameter(0).getClass<Pose>().x) * (value.x - getParameter(0).getClass<Pose>().z))) +
+                        sqrt(((value.qw - getParameter(0).getClass<Pose>().qw) * (value.qw - getParameter(0).getClass<Pose>().qw)) +
+                             ((value.qx - getParameter(0).getClass<Pose>().qx) * (value.qx - getParameter(0).getClass<Pose>().qx)) +
+                             ((value.qy - getParameter(0).getClass<Pose>().qy) * (value.qy - getParameter(0).getClass<Pose>().qy)) +
+                             ((value.qz - getParameter(0).getClass<Pose>().qx) * (value.qx - getParameter(0).getClass<Pose>().qz))) == 0);
 
             return false;
         }
diff --git a/source/RobotAPI/libraries/core/checks/ConditionCheckEqualsPoseWithTolerance.h b/source/RobotAPI/libraries/core/checks/ConditionCheckEqualsPoseWithTolerance.h
index 6d888801d6387861879afe7e56704c3ad85fbc09..a31803d6bc3a045cca19510c41030cd5fe941baf 100644
--- a/source/RobotAPI/libraries/core/checks/ConditionCheckEqualsPoseWithTolerance.h
+++ b/source/RobotAPI/libraries/core/checks/ConditionCheckEqualsPoseWithTolerance.h
@@ -1,8 +1,8 @@
 #ifndef ARMARX_ROBOTAPI_CONDITIONCHECKEQUALSPOSITIONWITHTOLERANCE_H
 #define ARMARX_ROBOTAPI_CONDITIONCHECKEQUALSPOSITIONWITHTOLERANCE_H
 
-#include <Core/core/system/ImportExport.h>
-#include <Core/observers/ConditionCheck.h>
+#include <ArmarXCore/core/system/ImportExport.h>
+#include <ArmarXCore/observers/ConditionCheck.h>
 #include <RobotAPI/libraries/core/FramedPose.h>
 
 namespace armarx
@@ -26,9 +26,9 @@ namespace armarx
             return new ConditionCheckApproxPose(*this);
         }
 
-        bool evaluate(const StringVariantMap &dataFields)
+        bool evaluate(const StringVariantMap& dataFields)
         {
-            if(dataFields.size() != 1)
+            if (dataFields.size() != 1)
             {
                 printf("Size of dataFields: %d\n", (int)dataFields.size());
                 throw InvalidConditionException("Wrong number of datafields for condition equals ");
@@ -37,63 +37,63 @@ namespace armarx
             const Variant& value = dataFields.begin()->second;
             VariantTypeId type = value.getType();
 
-            if(type == VariantType::Vector3)
+            if (type == VariantType::Vector3)
             {
-                const Vector3Ptr & typedValue =  value.getClass<Vector3>();
-                const Vector3Ptr & param =  getParameter(0).getClass<Vector3>();
-                return (sqrt(((typedValue->x-param->x)*(typedValue->x-param->x))+
-                             ((typedValue->y-param->y)*(typedValue->y-param->y))+
-                             ((typedValue->z-param->x)*(typedValue->x-param->z))) < getParameter(1).getFloat());
+                const Vector3Ptr& typedValue =  value.getClass<Vector3>();
+                const Vector3Ptr& param =  getParameter(0).getClass<Vector3>();
+                return (sqrt(((typedValue->x - param->x) * (typedValue->x - param->x)) +
+                             ((typedValue->y - param->y) * (typedValue->y - param->y)) +
+                             ((typedValue->z - param->x) * (typedValue->x - param->z))) < getParameter(1).getFloat());
             }
 
-            if(type == VariantType::Quaternion)
+            if (type == VariantType::Quaternion)
             {
-                const QuaternionPtr & typedValue =  value.getClass<Quaternion>();
-                const QuaternionPtr & param =  getParameter(0).getClass<Quaternion>();
-                Eigen::Matrix3f diffRot = typedValue->toEigen()*param->toEigen().transpose();
+                const QuaternionPtr& typedValue =  value.getClass<Quaternion>();
+                const QuaternionPtr& param =  getParameter(0).getClass<Quaternion>();
+                Eigen::Matrix3f diffRot = typedValue->toEigen() * param->toEigen().transpose();
                 Eigen::AngleAxisf aa(diffRot);
                 return fabs(aa.angle()) < getParameter(1).getFloat();
             }
 
 
-            if(type == VariantType::FramedPosition)
+            if (type == VariantType::FramedPosition)
             {
-                const FramedPositionPtr & typedValue =  value.getClass<FramedPosition>();
-                const FramedPositionPtr & param =  getParameter(0).getClass<FramedPosition>();
+                const FramedPositionPtr& typedValue =  value.getClass<FramedPosition>();
+                const FramedPositionPtr& param =  getParameter(0).getClass<FramedPosition>();
                 return param->getFrame() == typedValue->getFrame()
-                        && (sqrt(((typedValue->x-param->x)*(typedValue->x-param->x))+
-                             ((typedValue->y-param->y)*(typedValue->y-param->y))+
-                             ((typedValue->z-param->x)*(typedValue->x-param->z))) < getParameter(1).getFloat());
+                       && (sqrt(((typedValue->x - param->x) * (typedValue->x - param->x)) +
+                                ((typedValue->y - param->y) * (typedValue->y - param->y)) +
+                                ((typedValue->z - param->x) * (typedValue->x - param->z))) < getParameter(1).getFloat());
             }
 
 
-            if(type == VariantType::FramedOrientation)
+            if (type == VariantType::FramedOrientation)
             {
-                const FramedOrientationPtr & typedValue =  value.getClass<FramedOrientation>();
-                const FramedOrientationPtr & param =  getParameter(0).getClass<FramedOrientation>();
-                Eigen::Matrix3f diffRot = typedValue->toEigen()*param->toEigen().transpose();
+                const FramedOrientationPtr& typedValue =  value.getClass<FramedOrientation>();
+                const FramedOrientationPtr& param =  getParameter(0).getClass<FramedOrientation>();
+                Eigen::Matrix3f diffRot = typedValue->toEigen() * param->toEigen().transpose();
                 Eigen::AngleAxisf aa(diffRot);
                 return fabs(aa.angle()) < getParameter(1).getFloat();
             }
 
 
-            if(type == VariantType::FramedPose)
+            if (type == VariantType::FramedPose)
             {
-                const PosePtr & typedValue =  value.getClass<FramedPose>();
-                const PosePtr & param =  getParameter(0).getClass<FramedPose>();
-                bool positionOk =  (sqrt(((typedValue->position->x-param->position->x)*(typedValue->position->x-param->position->x))+
-                             ((typedValue->position->y-param->position->y)*(typedValue->position->y-param->position->y))+
-                             ((typedValue->position->z-param->position->x)*(typedValue->position->x-param->position->z)))
-                        <  getParameter(1).getFloat());
-
-                Eigen::Matrix3f diffRot = typedValue->toEigen().block<3,3>(0,0)*param->toEigen().block<3,3>(0,0).transpose();
+                const PosePtr& typedValue =  value.getClass<FramedPose>();
+                const PosePtr& param =  getParameter(0).getClass<FramedPose>();
+                bool positionOk = (sqrt(((typedValue->position->x - param->position->x) * (typedValue->position->x - param->position->x)) +
+                                        ((typedValue->position->y - param->position->y) * (typedValue->position->y - param->position->y)) +
+                                        ((typedValue->position->z - param->position->x) * (typedValue->position->x - param->position->z)))
+                                   <  getParameter(1).getFloat());
+
+                Eigen::Matrix3f diffRot = typedValue->toEigen().block<3, 3>(0, 0) * param->toEigen().block<3, 3>(0, 0).transpose();
                 Eigen::AngleAxisf aa(diffRot);
                 bool orientationOk =
-                            fabs(aa.angle()) < getParameter(2).getFloat();
+                    fabs(aa.angle()) < getParameter(2).getFloat();
                 return positionOk && orientationOk;
             }
 
-           return false;
+            return false;
         }
     };
 }
diff --git a/source/RobotAPI/libraries/core/checks/ConditionCheckMagnitudeChecks.cpp b/source/RobotAPI/libraries/core/checks/ConditionCheckMagnitudeChecks.cpp
index dccad8f961ce255f0704c382be2dcc97881cdef5..5b5ea5cddf872017db681e37b8126619e6f1d815 100644
--- a/source/RobotAPI/libraries/core/checks/ConditionCheckMagnitudeChecks.cpp
+++ b/source/RobotAPI/libraries/core/checks/ConditionCheckMagnitudeChecks.cpp
@@ -1,7 +1,10 @@
 #include "ConditionCheckMagnitudeChecks.h"
 
-namespace armarx {
-    
+#include <ArmarXCore/core/util/StringHelpers.h>
+
+namespace armarx
+{
+
     ConditionCheckMagnitudeLarger::ConditionCheckMagnitudeLarger()
     {
         setNumberParameters(1);
@@ -16,31 +19,31 @@ namespace armarx {
         return new ConditionCheckMagnitudeLarger(*this);
     }
 
-    bool ConditionCheckMagnitudeLarger::evaluate(const StringVariantMap &dataFields)
+    bool ConditionCheckMagnitudeLarger::evaluate(const StringVariantMap& dataFields)
     {
 
-        if(dataFields.size() != 1)
+        if (dataFields.size() != 1)
         {
-            printf("Size of dataFields: %d\n", (int)dataFields.size());
-            throw InvalidConditionException("Wrong number of datafields for condition equals ");
+            throw InvalidConditionException("Wrong number of datafields for condition magnitude larger: expected 1 actual: " + ValueToString(dataFields.size()));
         }
 
         const Variant& value = dataFields.begin()->second;
         VariantTypeId type = value.getType();
 
-        if(type == VariantType::Vector3)
+        if (type == VariantType::Vector3)
         {
             Eigen::Vector3f vec = value.getClass<Vector3>()->toEigen();
             return (vec).norm() > getParameter(0).getFloat();
         }
 
-        if(type == VariantType::FramedDirection)
+        if (type == VariantType::FramedDirection)
         {
             FramedDirectionPtr fV1 = value.getClass<FramedDirection>();
             Eigen::Vector3f vec = value.getClass<FramedDirection>()->toEigen();
             return (vec).norm() > getParameter(0).getFloat();
         }
-        if(type == VariantType::LinkedDirection)
+
+        if (type == VariantType::LinkedDirection)
         {
             LinkedDirectionPtr lV1 = value.getClass<LinkedDirection>();
 
@@ -66,10 +69,10 @@ namespace armarx {
         return new ConditionCheckMagnitudeSmaller(*this);
     }
 
-    bool ConditionCheckMagnitudeSmaller::evaluate(const StringVariantMap &dataFields)
+    bool ConditionCheckMagnitudeSmaller::evaluate(const StringVariantMap& dataFields)
     {
 
-        if(dataFields.size() != 1)
+        if (dataFields.size() != 1)
         {
             ARMARX_WARNING_S << "Size of dataFields: %d\n" << dataFields.size();
             throw InvalidConditionException("Wrong number of datafields for condition equals ");
@@ -78,21 +81,22 @@ namespace armarx {
         const Variant& value = dataFields.begin()->second;
         VariantTypeId type = value.getType();
 
-        if(type == VariantType::Vector3)
+        if (type == VariantType::Vector3)
         {
             Eigen::Vector3f vec = value.getClass<Vector3>()->toEigen();
             return (vec).norm() < getParameter(0).getFloat();
         }
 
-        if(type == VariantType::FramedDirection)
+        if (type == VariantType::FramedDirection)
         {
-//            FramedDirectionPtr fV1 = value.getClass<FramedDirection>();
+            //            FramedDirectionPtr fV1 = value.getClass<FramedDirection>();
             Eigen::Vector3f vec = value.getClass<FramedDirection>()->toEigen();
             return (vec).norm() < getParameter(0).getFloat();
         }
-        if(type == VariantType::LinkedDirection)
+
+        if (type == VariantType::LinkedDirection)
         {
-//            LinkedDirectionPtr lV1 = value.getClass<LinkedDirection>();
+            //            LinkedDirectionPtr lV1 = value.getClass<LinkedDirection>();
             Eigen::Vector3f vec = value.getClass<LinkedDirection>()->toEigen();
             return (vec).norm() < getParameter(0).getFloat();
         }
@@ -114,9 +118,9 @@ namespace armarx {
         return new ConditionCheckMagnitudeInRange(*this);
     }
 
-    bool ConditionCheckMagnitudeInRange::evaluate(const StringVariantMap &dataFields)
+    bool ConditionCheckMagnitudeInRange::evaluate(const StringVariantMap& dataFields)
     {
-        if(dataFields.size() != 1)
+        if (dataFields.size() != 1)
         {
             ARMARX_WARNING_S << "Size of dataFields: " << dataFields.size();
             throw InvalidConditionException("Wrong number of datafields for condition InRange ");
@@ -125,22 +129,22 @@ namespace armarx {
         const Variant& value = dataFields.begin()->second;
         VariantTypeId type = value.getType();
 
-        if(type == VariantType::Vector3)
+        if (type == VariantType::Vector3)
         {
             Eigen::Vector3f vec = value.getClass<Vector3>()->toEigen();
             return ((vec).norm() > getParameter(0).getFloat()) && ((vec).norm() < getParameter(1).getFloat());
         }
 
-        if(type == VariantType::FramedDirection)
+        if (type == VariantType::FramedDirection)
         {
-//            FramedDirectionPtr fV1 = value.getClass<FramedDirection>();
+            //            FramedDirectionPtr fV1 = value.getClass<FramedDirection>();
             Eigen::Vector3f vec = value.getClass<FramedDirection>()->toEigen();
             return ((vec).norm() > getParameter(0).getFloat()) && ((vec).norm() < getParameter(1).getFloat());
         }
 
-        if(type == VariantType::LinkedDirection)
+        if (type == VariantType::LinkedDirection)
         {
-//            LinkedDirectionPtr lV1 = value.getClass<LinkedDirection>();
+            //            LinkedDirectionPtr lV1 = value.getClass<LinkedDirection>();
             Eigen::Vector3f vec = value.getClass<LinkedDirection>()->toEigen();
             return ((vec).norm() > getParameter(0).getFloat()) && ((vec).norm() < getParameter(1).getFloat());
         }
diff --git a/source/RobotAPI/libraries/core/checks/ConditionCheckMagnitudeChecks.h b/source/RobotAPI/libraries/core/checks/ConditionCheckMagnitudeChecks.h
index 0ad27d90581528c947db40d46f0e2cc2260d0a6e..2c91a36fc0755fd5a8446586be472fb461dde936 100644
--- a/source/RobotAPI/libraries/core/checks/ConditionCheckMagnitudeChecks.h
+++ b/source/RobotAPI/libraries/core/checks/ConditionCheckMagnitudeChecks.h
@@ -1,20 +1,21 @@
 #ifndef ARMARX_CONDITIONCHECKMAGNITUDECHECKS_H
 #define ARMARX_CONDITIONCHECKMAGNITUDECHECKS_H
 
-#include <Core/core/system/ImportExport.h>
-#include <Core/observers/ConditionCheck.h>
+#include <ArmarXCore/core/system/ImportExport.h>
+#include <ArmarXCore/observers/ConditionCheck.h>
 #include <RobotAPI/libraries/core/FramedPose.h>
 #include <RobotAPI/libraries/core/LinkedPose.h>
 
-namespace armarx {
-    
+namespace armarx
+{
+
     class ConditionCheckMagnitudeLarger : public ConditionCheck, Logging
     {
     public:
         ConditionCheckMagnitudeLarger();
 
-        ConditionCheck *clone();
-        bool evaluate(const StringVariantMap &dataFields);
+        ConditionCheck* clone();
+        bool evaluate(const StringVariantMap& dataFields);
     };
 
     class ConditionCheckMagnitudeSmaller : public ConditionCheck, Logging
@@ -22,8 +23,8 @@ namespace armarx {
     public:
         ConditionCheckMagnitudeSmaller();
 
-        ConditionCheck *clone();
-        bool evaluate(const StringVariantMap &dataFields);
+        ConditionCheck* clone();
+        bool evaluate(const StringVariantMap& dataFields);
     };
 
     class ConditionCheckMagnitudeInRange : public ConditionCheck, Logging
@@ -31,8 +32,8 @@ namespace armarx {
     public:
         ConditionCheckMagnitudeInRange();
 
-        ConditionCheck *clone();
-        bool evaluate(const StringVariantMap &dataFields);
+        ConditionCheck* clone();
+        bool evaluate(const StringVariantMap& dataFields);
     };
 
 }
diff --git a/source/RobotAPI/libraries/core/math/MathUtils.h b/source/RobotAPI/libraries/core/math/MathUtils.h
index 1a56170a8d6e123a940c39f82ccd3f89ef7d2a5c..22b5ea0e22d3c2ef0cecc94c8aa62b4f221aec49 100644
--- a/source/RobotAPI/libraries/core/math/MathUtils.h
+++ b/source/RobotAPI/libraries/core/math/MathUtils.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::Core
 * @author     Simon Ottenhaus ( simon dot ottenhaus at kit dot edu )
 * @date       2015
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -47,7 +46,7 @@ namespace armarx
             {
                 return value < min ? min : (value > max ? max : value);
             }
-            static Eigen::Vector3f LimitMinMax(const Eigen::Vector3f &min, const Eigen::Vector3f &max, const Eigen::Vector3f &value)
+            static Eigen::Vector3f LimitMinMax(const Eigen::Vector3f& min, const Eigen::Vector3f& max, const Eigen::Vector3f& value)
             {
                 return Eigen::Vector3f(LimitMinMax(min(0), max(0), value(0)), LimitMinMax(min(1), max(1), value(1)), LimitMinMax(min(2), max(2), value(2)));
             }
@@ -64,37 +63,43 @@ namespace armarx
             {
                 return value >= min && value <= max;
             }
-            static bool CheckMinMax(const Eigen::Vector3f &min, const Eigen::Vector3f &max, const Eigen::Vector3f &value)
+            static bool CheckMinMax(const Eigen::Vector3f& min, const Eigen::Vector3f& max, const Eigen::Vector3f& value)
             {
                 return CheckMinMax(min(0), max(0), value(0)) && CheckMinMax(min(1), max(1), value(1)) && CheckMinMax(min(2), max(2), value(2));
             }
 
-            static std::vector<float> VectorSubtract(const std::vector<float> &v1, const std::vector<float> &v2)
+            static std::vector<float> VectorSubtract(const std::vector<float>& v1, const std::vector<float>& v2)
             {
                 std::vector<float> result;
-                for(size_t i = 0; i < v1.size() && i < v2.size(); i++)
+
+                for (size_t i = 0; i < v1.size() && i < v2.size(); i++)
                 {
                     result.push_back(v1.at(i) - v2.at(i));
                 }
+
                 return result;
             }
-            static std::vector<float> VectorAbsDiff(const std::vector<float> &v1, const std::vector<float> &v2)
+            static std::vector<float> VectorAbsDiff(const std::vector<float>& v1, const std::vector<float>& v2)
             {
                 std::vector<float> result;
-                for(size_t i = 0; i < v1.size() && i < v2.size(); i++)
+
+                for (size_t i = 0; i < v1.size() && i < v2.size(); i++)
                 {
                     result.push_back(std::fabs(v1.at(i) - v2.at(i)));
                 }
+
                 return result;
             }
 
-            static float VectorMax(const std::vector<float> &vec)
+            static float VectorMax(const std::vector<float>& vec)
             {
                 float max = vec.at(0);
-                for(size_t i = 1; i < vec.size(); i++)
+
+                for (size_t i = 1; i < vec.size(); i++)
                 {
                     max = std::max(max, vec.at(i));
                 }
+
                 return max;
             }
 
diff --git a/source/RobotAPI/libraries/core/math/MatrixHelpers.h b/source/RobotAPI/libraries/core/math/MatrixHelpers.h
index 258a16600462eb0be51dc1acc1c8c96507987ccb..859be8dd2923c67ba10d0a80d80cc9f28e3b9733 100644
--- a/source/RobotAPI/libraries/core/math/MatrixHelpers.h
+++ b/source/RobotAPI/libraries/core/math/MatrixHelpers.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::Core
 * @author     Simon Ottenhaus ( simon dot ottenhaus at kit dot edu )
 * @date       2015
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -34,31 +33,35 @@ namespace armarx
         class MatrixHelpers
         {
         public:
-            static void SetRowToValue(Eigen::MatrixXf &matrix, int rowNr, float value)
+            static void SetRowToValue(Eigen::MatrixXf& matrix, int rowNr, float value)
             {
-                for(int i = 0; i < matrix.cols(); i++)
+                for (int i = 0; i < matrix.cols(); i++)
                 {
                     matrix(rowNr, i) = value;
                 }
             }
 
-            static Eigen::Vector3f CalculateCog3D(const Eigen::MatrixXf &points)
+            static Eigen::Vector3f CalculateCog3D(const Eigen::MatrixXf& points)
             {
                 Eigen::Vector3f sum(0, 0, 0);
-                for(int i = 0; i < points.cols(); i++)
+
+                for (int i = 0; i < points.cols(); i++)
                 {
-                    sum += points.block<3,1>(0,i);
+                    sum += points.block<3, 1>(0, i);
                 }
+
                 return sum / points.cols();
             }
 
-            static Eigen::MatrixXf SubtractVectorFromAllColumns3D(const Eigen::MatrixXf &points, const Eigen::Vector3f &vec)
+            static Eigen::MatrixXf SubtractVectorFromAllColumns3D(const Eigen::MatrixXf& points, const Eigen::Vector3f& vec)
             {
                 Eigen::MatrixXf matrix(3, points.cols());
-                for(int i = 0; i < points.cols(); i++)
+
+                for (int i = 0; i < points.cols(); i++)
                 {
-                    matrix.block<3,1>(0,i) = points.block<3,1>(0,i) - vec;
+                    matrix.block<3, 1>(0, i) = points.block<3, 1>(0, i) - vec;
                 }
+
                 return matrix;
             }
 
diff --git a/source/RobotAPI/libraries/core/math/SVD.h b/source/RobotAPI/libraries/core/math/SVD.h
index 09f6ad0ffa4557d4647d20b28bda1a508010f23a..91fc384b12eeb5caef8b2f0775fd397e188851fb 100644
--- a/source/RobotAPI/libraries/core/math/SVD.h
+++ b/source/RobotAPI/libraries/core/math/SVD.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::Core
 * @author     Simon Ottenhaus ( simon dot ottenhaus at kit dot edu )
 * @date       2015
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -49,7 +48,7 @@ namespace armarx
 
             Eigen::Vector3f getLeftSingularVector3D(int nr)
             {
-                return matrixU.block<3,1>(0,nr);
+                return matrixU.block<3, 1>(0, nr);
             }
 
         };
diff --git a/source/RobotAPI/libraries/core/math/SlidingWindowVectorMedian.h b/source/RobotAPI/libraries/core/math/SlidingWindowVectorMedian.h
index dd0caa836098a446d3b9c0b181453e7fc064cf50..defc3a5780f5e77a73c8618c8d346a9b1d95a087 100644
--- a/source/RobotAPI/libraries/core/math/SlidingWindowVectorMedian.h
+++ b/source/RobotAPI/libraries/core/math/SlidingWindowVectorMedian.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::Core
 * @author     Simon Ottenhaus ( simon dot ottenhaus at kit dot edu )
 * @date       2015
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -29,7 +28,7 @@
 #include <math.h>
 #include <vector>
 
-#include <Core/core/exceptions/Exception.h>
+#include <ArmarXCore/core/exceptions/Exception.h>
 #include <boost/shared_ptr.hpp>
 
 namespace armarx
@@ -52,20 +51,20 @@ namespace armarx
             SlidingWindowVectorMedian(size_t vectorSize, size_t windowSize)
                 : windowSize(windowSize),
                   vectorSize(vectorSize),
-                  data(vectorSize * windowSize, 0), // initialize all data to 0
+                  data(vectorSize* windowSize, 0),  // initialize all data to 0
                   currentIndex(0),
                   fullCycle(false)
             {
             }
 
-            void addEntry(const std::vector<float> &entry)
+            void addEntry(const std::vector<float>& entry)
             {
-                if(entry.size() != vectorSize)
+                if (entry.size() != vectorSize)
                 {
                     throw LocalException("Vector of wrong size added. Execting: ") << vectorSize << "; Actual: " << entry.size();
                 }
 
-                for(size_t i = 0; i < entry.size(); i++)
+                for (size_t i = 0; i < entry.size(); i++)
                 {
                     data.at(i + currentIndex * vectorSize) = entry.at(i);
                 }
@@ -77,16 +76,20 @@ namespace armarx
             std::vector<float> getMedian()
             {
                 std::vector<float> median;
-                for(size_t i = 0; i < vectorSize; i++)
+
+                for (size_t i = 0; i < vectorSize; i++)
                 {
                     std::vector<float> samples;
-                    for(size_t n = 0; n < windowSize; n++)
+
+                    for (size_t n = 0; n < windowSize; n++)
                     {
                         samples.push_back(data.at(i + n * vectorSize));
                     }
+
                     std::sort(samples.begin(), samples.end());
                     median.push_back(StatUtils::GetMedian(samples));
                 }
+
                 return median;
             }
 
diff --git a/source/RobotAPI/libraries/core/math/StatUtils.h b/source/RobotAPI/libraries/core/math/StatUtils.h
index f63f00ad86b3088b0f6146154fcfcf32f865c565..709997af13f0c0a1167978c631379b8f5dc6b4d5 100644
--- a/source/RobotAPI/libraries/core/math/StatUtils.h
+++ b/source/RobotAPI/libraries/core/math/StatUtils.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::Core
 * @author     Simon Ottenhaus ( simon dot ottenhaus at kit dot edu )
 * @date       2015
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -34,34 +33,39 @@ namespace armarx
         class StatUtils
         {
         public:
-            static float GetPercentile(const std::vector<float> &sortedData, float percentile)
+            static float GetPercentile(const std::vector<float>& sortedData, float percentile)
             {
-                if(sortedData.size() == 0)
+                if (sortedData.size() == 0)
                 {
                     throw LocalException("GetPercentile not possible for empty vector");
                 }
+
                 float indexf = (sortedData.size() - 1) * percentile;
                 indexf = std::max(0.f, std::min(sortedData.size() - 1.f, indexf));
                 int index = (int)indexf;
                 float f = indexf - index;
-                if(index == (int)sortedData.size() - 1)
+
+                if (index == (int)sortedData.size() - 1)
                 {
                     return sortedData.at(sortedData.size() - 1);
                 }
+
                 return sortedData.at(index) * (1 - f) + sortedData.at(index + 1) * f;
             }
-            static std::vector<float> GetPercentiles(const std::vector<float> &sortedData, int percentiles)
+            static std::vector<float> GetPercentiles(const std::vector<float>& sortedData, int percentiles)
             {
                 std::vector<float> result;
                 result.push_back(sortedData.at(0));
-                for(int i = 1; i < percentiles; i++)
+
+                for (int i = 1; i < percentiles; i++)
                 {
                     result.push_back(GetPercentile(sortedData, 1.f / percentiles * i));
                 }
+
                 result.push_back(sortedData.at(sortedData.size() - 1));
                 return result;
             }
-            static float GetMedian(const std::vector<float> &sortedData)
+            static float GetMedian(const std::vector<float>& sortedData)
             {
                 return GetPercentile(sortedData, 0.5f);
             }
diff --git a/source/RobotAPI/libraries/core/math/Trigonometry.h b/source/RobotAPI/libraries/core/math/Trigonometry.h
index 4520e674d438992d4f770fad0bcc23455066f08c..e3abce2577e76102633b216ea6777bba47716ef5 100644
--- a/source/RobotAPI/libraries/core/math/Trigonometry.h
+++ b/source/RobotAPI/libraries/core/math/Trigonometry.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::Core
 * @author     Simon Ottenhaus ( simon dot ottenhaus at kit dot edu )
 * @date       2015
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -50,7 +49,7 @@ namespace armarx
                 return rad / M_PI * 180.0d;
             }
 
-            static double GetAngleFromVectorXY(const Eigen::Vector3f &vector)
+            static double GetAngleFromVectorXY(const Eigen::Vector3f& vector)
             {
                 return atan2(vector(1), vector(0));
             }
diff --git a/source/RobotAPI/libraries/core/observerfilters/MatrixFilters.h b/source/RobotAPI/libraries/core/observerfilters/MatrixFilters.h
index 801e0c24b90a3a914369e90b9cd7de180ef6a6f5..3fbb1ea0cbc3f92c6f113279ae83e11e61973c8a 100644
--- a/source/RobotAPI/libraries/core/observerfilters/MatrixFilters.h
+++ b/source/RobotAPI/libraries/core/observerfilters/MatrixFilters.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,16 +16,16 @@
 * @package    ArmarX::
 * @author     Simon Ottenhaus ( simon.ottenhaus at kit dot edu)
 * @date       2015
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
 #ifndef _ARMARX_ROBOTAPI_MATRIXFILTERS_H
 #define _ARMARX_ROBOTAPI_MATRIXFILTERS_H
 
-#include <Core/observers/filters/DatafieldFilter.h>
+#include <ArmarXCore/observers/filters/DatafieldFilter.h>
 #include <RobotAPI/interface/observers/ObserverFilters.h>
-#include <Core/util/variants/eigen3/MatrixVariant.h>
+#include <ArmarXCore/util/variants/eigen3/MatrixVariant.h>
 #include <algorithm>
 
 namespace armarx
@@ -35,8 +34,8 @@ namespace armarx
     {
 
         class MatrixMaxFilter :
-                public MatrixMaxFilterBase,
-                public DatafieldFilter
+            public MatrixMaxFilterBase,
+            public DatafieldFilter
         {
         public:
             MatrixMaxFilter()
@@ -44,17 +43,18 @@ namespace armarx
                 this->windowFilterSize = 1;
             }
 
-            VariantBasePtr calculate(const Ice::Current &) const
+            VariantBasePtr calculate(const Ice::Current&) const
             {
-                if(dataHistory.size() == 0)
+                if (dataHistory.size() == 0)
                 {
                     return new Variant(new MatrixFloat(1, 1));
                 }
+
                 VariantPtr currentValue = VariantPtr::dynamicCast(dataHistory.rbegin()->second);
                 MatrixFloatPtr matrix = MatrixFloatPtr::dynamicCast(currentValue->get<MatrixFloat>());
                 return new Variant(matrix->toEigen().maxCoeff());
             }
-            ParameterTypeList getSupportedTypes(const Ice::Current &) const
+            ParameterTypeList getSupportedTypes(const Ice::Current&) const
             {
                 ParameterTypeList result;
                 result.push_back(VariantType::MatrixFloat);
@@ -63,8 +63,8 @@ namespace armarx
         };
 
         class MatrixMinFilter :
-                public MatrixMinFilterBase,
-                public DatafieldFilter
+            public MatrixMinFilterBase,
+            public DatafieldFilter
         {
         public:
             MatrixMinFilter()
@@ -72,17 +72,18 @@ namespace armarx
                 this->windowFilterSize = 1;
             }
 
-            VariantBasePtr calculate(const Ice::Current &) const
+            VariantBasePtr calculate(const Ice::Current&) const
             {
-                if(dataHistory.size() == 0)
+                if (dataHistory.size() == 0)
                 {
                     return new Variant(new MatrixFloat(1, 1));
                 }
+
                 VariantPtr currentValue = VariantPtr::dynamicCast(dataHistory.rbegin()->second);
                 MatrixFloatPtr matrix = MatrixFloatPtr::dynamicCast(currentValue->get<MatrixFloat>());
                 return new Variant(matrix->toEigen().minCoeff());
             }
-            ParameterTypeList getSupportedTypes(const Ice::Current &) const
+            ParameterTypeList getSupportedTypes(const Ice::Current&) const
             {
                 ParameterTypeList result;
                 result.push_back(VariantType::MatrixFloat);
@@ -91,8 +92,8 @@ namespace armarx
         };
 
         class MatrixAvgFilter :
-                public MatrixAvgFilterBase,
-                public DatafieldFilter
+            public MatrixAvgFilterBase,
+            public DatafieldFilter
         {
         public:
             MatrixAvgFilter()
@@ -100,17 +101,18 @@ namespace armarx
                 this->windowFilterSize = 1;
             }
 
-            VariantBasePtr calculate(const Ice::Current &) const
+            VariantBasePtr calculate(const Ice::Current&) const
             {
-                if(dataHistory.size() == 0)
+                if (dataHistory.size() == 0)
                 {
                     return new Variant(new MatrixFloat(1, 1));
                 }
+
                 VariantPtr currentValue = VariantPtr::dynamicCast(dataHistory.rbegin()->second);
                 MatrixFloatPtr matrix = MatrixFloatPtr::dynamicCast(currentValue->get<MatrixFloat>());
                 return new Variant(matrix->toEigen().mean());
             }
-            ParameterTypeList getSupportedTypes(const Ice::Current &) const
+            ParameterTypeList getSupportedTypes(const Ice::Current&) const
             {
                 ParameterTypeList result;
                 result.push_back(VariantType::MatrixFloat);
@@ -119,8 +121,8 @@ namespace armarx
         };
 
         class MatrixPercentileFilter :
-                public MatrixPercentileFilterBase,
-                public DatafieldFilter
+            public MatrixPercentileFilterBase,
+            public DatafieldFilter
         {
         public:
             MatrixPercentileFilter()
@@ -133,46 +135,50 @@ namespace armarx
                 this->windowFilterSize = 1;
             }
 
-            VariantBasePtr calculate(const Ice::Current &) const
+            VariantBasePtr calculate(const Ice::Current&) const
             {
-                if(dataHistory.size() == 0)
+                if (dataHistory.size() == 0)
                 {
                     return new Variant(new MatrixFloat(1, 1));
                 }
+
                 VariantPtr currentValue = VariantPtr::dynamicCast(dataHistory.rbegin()->second);
                 MatrixFloatPtr matrix = MatrixFloatPtr::dynamicCast(currentValue->get<MatrixFloat>());
                 std::vector<float> vector = matrix->toVector();
                 std::sort(vector.begin(), vector.end());
                 return new Variant(GetPercentile(vector, percentile));
             }
-            ParameterTypeList getSupportedTypes(const Ice::Current &) const
+            ParameterTypeList getSupportedTypes(const Ice::Current&) const
             {
                 ParameterTypeList result;
                 result.push_back(VariantType::MatrixFloat);
                 return result;
             }
 
-            static float GetPercentile(const std::vector<float> &sortedData, float percentile)
+            static float GetPercentile(const std::vector<float>& sortedData, float percentile)
             {
-                if(sortedData.size() == 0)
+                if (sortedData.size() == 0)
                 {
                     throw LocalException("GetPercentile not possible for empty vector");
                 }
+
                 float indexf = (sortedData.size() - 1) * percentile;
                 indexf = std::max(0.f, std::min(sortedData.size() - 1.f, indexf));
                 int index = (int)indexf;
                 float f = indexf - index;
-                if(index == (int)sortedData.size() - 1)
+
+                if (index == (int)sortedData.size() - 1)
                 {
                     return sortedData.at(sortedData.size() - 1);
                 }
+
                 return sortedData.at(index) * (1 - f) + sortedData.at(index + 1) * f;
             }
         };
 
         class MatrixPercentilesFilter :
-                public MatrixPercentilesFilterBase,
-                public DatafieldFilter
+            public MatrixPercentilesFilterBase,
+            public DatafieldFilter
         {
         public:
             MatrixPercentilesFilter()
@@ -186,27 +192,30 @@ namespace armarx
                 this->windowFilterSize = 1;
             }
 
-            VariantBasePtr calculate(const Ice::Current &) const
+            VariantBasePtr calculate(const Ice::Current&) const
             {
-                if(dataHistory.size() == 0)
+                if (dataHistory.size() == 0)
                 {
                     ARMARX_IMPORTANT_S << "no data";
                     return new Variant(new MatrixFloat(1, 1));
                 }
+
                 VariantPtr currentValue = VariantPtr::dynamicCast(dataHistory.rbegin()->second);
                 MatrixFloatPtr matrix = MatrixFloatPtr::dynamicCast(currentValue->get<MatrixFloat>());
                 std::vector<float> vector = matrix->toVector();
                 std::sort(vector.begin(), vector.end());
                 std::vector<float> result;
                 result.push_back(vector.at(0));
-                for(int i = 1; i < percentiles; i++)
+
+                for (int i = 1; i < percentiles; i++)
                 {
                     result.push_back(MatrixPercentileFilter::GetPercentile(vector, 1.f / percentiles * i));
                 }
+
                 result.push_back(vector.at(vector.size() - 1));
                 return new Variant(new MatrixFloat(1, result.size(), result));
             }
-            ParameterTypeList getSupportedTypes(const Ice::Current &) const
+            ParameterTypeList getSupportedTypes(const Ice::Current&) const
             {
                 ParameterTypeList result;
                 result.push_back(VariantType::MatrixFloat);
@@ -215,8 +224,8 @@ namespace armarx
         };
 
         class MatrixCumulativeFrequencyFilter :
-                public MatrixCumulativeFrequencyFilterBase,
-                public DatafieldFilter
+            public MatrixCumulativeFrequencyFilterBase,
+            public DatafieldFilter
         {
         public:
             MatrixCumulativeFrequencyFilter()
@@ -230,40 +239,43 @@ namespace armarx
                 this->bins = bins;
                 this->windowFilterSize = 1;
             }
-            VariantBasePtr calculate(const Ice::Current &) const
+            VariantBasePtr calculate(const Ice::Current&) const
             {
-                if(dataHistory.size() == 0)
+                if (dataHistory.size() == 0)
                 {
                     return new Variant(new MatrixFloat(1, 1));
                 }
+
                 VariantPtr currentValue = VariantPtr::dynamicCast(dataHistory.rbegin()->second);
                 MatrixFloatPtr matrix = MatrixFloatPtr::dynamicCast(currentValue->get<MatrixFloat>());
                 std::vector<float> vector = matrix->toVector();
                 std::sort(vector.begin(), vector.end());
                 std::vector<int> result = Calculate(vector, min, max, bins);
                 std::vector<float> resultF;
-                for(int v : result)
+
+                for (int v : result)
                 {
                     resultF.push_back(v);
                 }
 
                 return new Variant(new MatrixFloat(1, resultF.size(), resultF));
             }
-            ParameterTypeList getSupportedTypes(const Ice::Current &) const
+            ParameterTypeList getSupportedTypes(const Ice::Current&) const
             {
                 ParameterTypeList result;
                 result.push_back(VariantType::MatrixFloat);
                 return result;
             }
-            static std::vector<int> Calculate(const std::vector<float> &sortedData, float min, float max, int bins)
+            static std::vector<int> Calculate(const std::vector<float>& sortedData, float min, float max, int bins)
             {
                 std::vector<int> result;
                 float val = min;
                 int nr = 0;
                 int lastCount = 0;
-                for(size_t i = 0; i < sortedData.size(); i++)
+
+                for (size_t i = 0; i < sortedData.size(); i++)
                 {
-                    if(sortedData.at(i) > val && nr < bins)
+                    if (sortedData.at(i) > val && nr < bins)
                     {
                         result.push_back(i);
                         nr++;
@@ -271,10 +283,12 @@ namespace armarx
                         lastCount = i;
                     }
                 }
-                while((int)result.size() < bins)
+
+                while ((int)result.size() < bins)
                 {
                     result.push_back(lastCount);
                 }
+
                 return result;
             }
 
diff --git a/source/RobotAPI/libraries/core/observerfilters/OffsetFilter.h b/source/RobotAPI/libraries/core/observerfilters/OffsetFilter.h
index db05fc81189a37286d23b2e758f8295cdc0f8fc5..076e77c1874b176472602c335a6e8942d6720aa9 100644
--- a/source/RobotAPI/libraries/core/observerfilters/OffsetFilter.h
+++ b/source/RobotAPI/libraries/core/observerfilters/OffsetFilter.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::
 * @author     Mirko Waechter ( mirko.waechter at kit dot edu)
 * @date       2014
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -25,12 +24,14 @@
 #define _ARMARX_ROBOTAPI_OFFSETFILTER_H
 
 #include <RobotAPI/interface/observers/ObserverFilters.h>
-#include <Core/observers/filters/DatafieldFilter.h>
+#include <ArmarXCore/observers/filters/DatafieldFilter.h>
 #include <RobotAPI/libraries/core/FramedPose.h>
-#include <Core/util/variants/eigen3/MatrixVariant.h>
+#include <ArmarXCore/util/variants/eigen3/MatrixVariant.h>
 
-namespace armarx {
-    namespace filters {
+namespace armarx
+{
+    namespace filters
+    {
 
         /**
          * @class OffsetFilter
@@ -41,8 +42,8 @@ namespace armarx {
          * at a specific moment.
          */
         class OffsetFilter :
-                public ::armarx::OffsetFilterBase,
-                public DatafieldFilter
+            public ::armarx::OffsetFilterBase,
+            public DatafieldFilter
         {
         public:
             OffsetFilter()
@@ -54,35 +55,38 @@ namespace armarx {
 
             // DatafieldFilterBase interface
         public:
-            VariantBasePtr calculate(const Ice::Current &c = Ice::Current()) const
+            VariantBasePtr calculate(const Ice::Current& c = Ice::Current()) const
             {
 
                 VariantPtr newVariant;
-                if(initialValue && dataHistory.size() > 0)
+
+                if (initialValue && dataHistory.size() > 0)
                 {
                     VariantTypeId type = dataHistory.begin()->second->getType();
                     VariantPtr currentValue = VariantPtr::dynamicCast(dataHistory.rbegin()->second);
-                    if(currentValue->getType() != initialValue->getType())
+
+                    if (currentValue->getType() != initialValue->getType())
                     {
                         ARMARX_ERROR_S << "Types in OffsetFilter are different: " << Variant::typeToString(currentValue->getType()) << " and " << Variant::typeToString(initialValue->getType());
                         return NULL;
                     }
-                    if(type == VariantType::Int)
+
+                    if (type == VariantType::Int)
                     {
                         int newValue = dataHistory.rbegin()->second->getInt() - initialValue->getInt();
                         newVariant = new Variant(newValue);
                     }
-                    else if(type == VariantType::Float)
+                    else if (type == VariantType::Float)
                     {
                         float newValue = dataHistory.rbegin()->second->getFloat() - initialValue->getFloat();
                         newVariant = new Variant(newValue);
                     }
-                    else if(type == VariantType::Double)
+                    else if (type == VariantType::Double)
                     {
                         double newValue = dataHistory.rbegin()->second->getDouble() - initialValue->getDouble();
                         newVariant = new Variant(newValue);
                     }
-                    else if(type == VariantType::FramedDirection)
+                    else if (type == VariantType::FramedDirection)
                     {
                         FramedDirectionPtr vec = FramedDirectionPtr::dynamicCast(currentValue->get<FramedDirection>());
                         FramedDirectionPtr intialVec = FramedDirectionPtr::dynamicCast(initialValue->get<FramedDirection>());
@@ -90,14 +94,14 @@ namespace armarx {
 
                         newVariant = new Variant(new FramedDirection(newValue, vec->frame, vec->agent));
                     }
-                    else if(type == VariantType::FramedPosition)
+                    else if (type == VariantType::FramedPosition)
                     {
                         FramedPositionPtr pos = FramedPositionPtr::dynamicCast(currentValue->get<FramedPosition>());
                         FramedPositionPtr intialPos = FramedPositionPtr::dynamicCast(initialValue->get<FramedPosition>());
                         Eigen::Vector3f newValue =  pos->toEigen() - intialPos->toEigen();
                         newVariant = new Variant(new FramedPosition(newValue, pos->frame, pos->agent));
                     }
-                    else if(type == VariantType::MatrixFloat)
+                    else if (type == VariantType::MatrixFloat)
                     {
                         MatrixFloatPtr matrix = MatrixFloatPtr::dynamicCast(currentValue->get<MatrixFloat>());
                         MatrixFloatPtr initialMatrix = MatrixFloatPtr::dynamicCast(initialValue->get<MatrixFloat>());
@@ -105,10 +109,11 @@ namespace armarx {
                         newVariant = new Variant(new MatrixFloat(newMatrix));
                     }
                 }
+
                 return newVariant;
 
             }
-            ParameterTypeList getSupportedTypes(const Ice::Current &) const
+            ParameterTypeList getSupportedTypes(const Ice::Current&) const
             {
                 ParameterTypeList result;
                 result.push_back(VariantType::Int);
@@ -125,13 +130,17 @@ namespace armarx {
 
             // DatafieldFilterBase interface
         public:
-            void update(Ice::Long timestamp, const VariantBasePtr &value, const Ice::Current &c)
+            void update(Ice::Long timestamp, const VariantBasePtr& value, const Ice::Current& c)
             {
                 DatafieldFilter::update(timestamp, value, c);
-                if(firstRun)
+
+                if (firstRun)
                 {
-                    if( dataHistory.size() == 0 )
+                    if (dataHistory.size() == 0)
+                    {
                         return;
+                    }
+
                     initialValue = VariantPtr::dynamicCast(dataHistory.begin()->second);
                     firstRun = false;
                 }
diff --git a/source/RobotAPI/libraries/core/observerfilters/PoseMedianFilter.h b/source/RobotAPI/libraries/core/observerfilters/PoseMedianFilter.h
index 7a6c80fa884edf6256b29879349af50a534c8f8e..64e558129a5b284b3a8cd157b7cd5ac953e936ae 100644
--- a/source/RobotAPI/libraries/core/observerfilters/PoseMedianFilter.h
+++ b/source/RobotAPI/libraries/core/observerfilters/PoseMedianFilter.h
@@ -1,12 +1,14 @@
 #ifndef _ARMARX_ROBOTAPI_MEDIANFILTER_H
 #define _ARMARX_ROBOTAPI_MEDIANFILTER_H
 
-#include <Core/observers/filters/MedianFilter.h>
+#include <ArmarXCore/observers/filters/MedianFilter.h>
 #include <RobotAPI/libraries/core/FramedPose.h>
 #include <RobotAPI/interface/core/PoseBase.h>
 
-namespace armarx {
-    namespace filters {
+namespace armarx
+{
+    namespace filters
+    {
 
         /**
          * @class PoseMedianFilter
@@ -15,8 +17,8 @@ namespace armarx {
          *  for a median for datafields of type float, int and double.
          */
         class PoseMedianFilter :
-                public ::armarx::PoseMedianFilterBase,
-                public MedianFilter
+            public ::armarx::PoseMedianFilterBase,
+            public MedianFilter
         {
         public:
             PoseMedianFilter(int windowSize = 11)
@@ -26,10 +28,12 @@ namespace armarx {
 
             // DatafieldFilterBase interface
         public:
-            VariantBasePtr calculate(const Ice::Current &c) const
+            VariantBasePtr calculate(const Ice::Current& c) const
             {
-                if(dataHistory.size() == 0)
+                if (dataHistory.size() == 0)
+                {
                     return NULL;
+                }
 
                 VariantTypeId type = dataHistory.begin()->second->getType();
 
@@ -41,6 +45,7 @@ namespace armarx {
                     std::string frame = "";
                     std::string agent = "";
                     VariantPtr var = VariantPtr::dynamicCast(dataHistory.begin()->second);
+
                     if (type == VariantType::FramedDirection)
                     {
                         FramedDirectionPtr p = var->get<FramedDirection>();
@@ -54,15 +59,18 @@ namespace armarx {
                         agent = p->agent;
                     }
 
-                    for (int i = 0; i < 3; ++i) {
+                    for (int i = 0; i < 3; ++i)
+                    {
                         std::vector<double> values;
-                        for(auto v : dataHistory)
+
+                        for (auto v : dataHistory)
                         {
                             VariantPtr v2 = VariantPtr::dynamicCast(v.second);
                             values.push_back(v2->get<Vector3>()->toEigen()[i]);
                         }
+
                         std::sort(values.begin(), values.end());
-                        vec[i] = values.at(values.size()/2);
+                        vec[i] = values.at(values.size() / 2);
                     }
 
                     if (type == VariantType::Vector3)
@@ -87,16 +95,17 @@ namespace armarx {
                         return NULL;
                     }
                 }
-                else if(type == VariantType::Double)
+                else if (type == VariantType::Double)
                 {
-//                    auto values = SortVariants<double>(dataHistory);
-//                    return new Variant(values.at(values.size()/2));
+                    //                    auto values = SortVariants<double>(dataHistory);
+                    //                    return new Variant(values.at(values.size()/2));
                 }
-                else if(type == VariantType::Int)
+                else if (type == VariantType::Int)
                 {
-//                    auto values = SortVariants<int>(dataHistory);
-//                    return new Variant(values.at(values.size()/2));
+                    //                    auto values = SortVariants<int>(dataHistory);
+                    //                    return new Variant(values.at(values.size()/2));
                 }
+
                 return MedianFilter::calculate(c);
             }
 
@@ -104,7 +113,7 @@ namespace armarx {
              * @brief This filter supports: Vector3, FramedDirection, FramedPosition
              * @return List of VariantTypes
              */
-            ParameterTypeList getSupportedTypes(const Ice::Current &c) const
+            ParameterTypeList getSupportedTypes(const Ice::Current& c) const
             {
                 ParameterTypeList result = MedianFilter::getSupportedTypes(c);
                 result.push_back(VariantType::Vector3);
diff --git a/source/RobotAPI/libraries/core/remoterobot/RemoteRobot.cpp b/source/RobotAPI/libraries/core/remoterobot/RemoteRobot.cpp
index a9754e47255936831ae22d95229c2cea78b3a5d3..a9007094e5e4430de94625917a1c60cbff1c7d08 100644
--- a/source/RobotAPI/libraries/core/remoterobot/RemoteRobot.cpp
+++ b/source/RobotAPI/libraries/core/remoterobot/RemoteRobot.cpp
@@ -17,375 +17,413 @@ using namespace boost;
 using namespace VirtualRobot;
 using namespace Eigen;
 
-namespace armarx{
-
-boost::recursive_mutex RemoteRobot::m;
-
-RemoteRobot::RemoteRobot(SharedRobotInterfacePrx robot) :
-    Robot(),
-    _robot(robot)
+namespace armarx
 {
-    _robot->ref();
-}
 
-RemoteRobot::~RemoteRobot()
-{
-    try
+    boost::recursive_mutex RemoteRobot::m;
+
+    RemoteRobot::RemoteRobot(SharedRobotInterfacePrx robot) :
+        Robot(),
+        _robot(robot)
     {
-        _robot->unref();
+        _robot->ref();
     }
-    catch(std::exception &e)
+
+    RemoteRobot::~RemoteRobot()
     {
-        ARMARX_DEBUG_S << "Unref of SharedRobot failed: " << e.what();
+        try
+        {
+            _robot->unref();
+        }
+        catch (std::exception& e)
+        {
+            ARMARX_DEBUG_S << "Unref of SharedRobot failed: " << e.what();
+        }
+        catch (...)
+        {
+            ARMARX_DEBUG_S << "Unref of SharedRobot failed: reason unknown";
+        }
+
     }
-    catch(...)
+
+    RobotNodePtr RemoteRobot::getRootNode()
     {
-        ARMARX_DEBUG_S << "Unref of SharedRobot failed: reason unknown";
-    }
+        if (!_root)
+        {
+            _root = RemoteRobot::createRemoteRobotNode(_robot->getRootNode(), shared_from_this());
+        }
 
-}
+        return _root;
+    }
 
-RobotNodePtr RemoteRobot::getRootNode()
-{
-    if (!_root)
-        _root = RemoteRobot::createRemoteRobotNode(_robot->getRootNode(),shared_from_this());
-    return _root;
-}
+    bool RemoteRobot::hasRobotNode(const string& robotNodeName)
+    {
+        if (_cachedNodes.find(name) == _cachedNodes.end())
+        {
+            return _robot->hasRobotNode(robotNodeName);
+        }
+        else
+        {
+            return true;
+        }
+    }
 
-bool RemoteRobot::hasRobotNode( const string &robotNodeName )
-{
-    if (_cachedNodes.find(name)==_cachedNodes.end())
-        return _robot->hasRobotNode(robotNodeName);
-    else
-        return true;
-}
 
+    bool RemoteRobot::hasRobotNode(RobotNodePtr robotNode)
+    {
+        return this->hasRobotNode(robotNode->getName());
+
+        /*
+         * This just does not work. because you cannot tell wheter RemoteRobotNode<RobotNodeRevolute> or another type is used
+         * perhaps you can infer the actual RobotNodeType somehow. Until now we just check for names which is
+         * much faster!
+         *
+        if  ( (_cachedNodes.find(name)==_cachedNodes.end()) || _robot->hasRobotNode(robotNode->getName())) {
+            shared_ptr<RemoteRobotNode> remoteNode(dynamic_pointer_cast<RemoteRobotNode>(robotNode));
+            if (! remoteNode) return false;
+
+            SharedRobotNodeInterfacePrx sharedNode = remoteNode->getSharedNode();
+            SharedRobotNodeInterfacePrx otherSharedNode = dynamic_pointer_cast<RemoteRobotNode>(this->getRobotNode(robotNodeName))->getSharedNode();
+            if (sharedNode == otherSharedNode)
+                return true;
+        }
 
-bool RemoteRobot::hasRobotNode( RobotNodePtr robotNode )
-{
-    return this->hasRobotNode(robotNode->getName());
-
-    /*
-     * This just does not work. because you cannot tell wheter RemoteRobotNode<RobotNodeRevolute> or another type is used
-     * perhaps you can infer the actual RobotNodeType somehow. Until now we just check for names which is
-     * much faster!
-     *
-    if  ( (_cachedNodes.find(name)==_cachedNodes.end()) || _robot->hasRobotNode(robotNode->getName())) {
-        shared_ptr<RemoteRobotNode> remoteNode(dynamic_pointer_cast<RemoteRobotNode>(robotNode));
-        if (! remoteNode) return false;
-
-        SharedRobotNodeInterfacePrx sharedNode = remoteNode->getSharedNode();
-        SharedRobotNodeInterfacePrx otherSharedNode = dynamic_pointer_cast<RemoteRobotNode>(this->getRobotNode(robotNodeName))->getSharedNode();
-        if (sharedNode == otherSharedNode)
-            return true;
+        return false;
+        */
     }
 
-    return false;
-    */
-}
 
+    RobotNodePtr RemoteRobot::getRobotNode(const string& robotNodeName)
+    {
+        DMES((format("Node: %1%") % robotNodeName));
 
-RobotNodePtr RemoteRobot::getRobotNode(const string &robotNodeName)
-{
-    DMES((format("Node: %1%") % robotNodeName));
+        if (_cachedNodes.find(robotNodeName) == _cachedNodes.end())
+        {
+            DMES("No cache hit");
+            _cachedNodes[robotNodeName] = RemoteRobot::createRemoteRobotNode(_robot->getRobotNode(robotNodeName),
+                                          shared_from_this());
+        }
+        else
+        {
+            DMES("Cache hit");
+        }
 
-    if (_cachedNodes.find(robotNodeName)==_cachedNodes.end())
-    {
-        DMES("No cache hit");
-        _cachedNodes[robotNodeName]=RemoteRobot::createRemoteRobotNode(_robot->getRobotNode(robotNodeName),
-                shared_from_this());
+        return _cachedNodes[robotNodeName];
     }
-    else
+
+    void RemoteRobot::getRobotNodes(vector< RobotNodePtr >& storeNodes, bool clearVector)
     {
-        DMES("Cache hit");
-    }
-    return _cachedNodes[robotNodeName];
-}
+        if (clearVector)
+        {
+            storeNodes.clear();
+        }
 
-void RemoteRobot::getRobotNodes(vector< RobotNodePtr > &storeNodes, bool clearVector)
-{
-    if (clearVector) storeNodes.clear();
-    NameList nodes = _robot->getRobotNodes();
-    BOOST_FOREACH(string name, nodes){
-        storeNodes.push_back(this->getRobotNode(name));
+        NameList nodes = _robot->getRobotNodes();
+        BOOST_FOREACH(string name, nodes)
+        {
+            storeNodes.push_back(this->getRobotNode(name));
+        }
     }
-}
 
-bool RemoteRobot::hasRobotNodeSet( const string &name )
-{
-    return _robot->hasRobotNodeSet(name);
-}
+    bool RemoteRobot::hasRobotNodeSet(const string& name)
+    {
+        return _robot->hasRobotNodeSet(name);
+    }
 
-RobotNodeSetPtr RemoteRobot::getRobotNodeSet(const string &nodeSetName)
-{
-    vector<RobotNodePtr> storeNodes;
-    RobotNodeSetInfoPtr info = _robot->getRobotNodeSet(nodeSetName);
-    return RobotNodeSet::createRobotNodeSet(
-            shared_from_this(),nodeSetName, info->names, info->rootName, info->tcpName);
-}
+    RobotNodeSetPtr RemoteRobot::getRobotNodeSet(const string& nodeSetName)
+    {
+        vector<RobotNodePtr> storeNodes;
+        RobotNodeSetInfoPtr info = _robot->getRobotNodeSet(nodeSetName);
+        return RobotNodeSet::createRobotNodeSet(
+                   shared_from_this(), nodeSetName, info->names, info->rootName, info->tcpName);
+    }
 
 
-void RemoteRobot::getRobotNodeSets(vector<RobotNodeSetPtr> &storeNodeSet)
-{
-    NameList sets= _robot->getRobotNodeSets();
+    void RemoteRobot::getRobotNodeSets(vector<RobotNodeSetPtr>& storeNodeSet)
+    {
+        NameList sets = _robot->getRobotNodeSets();
 
-    BOOST_FOREACH(string name, sets){
-        storeNodeSet.push_back(this->getRobotNodeSet(name));
+        BOOST_FOREACH(string name, sets)
+        {
+            storeNodeSet.push_back(this->getRobotNodeSet(name));
+        }
     }
-}
-
-Matrix4f RemoteRobot::getGlobalPose() const
-{
-    PosePtr p = PosePtr::dynamicCast(_robot->getGlobalPose());
-    return p->toEigen(); // convert to eigen first
-}
-
-string RemoteRobot::getName()
-{
-    return _robot->getName();
-}
 
-VirtualRobot::RobotNodePtr RemoteRobot::createLocalNode(SharedRobotNodeInterfacePrx remoteNode, std::vector<VirtualRobot::RobotNodePtr>& allNodes, std::map< VirtualRobot::RobotNodePtr, std::vector<std::string> > &childrenMap, RobotPtr robo)
-{
-    boost::recursive_mutex::scoped_lock cloneLock(m);
-    static int nonameCounter = 0;
-    if (!remoteNode || !robo)
+    Matrix4f RemoteRobot::getGlobalPose() const
     {
-        ARMARX_ERROR_S << " NULL data " << endl;
-        return VirtualRobot::RobotNodePtr();
+        PosePtr p = PosePtr::dynamicCast(_robot->getGlobalPose());
+        return p->toEigen(); // convert to eigen first
     }
-    VirtualRobot::RobotNodeFactoryPtr revoluteNodeFactory = VirtualRobot::RobotNodeFactory::fromName(VirtualRobot::RobotNodeRevoluteFactory::getName(), NULL);
-    VirtualRobot::RobotNodeFactoryPtr fixedNodeFactory = VirtualRobot::RobotNodeFactory::fromName(VirtualRobot::RobotNodeFixedFactory::getName(), NULL);
-    VirtualRobot::RobotNodeFactoryPtr prismaticNodeFactory = VirtualRobot::RobotNodeFactory::fromName(VirtualRobot::RobotNodePrismaticFactory::getName(), NULL);
-
-    Eigen::Matrix4f idMatrix = Eigen::Matrix4f::Identity();
-    Eigen::Vector3f idVec3 = Eigen::Vector3f::Zero();
-    std::string name = remoteNode->getName();
-    if (name.empty())
+
+    string RemoteRobot::getName()
     {
-        ARMARX_LOG_S << "Node without name!!!" << endl;
-        std::stringstream ss;
-        ss << "robot_node_" << nonameCounter;
-        nonameCounter++;
-        name = ss.str();
+        return _robot->getName();
     }
 
-    VirtualRobot::RobotNodePtr result;
-    PosePtr lTbase = PosePtr::dynamicCast(remoteNode->getLocalTransformation());
-    Eigen::Matrix4f localTransform = lTbase->toEigen();
-
-    //float jv = remoteNode->getJointValue();
-    float jvLo = remoteNode->getJointLimitLow();
-    float jvHi = remoteNode->getJointLimitHigh();
-    float jointOffset = 0;//remoteNode->getJointOffset();
-
-    JointType jt = remoteNode->getType();
-    switch (jt)
+    VirtualRobot::RobotNodePtr RemoteRobot::createLocalNode(SharedRobotNodeInterfacePrx remoteNode, std::vector<VirtualRobot::RobotNodePtr>& allNodes, std::map< VirtualRobot::RobotNodePtr, std::vector<std::string> >& childrenMap, RobotPtr robo)
     {
-        case ePrismatic:
+        boost::recursive_mutex::scoped_lock cloneLock(m);
+        static int nonameCounter = 0;
+
+        if (!remoteNode || !robo)
         {
-            Vector3Ptr axisBase = Vector3Ptr::dynamicCast(remoteNode->getJointTranslationDirection());
-            Eigen::Vector3f axis = axisBase->toEigen();
-            // convert axis to local coord system
-            Eigen::Vector4f result4f = Eigen::Vector4f::Zero();
-            result4f.segment(0,3) = axis;
-            PosePtr gp = PosePtr::dynamicCast(remoteNode->getGlobalPose());
-            result4f = gp->toEigen().inverse() * result4f;
-            axis = result4f.block(0,0,3,1);
-
-            result = prismaticNodeFactory->createRobotNode(robo, name, VirtualRobot::VisualizationNodePtr(), VirtualRobot::CollisionModelPtr(),
-            jvLo, jvHi, jointOffset, idMatrix, idVec3, axis);
+            ARMARX_ERROR_S << " NULL data " << endl;
+            return VirtualRobot::RobotNodePtr();
         }
-        break;
-        case eFixed:
-            result = fixedNodeFactory->createRobotNode(robo, name, VirtualRobot::VisualizationNodePtr(), VirtualRobot::CollisionModelPtr(), 0,
-            0, 0, localTransform, idVec3, idVec3);
-        break;
-        case eRevolute:
+
+        VirtualRobot::RobotNodeFactoryPtr revoluteNodeFactory = VirtualRobot::RobotNodeFactory::fromName(VirtualRobot::RobotNodeRevoluteFactory::getName(), NULL);
+        VirtualRobot::RobotNodeFactoryPtr fixedNodeFactory = VirtualRobot::RobotNodeFactory::fromName(VirtualRobot::RobotNodeFixedFactory::getName(), NULL);
+        VirtualRobot::RobotNodeFactoryPtr prismaticNodeFactory = VirtualRobot::RobotNodeFactory::fromName(VirtualRobot::RobotNodePrismaticFactory::getName(), NULL);
+
+        Eigen::Matrix4f idMatrix = Eigen::Matrix4f::Identity();
+        Eigen::Vector3f idVec3 = Eigen::Vector3f::Zero();
+        std::string name = remoteNode->getName();
+
+        if (name.empty())
         {
-            Vector3Ptr axisBase = Vector3Ptr::dynamicCast(remoteNode->getJointRotationAxis());
-            Eigen::Vector3f axis = axisBase->toEigen();
-            // convert axis to local coord system
-            Eigen::Vector4f result4f = Eigen::Vector4f::Zero();
-            result4f.segment(0,3) = axis;
-            PosePtr gp = PosePtr::dynamicCast(remoteNode->getGlobalPose());
-            result4f = gp->toEigen().inverse() * result4f;
-            axis = result4f.block(0,0,3,1);
-
-            result = revoluteNodeFactory->createRobotNode(robo, name, VirtualRobot::VisualizationNodePtr(), VirtualRobot::CollisionModelPtr(),
-            jvLo, jvHi, jointOffset, localTransform, axis, idVec3);
+            ARMARX_LOG_S << "Node without name!!!" << endl;
+            std::stringstream ss;
+            ss << "robot_node_" << nonameCounter;
+            nonameCounter++;
+            name = ss.str();
         }
-        break;
-        default:
-            ARMARX_ERROR_S << "JointType nyi..." << endl;
-            return VirtualRobot::RobotNodePtr();
-            break;
-    }
-    robo->registerRobotNode(result);
-    allNodes.push_back(result);
 
+        VirtualRobot::RobotNodePtr result;
+        PosePtr lTbase = PosePtr::dynamicCast(remoteNode->getLocalTransformation());
+        Eigen::Matrix4f localTransform = lTbase->toEigen();
 
-    // setup joint->nextNodes children
-    std::vector<std::string> childrenBase = remoteNode->getChildren();
-    std::vector<std::string> children;
+        //float jv = remoteNode->getJointValue();
+        float jvLo = remoteNode->getJointLimitLow();
+        float jvHi = remoteNode->getJointLimitHigh();
+        float jointOffset = 0;//remoteNode->getJointOffset();
 
-    // check for RobotNodes (sensors do also register as children!)
-    for (size_t i=0;i<childrenBase.size();i++)
-    {
-        if (_robot->hasRobotNode(childrenBase[i]))
+        JointType jt = remoteNode->getType();
+
+        switch (jt)
         {
-            SharedRobotNodeInterfacePrx rnRemote = _robot->getRobotNode(childrenBase[i]);
-            VirtualRobot::RobotNodePtr localNode = createLocalNode(rnRemote, allNodes, childrenMap, robo);
-            /* boost::shared_ptr< RemoteRobotNode<VirtualRobotNodeType> > rnRemote = boost::dynamic_pointer_cast<RemoteRobotNode>(rnRemoteBase);
-            if (!rnRemote)
+            case ePrismatic:
             {
-                ARMARX_ERROR_S << "RemoteRobot does not know robot node with name " << children[i] << endl;
-                continue;
-            }*/
+                Vector3Ptr axisBase = Vector3Ptr::dynamicCast(remoteNode->getJointTranslationDirection());
+                Eigen::Vector3f axis = axisBase->toEigen();
+                // convert axis to local coord system
+                Eigen::Vector4f result4f = Eigen::Vector4f::Zero();
+                result4f.segment(0, 3) = axis;
+                PosePtr gp = PosePtr::dynamicCast(remoteNode->getGlobalPose());
+                result4f = gp->toEigen().inverse() * result4f;
+                axis = result4f.block(0, 0, 3, 1);
+
+                result = prismaticNodeFactory->createRobotNode(robo, name, VirtualRobot::VisualizationNodePtr(), VirtualRobot::CollisionModelPtr(),
+                         jvLo, jvHi, jointOffset, idMatrix, idVec3, axis);
+            }
+            break;
 
+            case eFixed:
+                result = fixedNodeFactory->createRobotNode(robo, name, VirtualRobot::VisualizationNodePtr(), VirtualRobot::CollisionModelPtr(), 0,
+                         0, 0, localTransform, idVec3, idVec3);
+                break;
 
-            if (!localNode)
+            case eRevolute:
             {
-                ARMARX_ERROR_S << "Could not create local node: " << children[i] << endl;
-                continue;
+                Vector3Ptr axisBase = Vector3Ptr::dynamicCast(remoteNode->getJointRotationAxis());
+                Eigen::Vector3f axis = axisBase->toEigen();
+                // convert axis to local coord system
+                Eigen::Vector4f result4f = Eigen::Vector4f::Zero();
+                result4f.segment(0, 3) = axis;
+                PosePtr gp = PosePtr::dynamicCast(remoteNode->getGlobalPose());
+                result4f = gp->toEigen().inverse() * result4f;
+                axis = result4f.block(0, 0, 3, 1);
+
+                result = revoluteNodeFactory->createRobotNode(robo, name, VirtualRobot::VisualizationNodePtr(), VirtualRobot::CollisionModelPtr(),
+                         jvLo, jvHi, jointOffset, localTransform, axis, idVec3);
             }
-            children.push_back(childrenBase[i]);
+            break;
+
+            default:
+                ARMARX_ERROR_S << "JointType nyi..." << endl;
+                return VirtualRobot::RobotNodePtr();
+                break;
         }
-    }
-    childrenMap[result] = children;
-    return result;
-}
 
-VirtualRobot::RobotPtr RemoteRobot::createLocalClone()
-{
-    //ARMARX_IMPORTANT_S << "RemoteRobot local clone" << flush;
-    boost::recursive_mutex::scoped_lock cloneLock(m);
-    std::string robotType = getName();
-    std::string robotName = getName();
-    VirtualRobot::RobotPtr robo(new VirtualRobot::LocalRobot(robotName,robotType));
+        robo->registerRobotNode(result);
+        allNodes.push_back(result);
 
-    //RobotNodePtr
-    SharedRobotNodeInterfacePrx root = _robot->getRootNode();
 
-    std::vector<VirtualRobot::RobotNodePtr> allNodes;
-    std::map< VirtualRobot::RobotNodePtr, std::vector<std::string> > childrenMap;
+        // setup joint->nextNodes children
+        std::vector<std::string> childrenBase = remoteNode->getChildren();
+        std::vector<std::string> children;
 
-    VirtualRobot::RobotNodePtr rootLocal = createLocalNode(root, allNodes, childrenMap, robo);
+        // check for RobotNodes (sensors do also register as children!)
+        for (size_t i = 0; i < childrenBase.size(); i++)
+        {
+            if (_robot->hasRobotNode(childrenBase[i]))
+            {
+                SharedRobotNodeInterfacePrx rnRemote = _robot->getRobotNode(childrenBase[i]);
+                VirtualRobot::RobotNodePtr localNode = createLocalNode(rnRemote, allNodes, childrenMap, robo);
+                /* boost::shared_ptr< RemoteRobotNode<VirtualRobotNodeType> > rnRemote = boost::dynamic_pointer_cast<RemoteRobotNode>(rnRemoteBase);
+                if (!rnRemote)
+                {
+                    ARMARX_ERROR_S << "RemoteRobot does not know robot node with name " << children[i] << endl;
+                    continue;
+                }*/
+
+
+                if (!localNode)
+                {
+                    ARMARX_ERROR_S << "Could not create local node: " << children[i] << endl;
+                    continue;
+                }
+
+                children.push_back(childrenBase[i]);
+            }
+        }
 
-    bool res = VirtualRobot::RobotFactory::initializeRobot(robo, allNodes, childrenMap, rootLocal);
-    if (!res)
-    {
-        ARMARX_ERROR_S << "Failed to initialize local robot..." << endl;
-        return VirtualRobot::RobotPtr();
+        childrenMap[result] = children;
+        return result;
     }
 
-    // clone rns
-    std::vector<std::string> rns = _robot->getRobotNodeSets();
-    for (size_t i=0;i<rns.size();i++)
+    VirtualRobot::RobotPtr RemoteRobot::createLocalClone()
     {
-        RobotNodeSetInfoPtr rnsInfo = _robot->getRobotNodeSet(rns[i]);
-        RobotNodeSet::createRobotNodeSet(robo,rnsInfo->name,rnsInfo->names,rnsInfo->rootName,rnsInfo->tcpName,true);
-    }
-    //ARMARX_IMPORTANT_S << "RemoteRobot local clone end" << flush;
-    auto pose = PosePtr::dynamicCast(_robot->getGlobalPose());
-    robo->setGlobalPose(pose->toEigen());
-    return robo;
-}
+        //ARMARX_IMPORTANT_S << "RemoteRobot local clone" << flush;
+        boost::recursive_mutex::scoped_lock cloneLock(m);
+        std::string robotType = getName();
+        std::string robotName = getName();
+        VirtualRobot::RobotPtr robo(new VirtualRobot::LocalRobot(robotName, robotType));
 
-VirtualRobot::RobotPtr RemoteRobot::createLocalClone(RobotStateComponentInterfacePrx robotStatePrx, const string &filename)
-{
-    return createLocalClone(robotStatePrx->getSynchronizedRobot(), filename);
-}
+        //RobotNodePtr
+        SharedRobotNodeInterfacePrx root = _robot->getRootNode();
 
-RobotPtr RemoteRobot::createLocalClone(SharedRobotInterfacePrx sharedRobotPrx, const string &filename)
-{
-    boost::recursive_mutex::scoped_lock cloneLock(m);
-    ARMARX_VERBOSE_S << "Creating local clone of remote robot (filename:" << filename << ")" << endl;
-    VirtualRobot::RobotPtr result;
+        std::vector<VirtualRobot::RobotNodePtr> allNodes;
+        std::map< VirtualRobot::RobotNodePtr, std::vector<std::string> > childrenMap;
+
+        VirtualRobot::RobotNodePtr rootLocal = createLocalNode(root, allNodes, childrenMap, robo);
+
+        bool res = VirtualRobot::RobotFactory::initializeRobot(robo, allNodes, childrenMap, rootLocal);
+
+        if (!res)
+        {
+            ARMARX_ERROR_S << "Failed to initialize local robot..." << endl;
+            return VirtualRobot::RobotPtr();
+        }
+
+        // clone rns
+        std::vector<std::string> rns = _robot->getRobotNodeSets();
+
+        for (size_t i = 0; i < rns.size(); i++)
+        {
+            RobotNodeSetInfoPtr rnsInfo = _robot->getRobotNodeSet(rns[i]);
+            RobotNodeSet::createRobotNodeSet(robo, rnsInfo->name, rnsInfo->names, rnsInfo->rootName, rnsInfo->tcpName, true);
+        }
+
+        //ARMARX_IMPORTANT_S << "RemoteRobot local clone end" << flush;
+        auto pose = PosePtr::dynamicCast(_robot->getGlobalPose());
+        robo->setGlobalPose(pose->toEigen());
+        return robo;
+    }
 
-    if (!sharedRobotPrx)
+    VirtualRobot::RobotPtr RemoteRobot::createLocalClone(RobotStateComponentInterfacePrx robotStatePrx, const string& filename)
     {
-        ARMARX_ERROR_S << "NULL sharedRobotPrx. Aborting..." << endl;
-        return result;
+        return createLocalClone(robotStatePrx->getSynchronizedRobot(), filename);
     }
 
-    if (filename.empty())
+    RobotPtr RemoteRobot::createLocalClone(SharedRobotInterfacePrx sharedRobotPrx, const string& filename)
     {
-        RemoteRobotPtr rob(new RemoteRobot(sharedRobotPrx));
-        result = rob->createLocalClone();
-        if (!result)
+        boost::recursive_mutex::scoped_lock cloneLock(m);
+        ARMARX_VERBOSE_S << "Creating local clone of remote robot (filename:" << filename << ")" << endl;
+        VirtualRobot::RobotPtr result;
+
+        if (!sharedRobotPrx)
         {
-            ARMARX_ERROR_S << "Could not create local clone. Aborting..." << endl;
+            ARMARX_ERROR_S << "NULL sharedRobotPrx. Aborting..." << endl;
             return result;
         }
-    } else
-    {
-        result = RobotIO::loadRobot(filename);
-        if (!result)
+
+        if (filename.empty())
         {
-            ARMARX_ERROR_S << "Could not load robot file " << filename << ". Aborting..." << endl;
-            return result;
+            RemoteRobotPtr rob(new RemoteRobot(sharedRobotPrx));
+            result = rob->createLocalClone();
+
+            if (!result)
+            {
+                ARMARX_ERROR_S << "Could not create local clone. Aborting..." << endl;
+                return result;
+            }
         }
-    }
-    synchronizeLocalClone(result,sharedRobotPrx);
-    return result;
-}
+        else
+        {
+            result = RobotIO::loadRobot(filename);
 
-bool RemoteRobot::synchronizeLocalClone(VirtualRobot::RobotPtr robot, RobotStateComponentInterfacePrx robotStatePrx)
-{
-    return synchronizeLocalClone(robot, robotStatePrx->getSynchronizedRobot());
-}
+            if (!result)
+            {
+                ARMARX_ERROR_S << "Could not load robot file " << filename << ". Aborting..." << endl;
+                return result;
+            }
+        }
 
-bool RemoteRobot::synchronizeLocalClone(VirtualRobot::RobotPtr robot, SharedRobotInterfacePrx sharedRobotPrx)
-{
-    if (!sharedRobotPrx || !robot)
+        synchronizeLocalClone(result, sharedRobotPrx);
+        return result;
+    }
+
+    bool RemoteRobot::synchronizeLocalClone(VirtualRobot::RobotPtr robot, RobotStateComponentInterfacePrx robotStatePrx)
     {
-        ARMARX_ERROR_S << "NULL data. Aborting..." << endl;
-        return false;
+        return synchronizeLocalClone(robot, robotStatePrx->getSynchronizedRobot());
     }
-    RobotConfigPtr c(new RobotConfig(robot,"synchronizeLocalClone"));
-    NameValueMap jv = sharedRobotPrx->getConfig();
-    for ( NameValueMap::const_iterator it = jv.begin(); it!=jv.end(); it++ )
+
+    bool RemoteRobot::synchronizeLocalClone(VirtualRobot::RobotPtr robot, SharedRobotInterfacePrx sharedRobotPrx)
     {
-        // joint values
-        const std::string& jointName = it->first;
-        float jointAngle = it->second;
-        if (!c->setConfig(jointName,jointAngle))
+        if (!sharedRobotPrx || !robot)
         {
-            ARMARX_WARNING_S << "Joint not known in local copy:" << jointName << ". Skipping..." << endl;
+            ARMARX_ERROR_S << "NULL data. Aborting..." << endl;
+            return false;
+        }
+
+        RobotConfigPtr c(new RobotConfig(robot, "synchronizeLocalClone"));
+        NameValueMap jv = sharedRobotPrx->getConfig();
+
+        for (NameValueMap::const_iterator it = jv.begin(); it != jv.end(); it++)
+        {
+            // joint values
+            const std::string& jointName = it->first;
+            float jointAngle = it->second;
+
+            if (!c->setConfig(jointName, jointAngle))
+            {
+                ARMARX_WARNING_S << "Joint not known in local copy:" << jointName << ". Skipping..." << endl;
+            }
         }
+
+        robot->setConfig(c);
+        auto pose = PosePtr::dynamicCast(sharedRobotPrx->getGlobalPose());
+        robot->setGlobalPose(pose->toEigen());
+        return true;
     }
-    robot->setConfig(c);
-    auto pose = PosePtr::dynamicCast(sharedRobotPrx->getGlobalPose());
-    robot->setGlobalPose(pose->toEigen());
-    return true;
-}
 
 
-// Private (unused methods)
+    // Private (unused methods)
 
-bool RemoteRobot::hasEndEffector(const string& endEffectorName)
-{
-    return false;
-}
+    bool RemoteRobot::hasEndEffector(const string& endEffectorName)
+    {
+        return false;
+    }
 
-EndEffectorPtr RemoteRobot::getEndEffector(const string& endEffectorName)
-{
-    return EndEffectorPtr();
-}
+    EndEffectorPtr RemoteRobot::getEndEffector(const string& endEffectorName)
+    {
+        return EndEffectorPtr();
+    }
 
-void RemoteRobot::getEndEffectors(vector<EndEffectorPtr> &storeEEF){}
-void RemoteRobot::setRootNode(RobotNodePtr node){}
-void RemoteRobot::registerRobotNode(RobotNodePtr node){}
-void RemoteRobot::deregisterRobotNode(RobotNodePtr node){}
-void RemoteRobot::registerRobotNodeSet(RobotNodeSetPtr nodeSet){}
-void RemoteRobot::deregisterRobotNodeSet(RobotNodeSetPtr nodeSet){}
-void RemoteRobot::registerEndEffector(EndEffectorPtr endEffector){}
+    void RemoteRobot::getEndEffectors(vector<EndEffectorPtr>& storeEEF) {}
+    void RemoteRobot::setRootNode(RobotNodePtr node) {}
+    void RemoteRobot::registerRobotNode(RobotNodePtr node) {}
+    void RemoteRobot::deregisterRobotNode(RobotNodePtr node) {}
+    void RemoteRobot::registerRobotNodeSet(RobotNodeSetPtr nodeSet) {}
+    void RemoteRobot::deregisterRobotNodeSet(RobotNodeSetPtr nodeSet) {}
+    void RemoteRobot::registerEndEffector(EndEffectorPtr endEffector) {}
 
-void RemoteRobot::setGlobalPose(const Eigen::Matrix4f &globalPose, bool applyValues)
-{
-    if(_robot)
-        _robot->setGlobalPose(new Pose(globalPose));
-}
+    void RemoteRobot::setGlobalPose(const Eigen::Matrix4f& globalPose, bool applyValues)
+    {
+        if (_robot)
+        {
+            _robot->setGlobalPose(new Pose(globalPose));
+        }
+    }
 
 }
diff --git a/source/RobotAPI/libraries/core/remoterobot/RemoteRobot.h b/source/RobotAPI/libraries/core/remoterobot/RemoteRobot.h
index e251f861237890be99ebedf9890c638a0a466813..64bca72366ea03d0c8f6399d93352f1433f63888 100644
--- a/source/RobotAPI/libraries/core/remoterobot/RemoteRobot.h
+++ b/source/RobotAPI/libraries/core/remoterobot/RemoteRobot.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    RobotAPI::
  * @author     (stefan dot ulbrich at kit dot edu)
  * @date
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -73,7 +72,7 @@ namespace armarx
      */
     template<class VirtualRobotNodeType>
     class RemoteRobotNode :
-            public VirtualRobotNodeType
+        public VirtualRobotNodeType
     {
         friend struct RemoteRobotNodeInitializer<VirtualRobotNodeType>;
 
@@ -82,7 +81,7 @@ namespace armarx
             _node(node)
         {
             _node->ref();
-            this->name=_node->getName();
+            this->name = _node->getName();
             this->robot = vr;
             _node->getJointValueOffest();
             setJointLimits(_node->getJointLimitLow(), _node->getJointLimitHigh());
@@ -103,9 +102,9 @@ namespace armarx
         virtual Eigen::Matrix4f getGlobalPose() const;
         virtual Eigen::Matrix4f getPoseInRootFrame() const;
         virtual Eigen::Vector3f getPositionInRootFrame() const;
-        virtual bool hasChildNode(const std::string &child, bool recursive = false) const;
+        virtual bool hasChildNode(const std::string& child, bool recursive = false) const;
 
-        virtual std::vector<VirtualRobot::RobotNodePtr> getAllParents( VirtualRobot::RobotNodeSetPtr rns );
+        virtual std::vector<VirtualRobot::RobotNodePtr> getAllParents(VirtualRobot::RobotNodeSetPtr rns);
         virtual VirtualRobot::RobotNodePtr getParent();
         inline SharedRobotNodeInterfacePrx getSharedRobotNode()
         {
@@ -118,20 +117,20 @@ namespace armarx
         ///////////////////////// SETUP ////////////////////////////////////
         virtual void setJointLimits(float lo, float hi);
         //virtual void setPostJointTransformation(const Eigen::Matrix4f &trafo);
-        virtual void setLocalTransformation(const Eigen::Matrix4f &trafo);
+        virtual void setLocalTransformation(const Eigen::Matrix4f& trafo);
 
         virtual std::string getParentName() const;
         virtual std::vector< VirtualRobot::SceneObjectPtr> getChildren() const;
 
         virtual void updateTransformationMatrices();
-        virtual void updateTransformationMatrices(const Eigen::Matrix4f &globalPose);
+        virtual void updateTransformationMatrices(const Eigen::Matrix4f& globalPose);
 
 
         virtual bool hasChildNode(const VirtualRobot::RobotNodePtr child, bool recursive = false) const;
         virtual void addChildNode(VirtualRobot::RobotNodePtr child);
         virtual bool initialize(VirtualRobot::RobotNodePtr parent, bool initializeChildren = false);
         virtual void reset();
-        virtual void setGlobalPose( const Eigen::Matrix4f &pose );
+        virtual void setGlobalPose(const Eigen::Matrix4f& pose);
         virtual void setJointValue(float q, bool updateTransformations = true, bool clampToLimits = true);
 
         SharedRobotNodeInterfacePrx _node;
@@ -144,24 +143,24 @@ namespace armarx
     class RemoteRobot : public VirtualRobot::Robot
     {
         template<class T>
-        friend void boost::checked_delete(T *);
+        friend void boost::checked_delete(T*);
     protected:
         ~RemoteRobot();
     public:
-        RemoteRobot (SharedRobotInterfacePrx robot);
+        RemoteRobot(SharedRobotInterfacePrx robot);
 
 
         virtual VirtualRobot::RobotNodePtr getRootNode();
 
-        virtual bool hasRobotNode( const std::string &robotNodeName );
-        virtual bool hasRobotNode( VirtualRobot::RobotNodePtr );
+        virtual bool hasRobotNode(const std::string& robotNodeName);
+        virtual bool hasRobotNode(VirtualRobot::RobotNodePtr);
 
-        virtual VirtualRobot::RobotNodePtr getRobotNode(const std::string &robotNodeName);
-        virtual void getRobotNodes(std::vector< VirtualRobot::RobotNodePtr > &storeNodes, bool clearVector=true);
+        virtual VirtualRobot::RobotNodePtr getRobotNode(const std::string& robotNodeName);
+        virtual void getRobotNodes(std::vector< VirtualRobot::RobotNodePtr >& storeNodes, bool clearVector = true);
 
-        virtual bool hasRobotNodeSet( const std::string &name );
-        virtual VirtualRobot::RobotNodeSetPtr getRobotNodeSet(const std::string &nodeSetName);
-        virtual void getRobotNodeSets(std::vector<VirtualRobot::RobotNodeSetPtr> &storeNodeSet);
+        virtual bool hasRobotNodeSet(const std::string& name);
+        virtual VirtualRobot::RobotNodeSetPtr getRobotNodeSet(const std::string& nodeSetName);
+        virtual void getRobotNodeSets(std::vector<VirtualRobot::RobotNodeSetPtr>& storeNodeSet);
 
         /**
          *
@@ -186,9 +185,9 @@ namespace armarx
               In order to get a fully featured robot model you can pass a filename to VirtualRobot::Robot,
               but then you need to make sure that the loaded model is identical to the model of the remote robot (otherwise errors will occur).
             */
-        static VirtualRobot::RobotPtr createLocalClone(RobotStateComponentInterfacePrx robotStatePrx, const std::string &filename=std::string());
+        static VirtualRobot::RobotPtr createLocalClone(RobotStateComponentInterfacePrx robotStatePrx, const std::string& filename = std::string());
 
-        static VirtualRobot::RobotPtr createLocalClone(SharedRobotInterfacePrx sharedRobotPrx, const std::string &filename=std::string());
+        static VirtualRobot::RobotPtr createLocalClone(SharedRobotInterfacePrx sharedRobotPrx, const std::string& filename = std::string());
 
         /*!
                 Use this method to synchronize (i.e. copy the joint values) from the remote robot to the local clone.
@@ -210,7 +209,7 @@ namespace armarx
         /// Not implemented yet
         virtual VirtualRobot::EndEffectorPtr getEndEffector(const std::string& endEffectorName);
         /// Not implemented yet
-        virtual void getEndEffectors(std::vector<VirtualRobot::EndEffectorPtr> &storeEEF);
+        virtual void getEndEffectors(std::vector<VirtualRobot::EndEffectorPtr>& storeEEF);
 
         /// Not implemented yet
         virtual void setRootNode(VirtualRobot::RobotNodePtr node);
@@ -229,9 +228,9 @@ namespace armarx
          * @param globalPose new global pose
          * @param applyValues No effect. Will be always applied.
          */
-        virtual void setGlobalPose(const Eigen::Matrix4f &globalPose, bool applyValues = true);
+        virtual void setGlobalPose(const Eigen::Matrix4f& globalPose, bool applyValues = true);
 
-        VirtualRobot::RobotNodePtr createLocalNode(SharedRobotNodeInterfacePrx remoteNode, std::vector<VirtualRobot::RobotNodePtr> &allNodes, std::map<VirtualRobot::RobotNodePtr, std::vector<std::string> > &childrenMap, VirtualRobot::RobotPtr robo);
+        VirtualRobot::RobotNodePtr createLocalNode(SharedRobotNodeInterfacePrx remoteNode, std::vector<VirtualRobot::RobotNodePtr>& allNodes, std::map<VirtualRobot::RobotNodePtr, std::vector<std::string> >& childrenMap, VirtualRobot::RobotPtr robo);
 
     protected:
         SharedRobotInterfacePrx _robot;
diff --git a/source/RobotAPI/libraries/core/remoterobot/RemoteRobotNode.cpp b/source/RobotAPI/libraries/core/remoterobot/RemoteRobotNode.cpp
index ad62ae99d68c0cfbdaa0151255568783af9086b9..0e08d9dfe215b65a413f7e6303b7c8e044bfb348 100644
--- a/source/RobotAPI/libraries/core/remoterobot/RemoteRobotNode.cpp
+++ b/source/RobotAPI/libraries/core/remoterobot/RemoteRobotNode.cpp
@@ -4,191 +4,218 @@
 
 #include <VirtualRobot/VirtualRobot.h>
 
-#include <Core/interface/core/BasicTypes.h>
+#include <ArmarXCore/interface/core/BasicTypes.h>
 
 namespace armarx
 {
 
-using namespace std;
-using namespace boost;
-using namespace VirtualRobot;
-using namespace Eigen;
+    using namespace std;
+    using namespace boost;
+    using namespace VirtualRobot;
+    using namespace Eigen;
 
-RobotNodePtr RemoteRobot::createRemoteRobotNode(SharedRobotNodeInterfacePrx node, RobotPtr robot)
-{
-    switch (node->getType()) {
-        case ePrismatic:
-            return RobotNodePtr(new RemoteRobotNode<RobotNodePrismatic>(node,robot));
-        case eRevolute:
-            return RobotNodePtr(new RemoteRobotNode<RobotNodeRevolute>(node,robot));
-        case eFixed:
-            return RobotNodePtr(new RemoteRobotNode<RobotNodeFixed>(node,robot));
-        default:
-            break; // thow an exception
-    }
-    return RobotNodePtr();
-}
+    RobotNodePtr RemoteRobot::createRemoteRobotNode(SharedRobotNodeInterfacePrx node, RobotPtr robot)
+    {
+        switch (node->getType())
+        {
+            case ePrismatic:
+                return RobotNodePtr(new RemoteRobotNode<RobotNodePrismatic>(node, robot));
 
+            case eRevolute:
+                return RobotNodePtr(new RemoteRobotNode<RobotNodeRevolute>(node, robot));
 
-template<>
-void RemoteRobotNodeInitializer<VirtualRobot::RobotNodeRevolute>::initialize(RemoteRobotNode<VirtualRobot::RobotNodeRevolute>* remoteNode)
-{
-    // set rotation axis
-    remoteNode->jointRotationAxis = remoteNode->getGlobalPose().block<3,3>(0,0).inverse() * Vector3Ptr::dynamicCast(remoteNode->_node->getJointRotationAxis())->toEigen();
-}
+            case eFixed:
+                return RobotNodePtr(new RemoteRobotNode<RobotNodeFixed>(node, robot));
 
-template<>
-void RemoteRobotNodeInitializer<VirtualRobot::RobotNodePrismatic>::initialize(RemoteRobotNode<VirtualRobot::RobotNodePrismatic>* remoteNode)
-{
-    // set translation direction
-    remoteNode->jointTranslationDirection = remoteNode->getGlobalPose().block<3,3>(0,0).inverse() * Vector3Ptr::dynamicCast(remoteNode->_node->getJointTranslationDirection())->toEigen();
-}
+            default:
+                break; // thow an exception
+        }
 
-template<>
-void RemoteRobotNodeInitializer<VirtualRobot::RobotNodeFixed>::initialize(RemoteRobotNode<VirtualRobot::RobotNodeFixed>* remoteNode)
-{
-    // nothing to do for fixed joints
-}
+        return RobotNodePtr();
+    }
 
 
-template<class RobotNodeType>
-RemoteRobotNode<RobotNodeType>::~RemoteRobotNode(){
-    try
+    template<>
+    void RemoteRobotNodeInitializer<VirtualRobot::RobotNodeRevolute>::initialize(RemoteRobotNode<VirtualRobot::RobotNodeRevolute>* remoteNode)
     {
-        _node->unref();
+        // set rotation axis
+        remoteNode->jointRotationAxis = remoteNode->getGlobalPose().block<3, 3>(0, 0).inverse() * Vector3Ptr::dynamicCast(remoteNode->_node->getJointRotationAxis())->toEigen();
     }
-    catch(std::exception &e)
+
+    template<>
+    void RemoteRobotNodeInitializer<VirtualRobot::RobotNodePrismatic>::initialize(RemoteRobotNode<VirtualRobot::RobotNodePrismatic>* remoteNode)
     {
-        ARMARX_DEBUG_S << "Unref of SharedRobotNode failed: " << e.what();
+        // set translation direction
+        remoteNode->jointTranslationDirection = remoteNode->getGlobalPose().block<3, 3>(0, 0).inverse() * Vector3Ptr::dynamicCast(remoteNode->_node->getJointTranslationDirection())->toEigen();
     }
-    catch(...)
+
+    template<>
+    void RemoteRobotNodeInitializer<VirtualRobot::RobotNodeFixed>::initialize(RemoteRobotNode<VirtualRobot::RobotNodeFixed>* remoteNode)
     {
-        ARMARX_DEBUG_S << "Unref of SharedRobotNode failed: reason unknown";
+        // nothing to do for fixed joints
     }
-}
 
-template<class RobotNodeType>
-float RemoteRobotNode<RobotNodeType>::getJointValue() const{
-    return _node->getJointValue();
-}
 
-template<class RobotNodeType>
-float RemoteRobotNode<RobotNodeType>::getJointLimitHi() const
-{
-    return _node->getJointLimitHigh();
-}
-template<class RobotNodeType>
-float RemoteRobotNode<RobotNodeType>::getJointLimitLo() const
-{
-    return _node->getJointLimitLow();
-}
-/*
-template<class RobotNodeType>
-Eigen::Matrix4f RemoteRobotNode<RobotNodeType>::getPostJointTransformation(){
-	return PosePtr::dynamicCast(_node->getPostJointTransformation())->toEigen();
-}*/
-
-template<class RobotNodeType>
-Eigen::Matrix4f RemoteRobotNode<RobotNodeType>::getLocalTransformation(){
-	return PosePtr::dynamicCast(_node->getLocalTransformation())->toEigen();
-}
+    template<class RobotNodeType>
+    RemoteRobotNode<RobotNodeType>::~RemoteRobotNode()
+    {
+        try
+        {
+            _node->unref();
+        }
+        catch (std::exception& e)
+        {
+            ARMARX_DEBUG_S << "Unref of SharedRobotNode failed: " << e.what();
+        }
+        catch (...)
+        {
+            ARMARX_DEBUG_S << "Unref of SharedRobotNode failed: reason unknown";
+        }
+    }
 
-template<class RobotNodeType>
-Eigen::Matrix4f RemoteRobotNode<RobotNodeType>::getGlobalPose() const {
-    return FramedPosePtr::dynamicCast(_node->getGlobalPose())->toEigen();
-}
-template<class RobotNodeType>
-Eigen::Matrix4f RemoteRobotNode<RobotNodeType>::getPoseInRootFrame() const
-{
-    return FramedPosePtr::dynamicCast(_node->getPoseInRootFrame())->toEigen();
-}
+    template<class RobotNodeType>
+    float RemoteRobotNode<RobotNodeType>::getJointValue() const
+    {
+        return _node->getJointValue();
+    }
 
-template<class RobotNodeType>
-Eigen::Vector3f RemoteRobotNode<RobotNodeType>::getPositionInRootFrame() const
-{
-    Vector3Ptr pos = Vector3Ptr::dynamicCast(_node->getPoseInRootFrame()->position);
-    ARMARX_CHECK_EXPRESSION(pos);
-    return pos->toEigen();
-}
+    template<class RobotNodeType>
+    float RemoteRobotNode<RobotNodeType>::getJointLimitHi() const
+    {
+        return _node->getJointLimitHigh();
+    }
+    template<class RobotNodeType>
+    float RemoteRobotNode<RobotNodeType>::getJointLimitLo() const
+    {
+        return _node->getJointLimitLow();
+    }
+    /*
+    template<class RobotNodeType>
+    Eigen::Matrix4f RemoteRobotNode<RobotNodeType>::getPostJointTransformation(){
+        return PosePtr::dynamicCast(_node->getPostJointTransformation())->toEigen();
+    }*/
+
+    template<class RobotNodeType>
+    Eigen::Matrix4f RemoteRobotNode<RobotNodeType>::getLocalTransformation()
+    {
+        return PosePtr::dynamicCast(_node->getLocalTransformation())->toEigen();
+    }
 
-template<class RobotNodeType>
-bool RemoteRobotNode<RobotNodeType>::hasChildNode(const RobotNodePtr child, bool recursive) const{
-	return false;
-}
-template<class RobotNodeType>
-bool RemoteRobotNode<RobotNodeType>::hasChildNode(const std::string &child, bool recursive) const{
-	return _node->hasChild(child,recursive);
-}
+    template<class RobotNodeType>
+    Eigen::Matrix4f RemoteRobotNode<RobotNodeType>::getGlobalPose() const
+    {
+        return FramedPosePtr::dynamicCast(_node->getGlobalPose())->toEigen();
+    }
+    template<class RobotNodeType>
+    Eigen::Matrix4f RemoteRobotNode<RobotNodeType>::getPoseInRootFrame() const
+    {
+        return FramedPosePtr::dynamicCast(_node->getPoseInRootFrame())->toEigen();
+    }
 
-template<class RobotNodeType>
-void RemoteRobotNode<RobotNodeType>::setJointLimits(float lo, float hi){
-}
+    template<class RobotNodeType>
+    Eigen::Vector3f RemoteRobotNode<RobotNodeType>::getPositionInRootFrame() const
+    {
+        Vector3Ptr pos = Vector3Ptr::dynamicCast(_node->getPoseInRootFrame()->position);
+        ARMARX_CHECK_EXPRESSION(pos);
+        return pos->toEigen();
+    }
 
-template<class RobotNodeType>
-vector<RobotNodePtr> RemoteRobotNode<RobotNodeType>::getAllParents( RobotNodeSetPtr rns ){
-	NameList nodes = _node->getAllParents(rns->getName());
-	vector<RobotNodePtr> result;
-	RobotPtr robot = this->robot.lock();
+    template<class RobotNodeType>
+    bool RemoteRobotNode<RobotNodeType>::hasChildNode(const RobotNodePtr child, bool recursive) const
+    {
+        return false;
+    }
+    template<class RobotNodeType>
+    bool RemoteRobotNode<RobotNodeType>::hasChildNode(const std::string& child, bool recursive) const
+    {
+        return _node->hasChild(child, recursive);
+    }
 
-	BOOST_FOREACH(string name, nodes){
-		result.push_back(robot->getRobotNode(name));
-	}
-	return result;
-}
+    template<class RobotNodeType>
+    void RemoteRobotNode<RobotNodeType>::setJointLimits(float lo, float hi)
+    {
+    }
 
-template<class RobotNodeType>
-RobotNodePtr RemoteRobotNode<RobotNodeType>::getParent(){
-	return this->robot.lock()->getRobotNode(_node->getParent());
-}
-/*
-template<class RobotNodeType>
-void RemoteRobotNode<RobotNodeType>::setPostJointTransformation(const Eigen::Matrix4f &trafo){
-}*/
-template<class RobotNodeType>
-void RemoteRobotNode<RobotNodeType>::setLocalTransformation(const Eigen::Matrix4f &trafo){
-}
-template<class RobotNodeType>
-std::vector<std::string> RemoteRobotNode<RobotNodeType>::getChildrenNames() const{
-	return _node->getChildren();
-}
-template<class RobotNodeType>
-std::string RemoteRobotNode<RobotNodeType>::getParentName() const{
-	return _node->getParent();
-}
-template<class RobotNodeType>
-std::vector<SceneObjectPtr> RemoteRobotNode<RobotNodeType>::getChildren() const{
-	NameList nodes = _node->getChildren();
-	vector<SceneObjectPtr> result;
-	BOOST_FOREACH(string name, nodes){
-		result.push_back(this->robot.lock()->getRobotNode(name));
-	}
-	return result;
-}
+    template<class RobotNodeType>
+    vector<RobotNodePtr> RemoteRobotNode<RobotNodeType>::getAllParents(RobotNodeSetPtr rns)
+    {
+        NameList nodes = _node->getAllParents(rns->getName());
+        vector<RobotNodePtr> result;
+        RobotPtr robot = this->robot.lock();
+
+        BOOST_FOREACH(string name, nodes)
+        {
+            result.push_back(robot->getRobotNode(name));
+        }
+        return result;
+    }
+
+    template<class RobotNodeType>
+    RobotNodePtr RemoteRobotNode<RobotNodeType>::getParent()
+    {
+        return this->robot.lock()->getRobotNode(_node->getParent());
+    }
+    /*
+    template<class RobotNodeType>
+    void RemoteRobotNode<RobotNodeType>::setPostJointTransformation(const Eigen::Matrix4f &trafo){
+    }*/
+    template<class RobotNodeType>
+    void RemoteRobotNode<RobotNodeType>::setLocalTransformation(const Eigen::Matrix4f& trafo)
+    {
+    }
+    template<class RobotNodeType>
+    std::vector<std::string> RemoteRobotNode<RobotNodeType>::getChildrenNames() const
+    {
+        return _node->getChildren();
+    }
+    template<class RobotNodeType>
+    std::string RemoteRobotNode<RobotNodeType>::getParentName() const
+    {
+        return _node->getParent();
+    }
+    template<class RobotNodeType>
+    std::vector<SceneObjectPtr> RemoteRobotNode<RobotNodeType>::getChildren() const
+    {
+        NameList nodes = _node->getChildren();
+        vector<SceneObjectPtr> result;
+        BOOST_FOREACH(string name, nodes)
+        {
+            result.push_back(this->robot.lock()->getRobotNode(name));
+        }
+        return result;
+    }
 
 
-template<class RobotNodeType>
-void RemoteRobotNode<RobotNodeType>::updateTransformationMatrices(){
-}
-template<class RobotNodeType>
-void RemoteRobotNode<RobotNodeType>::updateTransformationMatrices(const Eigen::Matrix4f &globalPose){
-}
+    template<class RobotNodeType>
+    void RemoteRobotNode<RobotNodeType>::updateTransformationMatrices()
+    {
+    }
+    template<class RobotNodeType>
+    void RemoteRobotNode<RobotNodeType>::updateTransformationMatrices(const Eigen::Matrix4f& globalPose)
+    {
+    }
 
 
-template<class RobotNodeType>
-void RemoteRobotNode<RobotNodeType>::addChildNode(RobotNodePtr child){
-}
-template<class RobotNodeType>
-bool RemoteRobotNode<RobotNodeType>::initialize(RobotNodePtr parent, bool initializeChildren){
-	return false;
-}
-template<class RobotNodeType>
-void RemoteRobotNode<RobotNodeType>::reset(){
-}
-template<class RobotNodeType>
-void RemoteRobotNode<RobotNodeType>::setGlobalPose( const Eigen::Matrix4f &pose ){
-}
-template<class RobotNodeType>
-void RemoteRobotNode<RobotNodeType>::setJointValue(float q, bool updateTransformations, bool clampToLimits){
-}
+    template<class RobotNodeType>
+    void RemoteRobotNode<RobotNodeType>::addChildNode(RobotNodePtr child)
+    {
+    }
+    template<class RobotNodeType>
+    bool RemoteRobotNode<RobotNodeType>::initialize(RobotNodePtr parent, bool initializeChildren)
+    {
+        return false;
+    }
+    template<class RobotNodeType>
+    void RemoteRobotNode<RobotNodeType>::reset()
+    {
+    }
+    template<class RobotNodeType>
+    void RemoteRobotNode<RobotNodeType>::setGlobalPose(const Eigen::Matrix4f& pose)
+    {
+    }
+    template<class RobotNodeType>
+    void RemoteRobotNode<RobotNodeType>::setJointValue(float q, bool updateTransformations, bool clampToLimits)
+    {
+    }
 
 }
diff --git a/source/RobotAPI/libraries/core/remoterobot/RobotStateObserver.cpp b/source/RobotAPI/libraries/core/remoterobot/RobotStateObserver.cpp
index d0ffd0c3373f94bfa84d30c07ada5dbbc22b4c35..36713d9ad74c379c9ee248f1aac33964fdb4e913 100644
--- a/source/RobotAPI/libraries/core/remoterobot/RobotStateObserver.cpp
+++ b/source/RobotAPI/libraries/core/remoterobot/RobotStateObserver.cpp
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -23,10 +22,10 @@
 
 #include "RobotStateObserver.h"
 #include <RobotAPI/interface/core/RobotState.h>
-#include <Core/observers/checks/ConditionCheckEquals.h>
-#include <Core/observers/checks/ConditionCheckInRange.h>
-#include <Core/observers/checks/ConditionCheckLarger.h>
-#include <Core/observers/checks/ConditionCheckSmaller.h>
+#include <ArmarXCore/observers/checks/ConditionCheckEquals.h>
+#include <ArmarXCore/observers/checks/ConditionCheckInRange.h>
+#include <ArmarXCore/observers/checks/ConditionCheckLarger.h>
+#include <ArmarXCore/observers/checks/ConditionCheckSmaller.h>
 
 #include <RobotAPI/libraries/core/remoterobot/RemoteRobot.h>
 
@@ -35,7 +34,7 @@
 #include <VirtualRobot/Nodes/RobotNode.h>
 #include <VirtualRobot/RobotConfig.h>
 #include <VirtualRobot/VirtualRobot.h>
-#include <Core/observers/variant/DatafieldRef.h>
+#include <ArmarXCore/observers/variant/DatafieldRef.h>
 
 #include <boost/algorithm/string/trim.hpp>
 
@@ -57,11 +56,11 @@ RobotStateObserver::RobotStateObserver()
 void RobotStateObserver::onInitObserver()
 {
 
-	// register all checks
-	offerConditionCheck("equals", new ConditionCheckEquals());
-	offerConditionCheck("inrange", new ConditionCheckInRange());
-	offerConditionCheck("larger", new ConditionCheckLarger());
-	offerConditionCheck("smaller", new ConditionCheckSmaller());
+    // register all checks
+    offerConditionCheck("equals", new ConditionCheckEquals());
+    offerConditionCheck("inrange", new ConditionCheckInRange());
+    offerConditionCheck("larger", new ConditionCheckLarger());
+    offerConditionCheck("smaller", new ConditionCheckSmaller());
 }
 
 void RobotStateObserver::onConnectObserver()
@@ -81,52 +80,68 @@ void RobotStateObserver::onConnectObserver()
 
 void RobotStateObserver::updatePoses()
 {
-    if(getState() < eManagedIceObjectStarting)
+    if (getState() < eManagedIceObjectStarting)
+    {
         return;
-    if(!robot)
+    }
+
+    if (!robot)
+    {
         return;
+    }
+
     ScopedRecursiveLock lock(dataMutex);
     ReadLockPtr lock2 = robot->getReadLock();
     FramedPoseBaseMap tcpPoses;
     std::string rootFrame =  robot->getRootNode()->getName();
+
     //IceUtil::Time start = IceUtil::Time::now();
-    for(unsigned int i=0; i < nodesToReport.size(); i++)
+    for (unsigned int i = 0; i < nodesToReport.size(); i++)
     {
         VirtualRobot::RobotNodePtr& node = nodesToReport.at(i);
-        const std::string &tcpName  = node->getName();
-        const Eigen::Matrix4f &currentPose = node->getPoseInRootFrame();
+        const std::string& tcpName  = node->getName();
+        const Eigen::Matrix4f& currentPose = node->getPoseInRootFrame();
         tcpPoses[tcpName] = new FramedPose(currentPose, rootFrame, robot->getName());
 
     }
+
     udpatePoseDatafields(tcpPoses);
 
 }
 
-void RobotStateObserver::udpatePoseDatafields(const FramedPoseBaseMap &poseMap)
+void RobotStateObserver::udpatePoseDatafields(const FramedPoseBaseMap& poseMap)
 {
-//        ARMARX_INFO << deactivateSpam() << "new tcp poses reported";
+    //        ARMARX_INFO << deactivateSpam() << "new tcp poses reported";
     FramedPoseBaseMap::const_iterator it = poseMap.begin();
-    for(; it != poseMap.end(); it++)
+
+    for (; it != poseMap.end(); it++)
     {
 
         FramedPosePtr vec = FramedPosePtr::dynamicCast(it->second);
-        const std::string &tcpName = it->first;
-        if(!existsDataField(TCP_POSE_CHANNEL, tcpName))
+        const std::string& tcpName = it->first;
+
+        if (!existsDataField(TCP_POSE_CHANNEL, tcpName))
+        {
             offerDataFieldWithDefault(TCP_POSE_CHANNEL, tcpName, Variant(it->second), "Pose of " + tcpName);
+        }
         else
+        {
             setDataField(TCP_POSE_CHANNEL, tcpName, Variant(it->second));
+        }
+
         updateChannel(TCP_POSE_CHANNEL);
-        if(!existsChannel(tcpName))
+
+        if (!existsChannel(tcpName))
         {
             offerChannel(tcpName, "pose components of " + tcpName);
-            offerDataFieldWithDefault(tcpName,"x", Variant(vec->position->x), "X axis");
-            offerDataFieldWithDefault(tcpName,"y", Variant(vec->position->y), "Y axis");
-            offerDataFieldWithDefault(tcpName,"z", Variant(vec->position->z), "Z axis");
-            offerDataFieldWithDefault(tcpName,"qx", Variant(vec->orientation->qx), "Quaternion part x");
-            offerDataFieldWithDefault(tcpName,"qy", Variant(vec->orientation->qy), "Quaternion part y");
-            offerDataFieldWithDefault(tcpName,"qz", Variant(vec->orientation->qz), "Quaternion part z");
-            offerDataFieldWithDefault(tcpName,"qw", Variant(vec->orientation->qw), "Quaternion part w");
-            offerDataFieldWithDefault(tcpName,"frame", Variant(vec->frame), "Reference Frame");
+            offerDataFieldWithDefault(tcpName, "x", Variant(vec->position->x), "X axis");
+            offerDataFieldWithDefault(tcpName, "y", Variant(vec->position->y), "Y axis");
+            offerDataFieldWithDefault(tcpName, "z", Variant(vec->position->z), "Z axis");
+            offerDataFieldWithDefault(tcpName, "qx", Variant(vec->orientation->qx), "Quaternion part x");
+            offerDataFieldWithDefault(tcpName, "qy", Variant(vec->orientation->qy), "Quaternion part y");
+            offerDataFieldWithDefault(tcpName, "qz", Variant(vec->orientation->qz), "Quaternion part z");
+            offerDataFieldWithDefault(tcpName, "qw", Variant(vec->orientation->qw), "Quaternion part w");
+            offerDataFieldWithDefault(tcpName, "frame", Variant(vec->frame), "Reference Frame");
         }
         else
         {
@@ -141,111 +156,141 @@ void RobotStateObserver::udpatePoseDatafields(const FramedPoseBaseMap &poseMap)
             newValues["frame"] =  new Variant(vec->frame);
             setDataFieldsFlatCopy(tcpName, newValues);
         }
+
         updateChannel(tcpName);
 
     }
 }
 
-DatafieldRefBasePtr RobotStateObserver::getPoseDatafield(const std::string &nodeName, const Ice::Current &) const
+DatafieldRefBasePtr RobotStateObserver::getPoseDatafield(const std::string& nodeName, const Ice::Current&) const
 {
     return getDataFieldRef(new DataFieldIdentifier(getName(), TCP_POSE_CHANNEL, nodeName));
 }
 
-void RobotStateObserver::updateNodeVelocities(const NameValueMap &jointVel)
+void RobotStateObserver::updateNodeVelocities(const NameValueMap& jointVel)
 {
 
-    if(getState() < eManagedIceObjectStarting)
+    if (getState() < eManagedIceObjectStarting)
+    {
         return;
+    }
+
     ScopedRecursiveLock lock(dataMutex);
-    if(!robot)
+
+    if (!robot)
+    {
         return;
+    }
+
     ReadLockPtr lock2 = robot->getReadLock();
-    if(!velocityReportRobot)
+
+    if (!velocityReportRobot)
+    {
         velocityReportRobot = robot->clone(robot->getName());
-//    IceUtil::Time start = IceUtil::Time::now();
-//    ARMARX_INFO << jointVel;    FramedPoseBaseMap tcpPoses;
+    }
+
+    //    IceUtil::Time start = IceUtil::Time::now();
+    //    ARMARX_INFO << jointVel;    FramedPoseBaseMap tcpPoses;
     FramedDirectionMap tcpTranslationVelocities;
     FramedDirectionMap tcpOrientationVelocities;
     std::string rootFrame =  robot->getRootNode()->getName();
     NameValueMap tempJointAngles = robot->getConfig()->getRobotNodeJointValueMap();
     FramedPoseBaseMap tcpPoses;
-    for(unsigned int i=0; i < nodesToReport.size(); i++)
+
+    for (unsigned int i = 0; i < nodesToReport.size(); i++)
     {
         RobotNodePtr node = nodesToReport.at(i);
-        const std::string &tcpName  = node->getName();
-        const Eigen::Matrix4f &currentPose = node->getPoseInRootFrame();
+        const std::string& tcpName  = node->getName();
+        const Eigen::Matrix4f& currentPose = node->getPoseInRootFrame();
         tcpPoses[tcpName] = new FramedPose(currentPose, rootFrame, robot->getName());
 
     }
 
     double tDelta = 0.001;
-    for(NameValueMap::iterator it = tempJointAngles.begin(); it != tempJointAngles.end(); it++)
+
+    for (NameValueMap::iterator it = tempJointAngles.begin(); it != tempJointAngles.end(); it++)
     {
         NameValueMap::const_iterator itSrc = jointVel.find(it->first);
-        if(itSrc != jointVel.end())
+
+        if (itSrc != jointVel.end())
+        {
             it->second += itSrc->second * tDelta;
+        }
     }
 
     velocityReportRobot->setJointValues(tempJointAngles);
-//    ARMARX_INFO << deactivateSpam(1) << "duration: " << (IceUtil::Time::now()-start).toMicroSecondsDouble();
-//    start = IceUtil::Time::now();
+    //    ARMARX_INFO << deactivateSpam(1) << "duration: " << (IceUtil::Time::now()-start).toMicroSecondsDouble();
+    //    start = IceUtil::Time::now();
     Eigen::Matrix4f mat;
     Eigen::Vector3f rpy;
-    for(unsigned int i=0; i < nodesToReport.size(); i++)
+
+    for (unsigned int i = 0; i < nodesToReport.size(); i++)
     {
         RobotNodePtr node = velocityReportRobot->getRobotNode(nodesToReport.at(i)->getName());
-        const std::string &tcpName  = node->getName();
-        const Eigen::Matrix4f &currentPose = node->getPoseInRootFrame();
+        const std::string& tcpName  = node->getName();
+        const Eigen::Matrix4f& currentPose = node->getPoseInRootFrame();
 
 
         FramedPosePtr lastPose = FramedPosePtr::dynamicCast(tcpPoses[tcpName]);
 
-        tcpTranslationVelocities[tcpName] = new FramedDirection((currentPose.block(0,3,3,1) - lastPose->toEigen().block(0,3,3,1))/tDelta, rootFrame, robot->getName());
+        tcpTranslationVelocities[tcpName] = new FramedDirection((currentPose.block(0, 3, 3, 1) - lastPose->toEigen().block(0, 3, 3, 1)) / tDelta, rootFrame, robot->getName());
 
         mat = currentPose * lastPose->toEigen().inverse();
 
         VirtualRobot::MathTools::eigen4f2rpy(mat, rpy);
 
-        tcpOrientationVelocities[tcpName] = new FramedDirection(rpy/tDelta, rootFrame, robot->getName());
+        tcpOrientationVelocities[tcpName] = new FramedDirection(rpy / tDelta, rootFrame, robot->getName());
 
 
     }
-//    ARMARX_INFO << deactivateSpam(1) << "duration2: " << (IceUtil::Time::now()-start).toMicroSecondsDouble();
-//    ARMARX_INFO << deactivateSpam(5) << "TCP Pose Vel Calc took: " << ( IceUtil::Time::now() - start).toMilliSecondsDouble();
+
+    //    ARMARX_INFO << deactivateSpam(1) << "duration2: " << (IceUtil::Time::now()-start).toMicroSecondsDouble();
+    //    ARMARX_INFO << deactivateSpam(5) << "TCP Pose Vel Calc took: " << ( IceUtil::Time::now() - start).toMilliSecondsDouble();
     updateVelocityDatafields(tcpTranslationVelocities, tcpOrientationVelocities);
 }
 
-void RobotStateObserver::updateVelocityDatafields(const FramedDirectionMap &tcpTranslationVelocities, const FramedDirectionMap &tcpOrientationVelocities)
+void RobotStateObserver::updateVelocityDatafields(const FramedDirectionMap& tcpTranslationVelocities, const FramedDirectionMap& tcpOrientationVelocities)
 {
     FramedDirectionMap::const_iterator it = tcpTranslationVelocities.begin();
-    for(; it != tcpTranslationVelocities.end(); it++)
+
+    for (; it != tcpTranslationVelocities.end(); it++)
     {
 
         FramedDirectionPtr vec = FramedDirectionPtr::dynamicCast(it->second);
         FramedDirectionPtr vecOri;
         FramedDirectionMap::const_iterator itOri = tcpOrientationVelocities.find(it->first);
-        if(itOri != tcpOrientationVelocities.end())
+
+        if (itOri != tcpOrientationVelocities.end())
+        {
             vecOri = FramedDirectionPtr::dynamicCast(itOri->second);
-        const std::string &tcpName = it->first;
+        }
+
+        const std::string& tcpName = it->first;
 
         ARMARX_CHECK_EXPRESSION(vec->frame == vecOri->frame);
 
-        if(!existsDataField(TCP_TRANS_VELOCITIES_CHANNEL, tcpName))
+        if (!existsDataField(TCP_TRANS_VELOCITIES_CHANNEL, tcpName))
+        {
             offerDataFieldWithDefault(TCP_TRANS_VELOCITIES_CHANNEL, tcpName, Variant(it->second), "Pose of " + tcpName);
+        }
         else
+        {
             setDataField(TCP_TRANS_VELOCITIES_CHANNEL, tcpName, Variant(it->second));
+        }
+
         updateChannel(TCP_TRANS_VELOCITIES_CHANNEL);
-        const std::string channelName = tcpName+"Velocities";
-        if(!existsChannel(channelName))
+        const std::string channelName = tcpName + "Velocities";
+
+        if (!existsChannel(channelName))
         {
             offerChannel(channelName, "pose components of " + tcpName);
-            offerDataFieldWithDefault(channelName,"x", Variant(vec->x), "X axis");
-            offerDataFieldWithDefault(channelName,"y", Variant(vec->y), "Y axis");
-            offerDataFieldWithDefault(channelName,"z", Variant(vec->z), "Z axis");
-            offerDataFieldWithDefault(channelName,"roll", Variant(vecOri->x), "Roll");
-            offerDataFieldWithDefault(channelName,"pitch", Variant(vecOri->y), "Pitch");
-            offerDataFieldWithDefault(channelName,"yaw", Variant(vecOri->z), "Yaw");
-            offerDataFieldWithDefault(channelName,"frame", Variant(vecOri->frame), "Reference Frame");
+            offerDataFieldWithDefault(channelName, "x", Variant(vec->x), "X axis");
+            offerDataFieldWithDefault(channelName, "y", Variant(vec->y), "Y axis");
+            offerDataFieldWithDefault(channelName, "z", Variant(vec->z), "Z axis");
+            offerDataFieldWithDefault(channelName, "roll", Variant(vecOri->x), "Roll");
+            offerDataFieldWithDefault(channelName, "pitch", Variant(vecOri->y), "Pitch");
+            offerDataFieldWithDefault(channelName, "yaw", Variant(vecOri->z), "Yaw");
+            offerDataFieldWithDefault(channelName, "frame", Variant(vecOri->frame), "Reference Frame");
         }
         else
         {
@@ -259,6 +304,7 @@ void RobotStateObserver::updateVelocityDatafields(const FramedDirectionMap &tcpT
             newValues["frame"] =  new Variant(vec->frame);
             setDataFieldsFlatCopy(channelName, newValues);
         }
+
         updateChannel(channelName);
 
     }
@@ -280,15 +326,19 @@ void RobotStateObserver::setRobot(RobotPtr robot)
     robotNodes = robot->getRobotNodeSets();
 
     std::string nodesetsString = getProperty<std::string>("TCPsToReport").getValue();
-    if(!nodesetsString.empty())
+
+    if (!nodesetsString.empty())
     {
-        if(nodesetsString=="*")
+        if (nodesetsString == "*")
         {
             auto nodesets = robot->getRobotNodeSets();
-            for(RobotNodeSetPtr& set : nodesets)
+
+            for (RobotNodeSetPtr& set : nodesets)
             {
-                if(set->getTCP())
+                if (set->getTCP())
+                {
                     nodesToReport.push_back(set->getTCP());
+                }
             }
         }
         else
@@ -298,15 +348,20 @@ void RobotStateObserver::setRobot(RobotPtr robot)
                          nodesetsString,
                          boost::is_any_of(","),
                          boost::token_compress_on);
-            for(auto name : nodesetNames)
+
+            for (auto name : nodesetNames)
             {
                 boost::trim(name);
                 auto node = robot->getRobotNode(name);
 
-                if(node)
+                if (node)
+                {
                     nodesToReport.push_back(node);
+                }
                 else
+                {
                     ARMARX_ERROR << "Could not find node set with name: " << name;
+                }
             }
         }
     }
diff --git a/source/RobotAPI/libraries/core/remoterobot/RobotStateObserver.h b/source/RobotAPI/libraries/core/remoterobot/RobotStateObserver.h
index a4f230e585434bbfdad585291e99d2a0fa4d1ccf..2c4eae0066b81b1f61ca99cb9c2777254fb4a47d 100644
--- a/source/RobotAPI/libraries/core/remoterobot/RobotStateObserver.h
+++ b/source/RobotAPI/libraries/core/remoterobot/RobotStateObserver.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -24,14 +23,14 @@
 #ifndef _ARMARX_CORE_KINEMATIC_UNIT_OBSERVER_H
 #define _ARMARX_CORE_KINEMATIC_UNIT_OBSERVER_H
 
-#include <Core/core/system/ImportExport.h>
-#include <Core/core/Component.h>
-#include <Core/interface/observers/VariantBase.h>
+#include <ArmarXCore/core/system/ImportExport.h>
+#include <ArmarXCore/core/Component.h>
+#include <ArmarXCore/interface/observers/VariantBase.h>
 #include <RobotAPI/interface/units/KinematicUnitInterface.h>
 #include <RobotAPI/interface/core/RobotStateObserverInterface.h>
 #include <RobotAPI/interface/core/RobotState.h>
-#include <Core/observers/ConditionCheck.h>
-#include <Core/observers/Observer.h>
+#include <ArmarXCore/observers/ConditionCheck.h>
+#include <ArmarXCore/observers/Observer.h>
 
 #include <string>
 
@@ -50,10 +49,10 @@ namespace armarx
      * RobotStatePropertyDefinition Property Definitions
      */
     class RobotStateObserverPropertyDefinitions:
-            public ComponentPropertyDefinitions
+        public ComponentPropertyDefinitions
     {
     public:
-       RobotStateObserverPropertyDefinitions(std::string prefix):
+        RobotStateObserverPropertyDefinitions(std::string prefix):
             ComponentPropertyDefinitions(prefix)
         {
             defineOptionalProperty<std::string>("TCPsToReport", "", "comma seperated list of nodesets' endeffectors, which poses and velocities that should be reported. * for all, empty for none");
@@ -62,48 +61,51 @@ namespace armarx
 
     typedef ::std::map< ::std::string, ::armarx::FramedPoseBasePtr> FramedPoseBaseMap;
 
-   /**
-    * ArmarX RobotStateObserver.
-    *
-    * The RobotStateObserver allows to install conditions on all channel reported by the KinematicUnit.
-    * These include joint angles, velocities, torques and motor temperatures
-    *
-    * The RobotStateObserver retrieves its configuration from a VirtualRobot robot model. Within the model, the joints
-    * which are observer by the unit are define by a robotnodeset
-    */
+    /**
+     * ArmarX RobotStateObserver.
+     *
+     * The RobotStateObserver allows to install conditions on all channel reported by the KinematicUnit.
+     * These include joint angles, velocities, torques and motor temperatures
+     *
+     * The RobotStateObserver retrieves its configuration from a VirtualRobot robot model. Within the model, the joints
+     * which are observer by the unit are define by a robotnodeset
+     */
     class ARMARXCORE_IMPORT_EXPORT RobotStateObserver :
         virtual public Observer,
         virtual public RobotStateObserverInterface
     {
     public:
         RobotStateObserver();
-   		// framework hooks
-   		void onInitObserver();
-   		void onConnectObserver();
+        // framework hooks
+        void onInitObserver();
+        void onConnectObserver();
 
         virtual PropertyDefinitionsPtr createPropertyDefinitions();
 
         void setRobot(VirtualRobot::RobotPtr robot);
 
-        virtual std::string getDefaultName() const { return "RobotStateObserver"; }
+        virtual std::string getDefaultName() const
+        {
+            return "RobotStateObserver";
+        }
 
         void updatePoses();
-        void updateNodeVelocities(const NameValueMap &jointVel);
+        void updateNodeVelocities(const NameValueMap& jointVel);
     protected:
 
-        void updateVelocityDatafields(const FramedDirectionMap &tcpTranslationVelocities, const FramedDirectionMap &tcpOrientationVelocities);
+        void updateVelocityDatafields(const FramedDirectionMap& tcpTranslationVelocities, const FramedDirectionMap& tcpOrientationVelocities);
 
-        void udpatePoseDatafields(const FramedPoseBaseMap &poseMap);
+        void udpatePoseDatafields(const FramedPoseBaseMap& poseMap);
     private:
-    	std::string robotNodeSetName;
-		RobotStateComponentInterfacePrx server;
+        std::string robotNodeSetName;
+        RobotStateComponentInterfacePrx server;
         VirtualRobot::RobotPtr  robot, velocityReportRobot;
         std::vector<VirtualRobot::RobotNodePtr > nodesToReport;
         RecursiveMutex dataMutex;
 
         // RobotStateObserverInterface interface
     public:
-        DatafieldRefBasePtr getPoseDatafield(const std::string &nodeName, const Ice::Current &) const;
+        DatafieldRefBasePtr getPoseDatafield(const std::string& nodeName, const Ice::Current&) const;
     };
 
     typedef IceInternal::Handle<RobotStateObserver> RobotStateObserverPtr;
diff --git a/source/RobotAPI/libraries/core/remoterobot/test/ArmarPoseTest.cpp b/source/RobotAPI/libraries/core/remoterobot/test/ArmarPoseTest.cpp
index 553f2ff8a458cb2331fa81bbc3f64f7344210acd..0c7f49a96a80e183ac3c9c84c3614e8b003b15a1 100644
--- a/source/RobotAPI/libraries/core/remoterobot/test/ArmarPoseTest.cpp
+++ b/source/RobotAPI/libraries/core/remoterobot/test/ArmarPoseTest.cpp
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -24,7 +23,7 @@
 #define BOOST_TEST_MODULE RobotAPI::FramedPose::Test
 #define ARMARX_BOOST_TEST
 #include <RobotAPI/Test.h>
-#include <Core/util/json/JSONObject.h>
+#include <ArmarXCore/util/json/JSONObject.h>
 #include <RobotAPI/libraries/core/FramedPose.h>
 
 
@@ -41,8 +40,9 @@ BOOST_AUTO_TEST_CASE(complexVariantToDict)
     pos->z = 3;
     pos->frame = "Base";
     VariantPtr var = new Variant(pos);
-    auto dict = json->ConvertToBasicVariantMap(json,var);
-    for(auto e : dict)
+    auto dict = json->ConvertToBasicVariantMap(json, var);
+
+    for (auto e : dict)
     {
         ARMARX_INFO_S << e.first << ": " << *VariantPtr::dynamicCast(e.second);
     }
diff --git a/source/RobotAPI/libraries/drivers/WeissHapticSensor/AbstractInterface.cpp b/source/RobotAPI/libraries/drivers/WeissHapticSensor/AbstractInterface.cpp
index b450fb668f81c4bc9bc73986211bb46d92ef2733..d043c16bb07af22398afd2a338be706ed3b557c0 100644
--- a/source/RobotAPI/libraries/drivers/WeissHapticSensor/AbstractInterface.cpp
+++ b/source/RobotAPI/libraries/drivers/WeissHapticSensor/AbstractInterface.cpp
@@ -19,11 +19,11 @@ AbstractInterface::~AbstractInterface()
 {
 }
 
-int AbstractInterface::read(unsigned char *buf, unsigned int len)
+int AbstractInterface::read(unsigned char* buf, unsigned int len)
 {
     int res = readInternal(buf, len);
 
-    if(log != NULL)
+    if (log != NULL)
     {
         log->logRead(buf, res);
     }
@@ -31,9 +31,9 @@ int AbstractInterface::read(unsigned char *buf, unsigned int len)
     return res;
 }
 
-int AbstractInterface::write(unsigned char *buf, unsigned int len)
+int AbstractInterface::write(unsigned char* buf, unsigned int len)
 {
-    if(log != NULL)
+    if (log != NULL)
     {
         log->logWrite(buf, len);
     }
@@ -42,26 +42,27 @@ int AbstractInterface::write(unsigned char *buf, unsigned int len)
 }
 
 
-Response AbstractInterface::submitCmd( unsigned char id, unsigned char *payload, unsigned int len, bool pending )
+Response AbstractInterface::submitCmd(unsigned char id, unsigned char* payload, unsigned int len, bool pending)
 {
     fireAndForgetCmd(id, payload, len, pending);
     return receive(pending, id);
 }
 
-void AbstractInterface::fireAndForgetCmd( unsigned char id, unsigned char *payload, unsigned int len, bool pending )
+void AbstractInterface::fireAndForgetCmd(unsigned char id, unsigned char* payload, unsigned int len, bool pending)
 {
 
     int res;
 
     // Check if we're connected
-    if ( !connected )
+    if (!connected)
     {
         throw TransmissionException("Interface not connected");
     }
 
     // Send command
-    res = send( id, len, payload );
-    if ( res < 0 )
+    res = send(id, len, payload);
+
+    if (res < 0)
     {
         throw TransmissionException("Message send failed");
     }
@@ -74,7 +75,7 @@ void AbstractInterface::startLogging(std::string file)
 
 void AbstractInterface::logText(std::string message)
 {
-    if(log != NULL)
+    if (log != NULL)
     {
         log->logText(message);
     }
@@ -87,13 +88,14 @@ Response AbstractInterface::receiveWithoutChecks()
     msg_t msg;
 
     // Receive response data
-    res = receive( &msg );
-    if ( res < 0 )
+    res = receive(&msg);
+
+    if (res < 0)
     {
         throw TransmissionException("Message receive failed");
     }
 
-    status = (status_t) make_short( msg.data[0], msg.data[1] );
+    status = (status_t) make_short(msg.data[0], msg.data[1]);
 
     return Response(res, msg.id, status, msg.data, msg.len);
 }
@@ -108,14 +110,15 @@ Response AbstractInterface::receive(bool pending, unsigned char expectedId)
     do
     {
         // Receive response data
-        res = receive( &msg );
-        if ( res < 0 )
+        res = receive(&msg);
+
+        if (res < 0)
         {
             throw TransmissionException("Message receive failed");
         }
 
         // Check response ID
-        if ( msg.id != expectedId )
+        if (msg.id != expectedId)
         {
             //std::strstream strStream;
             //strStream << "Response ID ()" << msg.id << ") does not match submitted command ID (" << id << ")";
@@ -123,37 +126,39 @@ Response AbstractInterface::receive(bool pending, unsigned char expectedId)
             throw TransmissionException(str(boost::format("Response ID (%02X) does not match submitted command ID (%02X)") % (int)msg.id % (int)expectedId));
         }
 
-        if ( pending )
+        if (pending)
         {
-            if ( msg.len < 2 )
+            if (msg.len < 2)
             {
                 throw TransmissionException("No status code received");
             }
 
-            status = (status_t) make_short( msg.data[0], msg.data[1] );
+            status = (status_t) make_short(msg.data[0], msg.data[1]);
         }
     }
-    while( pending && status == E_CMD_PENDING );
+    while (pending && status == E_CMD_PENDING);
 
-    status = (status_t) make_short( msg.data[0], msg.data[1] );
+    status = (status_t) make_short(msg.data[0], msg.data[1]);
 
     return Response(res, msg.id, status, msg.data, msg.len);
 }
 
-int AbstractInterface::receive( msg_t *msg )
+int AbstractInterface::receive(msg_t* msg)
 {
     int res;
-    unsigned char header[3];			// 1 byte command, 2 bytes payload length
-    unsigned short checksum = 0x50f5;	// Checksum over preamble (0xaa 0xaa 0xaa)
+    unsigned char header[3];            // 1 byte command, 2 bytes payload length
+    unsigned short checksum = 0x50f5;   // Checksum over preamble (0xaa 0xaa 0xaa)
     unsigned int sync;
 
     logText("read preamble");
     // Syncing - necessary for compatibility with serial interface
     sync = 0;
-    while( sync != MSG_PREAMBLE_LEN )
+
+    while (sync != MSG_PREAMBLE_LEN)
     {
-        res = read( header, 1 );
-        if ( res > 0 && header[0] == MSG_PREAMBLE_BYTE )
+        res = read(header, 1);
+
+        if (res > 0 && header[0] == MSG_PREAMBLE_BYTE)
         {
             sync++;
         }
@@ -164,20 +169,21 @@ int AbstractInterface::receive( msg_t *msg )
     }
 
     // Read header
-    res = read( header, 3 );
-    if ( res < 3 )
+    res = read(header, 3);
+
+    if (res < 3)
     {
         throw TransmissionException(str(boost::format("Failed to receive header data (%d bytes read)") % res));
     }
 
     // Calculate checksum over header
-    checksum = Checksum::Update_crc16( header, 3, checksum );
+    checksum = Checksum::Update_crc16(header, 3, checksum);
 
     // Get message id of received
     msg->id = header[0];
 
     // Get payload size of received message
-    msg->len = make_short( header[1], header[2] );
+    msg->len = make_short(header[1], header[2]);
 
     // Allocate space for payload and checksum
     //msg->data.resize( msg->len + 2u );
@@ -210,7 +216,8 @@ int AbstractInterface::receive( msg_t *msg )
     // Read payload and checksum:
     // payload: msg->len
     // checksum: 2 byte
-    int read = this->read( data, msg->len + 2 );
+    int read = this->read(data, msg->len + 2);
+
     if (read != (int)msg->len + 2)
     {
         delete[] data;
@@ -227,8 +234,9 @@ int AbstractInterface::receive( msg_t *msg )
     }*/
 
     // Check checksum
-    checksum = Checksum::Update_crc16( data, msg->len + 2, checksum );
-    if ( checksum != 0 )
+    checksum = Checksum::Update_crc16(data, msg->len + 2, checksum);
+
+    if (checksum != 0)
     {
         delete[] data;
         logText("CHECKSUM ERROR");
@@ -241,7 +249,7 @@ int AbstractInterface::receive( msg_t *msg )
     return msg->len + 8;
 }
 
-int AbstractInterface::send(unsigned char id, unsigned int len, unsigned char *data)
+int AbstractInterface::send(unsigned char id, unsigned int len, unsigned char* data)
 {
     unsigned char header[MSG_PREAMBLE_LEN + 3];
     unsigned short crc;
@@ -250,29 +258,33 @@ int AbstractInterface::send(unsigned char id, unsigned int len, unsigned char *d
     logText("write preamble");
 
     // Preamble
-    for ( i = 0; i < MSG_PREAMBLE_LEN; i++ ) header[i] = MSG_PREAMBLE_BYTE;
+    for (i = 0; i < MSG_PREAMBLE_LEN; i++)
+    {
+        header[i] = MSG_PREAMBLE_BYTE;
+    }
 
     // Command ID
     header[MSG_PREAMBLE_LEN] = id;
 
     // Length
-    header[MSG_PREAMBLE_LEN + 1] = lo( len );
-    header[MSG_PREAMBLE_LEN + 2] = hi( len );
+    header[MSG_PREAMBLE_LEN + 1] = lo(len);
+    header[MSG_PREAMBLE_LEN + 2] = hi(len);
 
     // Checksum
-    crc = Checksum::Crc16( header, 6 );
-    crc = Checksum::Update_crc16( data, len, crc );
+    crc = Checksum::Crc16(header, 6);
+    crc = Checksum::Update_crc16(data, len, crc);
+
 
+    unsigned char* buf = new unsigned char[ 6 + len + 2 ];
+    memcpy(buf, header, 6);
+    memcpy(buf + 6, data, len);
+    memcpy(buf + 6 + len, (unsigned char*) &crc, 2);
 
-    unsigned char *buf = new unsigned char[ 6 + len + 2 ];
-    memcpy( buf, header, 6 );
-    memcpy( buf + 6, data, len );
-    memcpy( buf + 6 + len, (unsigned char *) &crc, 2 );
+    res = write(buf, 6 + len + 2);
 
-    res = write( buf, 6 + len + 2 );
-    if ( res < 6 + (int)len + 2 )
+    if (res < 6 + (int)len + 2)
     {
-		delete[] buf;
+        delete[] buf;
         close();
         throw TransmissionException("Failed to submit message checksum");
         //cerr << "Failed to submit message checksum" << endl;
@@ -288,6 +300,7 @@ int AbstractInterface::send(unsigned char id, unsigned int len, unsigned char *d
 
 
 
-std::ostream& operator<<(std::ostream &strm, const AbstractInterface &a) {
-  return strm << a.toString();
+std::ostream& operator<<(std::ostream& strm, const AbstractInterface& a)
+{
+    return strm << a.toString();
 }
diff --git a/source/RobotAPI/libraries/drivers/WeissHapticSensor/AbstractInterface.h b/source/RobotAPI/libraries/drivers/WeissHapticSensor/AbstractInterface.h
index 19e45a9cc1821573cd222cd4f1c53b2894c640af..b148061e0c0701d48d080bf3ba192c27fb33f0a3 100644
--- a/source/RobotAPI/libraries/drivers/WeissHapticSensor/AbstractInterface.h
+++ b/source/RobotAPI/libraries/drivers/WeissHapticSensor/AbstractInterface.h
@@ -7,18 +7,18 @@
 #include <boost/shared_ptr.hpp>
 
 
-#define MSG_PREAMBLE_BYTE		0xaa
-#define MSG_PREAMBLE_LEN		3
+#define MSG_PREAMBLE_BYTE       0xaa
+#define MSG_PREAMBLE_LEN        3
 
 // Combine bytes to different types
-#define make_short( lowbyte, highbyte )				( (unsigned short)lowbyte | ( (unsigned short)highbyte << 8 ) )
-#define make_signed_short( lowbyte, highbyte )		( (signed short) ( (unsigned short) lowbyte | ( (unsigned short) highbyte << 8 ) ) )
-#define make_int( lowbyte, mid1, mid2, highbyte )	( (unsigned int) lowbyte | ( (unsigned int) mid1 << 8 ) | ( (unsigned int) mid2 << 16 ) | ( (unsigned int) highbyte << 24 ) )
-#define make_float( result, byteptr )				memcpy( &result, byteptr, sizeof( float ) )
+#define make_short( lowbyte, highbyte )             ( (unsigned short)lowbyte | ( (unsigned short)highbyte << 8 ) )
+#define make_signed_short( lowbyte, highbyte )      ( (signed short) ( (unsigned short) lowbyte | ( (unsigned short) highbyte << 8 ) ) )
+#define make_int( lowbyte, mid1, mid2, highbyte )   ( (unsigned int) lowbyte | ( (unsigned int) mid1 << 8 ) | ( (unsigned int) mid2 << 16 ) | ( (unsigned int) highbyte << 24 ) )
+#define make_float( result, byteptr )               memcpy( &result, byteptr, sizeof( float ) )
 
 // Byte access
-#define hi( x )    	(unsigned char) ( ((x) >> 8) & 0xff )	// Returns the upper byte of the passed short
-#define lo( x )    	(unsigned char) ( (x) & 0xff )       	// Returns the lower byte of the passed short
+#define hi( x )     (unsigned char) ( ((x) >> 8) & 0xff )   // Returns the upper byte of the passed short
+#define lo( x )     (unsigned char) ( (x) & 0xff )          // Returns the lower byte of the passed short
 
 
 
@@ -31,19 +31,22 @@ public:
     virtual ~AbstractInterface();
     virtual int open() = 0;
     virtual void close() = 0;
-    int read( unsigned char *buf, unsigned int len);
-    int write( unsigned char *buf, unsigned int len);
+    int read(unsigned char* buf, unsigned int len);
+    int write(unsigned char* buf, unsigned int len);
 
-    bool IsConnected() const { return connected; }
+    bool IsConnected() const
+    {
+        return connected;
+    }
 
     virtual std::string toString() const = 0;
 
-    int send(unsigned char id, unsigned int len, unsigned char *data);
-    int receive( msg_t *msg );
-    Response submitCmd( unsigned char id, unsigned char *payload, unsigned int len, bool pending );
+    int send(unsigned char id, unsigned int len, unsigned char* data);
+    int receive(msg_t* msg);
+    Response submitCmd(unsigned char id, unsigned char* payload, unsigned int len, bool pending);
     Response receive(bool pending, unsigned char expectedId);
     Response receiveWithoutChecks();
-    void fireAndForgetCmd( unsigned char id, unsigned char *payload, unsigned int len, bool pending );
+    void fireAndForgetCmd(unsigned char id, unsigned char* payload, unsigned int len, bool pending);
 
     void startLogging(std::string file);
     void logText(std::string message);
@@ -51,15 +54,15 @@ public:
 protected:
     bool connected;
 
-    virtual int readInternal( unsigned char *buf, unsigned int len) = 0;
-    virtual int writeInternal( unsigned char *buf, unsigned int len) = 0;
+    virtual int readInternal(unsigned char* buf, unsigned int len) = 0;
+    virtual int writeInternal(unsigned char* buf, unsigned int len) = 0;
 
 private:
     friend std::ostream& operator<<(std::ostream&, const AbstractInterface&);
     boost::shared_ptr<BinaryLogger> log;
 };
 
-std::ostream& operator<<(std::ostream &strm, const AbstractInterface &a);
+std::ostream& operator<<(std::ostream& strm, const AbstractInterface& a);
 
 
 #endif // ABSTRACTINTERFACE_H
diff --git a/source/RobotAPI/libraries/drivers/WeissHapticSensor/BinaryLogger.cpp b/source/RobotAPI/libraries/drivers/WeissHapticSensor/BinaryLogger.cpp
index 40c39409735c5b9fefd71983e83294bc19d6c9ca..9142b7349a5bcb8b8260d101d4e3baed9568d50f 100644
--- a/source/RobotAPI/libraries/drivers/WeissHapticSensor/BinaryLogger.cpp
+++ b/source/RobotAPI/libraries/drivers/WeissHapticSensor/BinaryLogger.cpp
@@ -11,24 +11,28 @@ BinaryLogger::~BinaryLogger()
     log.close();
 }
 
-void BinaryLogger::logRead(unsigned char *buf, unsigned int len)
+void BinaryLogger::logRead(unsigned char* buf, unsigned int len)
 {
     log << "READ";
-    for(unsigned int i = 0; i < len; i++)
+
+    for (unsigned int i = 0; i < len; i++)
     {
         log << boost::format(" %02X") % (int)buf[i];
     }
+
     log << std::endl;
     log.flush();
 }
 
-void BinaryLogger::logWrite(unsigned char *buf, unsigned int len)
+void BinaryLogger::logWrite(unsigned char* buf, unsigned int len)
 {
     log << "WRITE";
-    for(unsigned int i = 0; i < len; i++)
+
+    for (unsigned int i = 0; i < len; i++)
     {
         log << boost::format(" %02X") % (int)buf[i];
     }
+
     log << std::endl;
     log.flush();
 }
diff --git a/source/RobotAPI/libraries/drivers/WeissHapticSensor/BinaryLogger.h b/source/RobotAPI/libraries/drivers/WeissHapticSensor/BinaryLogger.h
index 535786e85c1b1f02e3fd12dc3fda398cdd239654..e48ce78dc925f224852fce4002aa8089a45af474 100644
--- a/source/RobotAPI/libraries/drivers/WeissHapticSensor/BinaryLogger.h
+++ b/source/RobotAPI/libraries/drivers/WeissHapticSensor/BinaryLogger.h
@@ -9,8 +9,8 @@ public:
     BinaryLogger(std::string filename);
     ~BinaryLogger();
 
-    void logRead(unsigned char *buf, unsigned int len);
-    void logWrite(unsigned char *buf, unsigned int len);
+    void logRead(unsigned char* buf, unsigned int len);
+    void logWrite(unsigned char* buf, unsigned int len);
     void logText(std::string message);
 
 private:
diff --git a/source/RobotAPI/libraries/drivers/WeissHapticSensor/CMakeLists.txt b/source/RobotAPI/libraries/drivers/WeissHapticSensor/CMakeLists.txt
index 69c5f8a2b3968cf42865d9755d9ee15c585dd829..0097fc9571d1b23b2794821be4ee36f038405082 100644
--- a/source/RobotAPI/libraries/drivers/WeissHapticSensor/CMakeLists.txt
+++ b/source/RobotAPI/libraries/drivers/WeissHapticSensor/CMakeLists.txt
@@ -10,8 +10,8 @@ if (Eigen3_FOUND)
 endif()
 
 set(LIB_NAME       WeissHapticSensor)
-set(LIB_VERSION    0.1.0)
-set(LIB_SOVERSION  0)
+
+
 
 set(LIBS RobotAPIUnits ArmarXCoreObservers ArmarXCoreEigen3Variants)
 
@@ -43,4 +43,4 @@ set(LIB_HEADERS
     CalibrationHelper.h
 )
 
-armarx_add_library("${LIB_NAME}" "${LIB_VERSION}" "${LIB_SOVERSION}" "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
+armarx_add_library("${LIB_NAME}"  "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
diff --git a/source/RobotAPI/libraries/drivers/WeissHapticSensor/CalibrationHelper.cpp b/source/RobotAPI/libraries/drivers/WeissHapticSensor/CalibrationHelper.cpp
index 244edebedae87da6a36d37eff64a6bd955d0c682..0497f62321d65cb6b724e257ff3fd466fb15acc2 100644
--- a/source/RobotAPI/libraries/drivers/WeissHapticSensor/CalibrationHelper.cpp
+++ b/source/RobotAPI/libraries/drivers/WeissHapticSensor/CalibrationHelper.cpp
@@ -17,7 +17,7 @@ void CalibrationHelper::addNoiseSample(Eigen::MatrixXf data)
 
 bool CalibrationHelper::addMaxValueSample(Eigen::MatrixXf data)
 {
-    if(data.maxCoeff() <= noiseThreshold)
+    if (data.maxCoeff() <= noiseThreshold)
     {
         this->maximumValues = this->maximumValues.cwiseMax(data);
         return true;
@@ -50,15 +50,17 @@ int CalibrationHelper::getNoiseSampleCount()
 
 Eigen::MatrixXf CalibrationHelper::getMatrixAverage(std::vector<Eigen::MatrixXf> samples)
 {
-    if(samples.size() == 0)
+    if (samples.size() == 0)
     {
         throw std::runtime_error("Average of zero samples not possible");
     }
 
     Eigen::MatrixXf sum = samples.at(0);
-    for(std::vector<Eigen::MatrixXf>::iterator it = samples.begin() + 1; it != samples.end(); ++it)
+
+    for (std::vector<Eigen::MatrixXf>::iterator it = samples.begin() + 1; it != samples.end(); ++it)
     {
         sum += *it;
     }
+
     return sum / (float)samples.size();
 }
diff --git a/source/RobotAPI/libraries/drivers/WeissHapticSensor/Checksum.cpp b/source/RobotAPI/libraries/drivers/WeissHapticSensor/Checksum.cpp
index 15b3cecfff3a5073d476ce5c544f6ad617696859..44ebd21ff0fa2cbfd03f22e32d4c5670349c4f3c 100644
--- a/source/RobotAPI/libraries/drivers/WeissHapticSensor/Checksum.cpp
+++ b/source/RobotAPI/libraries/drivers/WeissHapticSensor/Checksum.cpp
@@ -8,7 +8,8 @@
  * corresponding to x^16 + x^12 + x^5 + 1
  */
 
-const unsigned short Checksum::CRC_TABLE_CCITT16[256] = {
+const unsigned short Checksum::CRC_TABLE_CCITT16[256] =
+{
     0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50a5, 0x60c6, 0x70e7,
     0x8108, 0x9129, 0xa14a, 0xb16b, 0xc18c, 0xd1ad, 0xe1ce, 0xf1ef,
     0x1231, 0x0210, 0x3273, 0x2252, 0x52b5, 0x4294, 0x72f7, 0x62d6,
@@ -59,15 +60,16 @@ const unsigned short Checksum::CRC_TABLE_CCITT16[256] = {
  * @return CRC16 checksum
  */
 
-unsigned short Checksum::Update_crc16( unsigned char *data, unsigned int size, unsigned short crc )
+unsigned short Checksum::Update_crc16(unsigned char* data, unsigned int size, unsigned short crc)
 {
     unsigned long c;
 
     /* process each byte prior to checksum field */
-    for ( c=0; c < size; c++ )
+    for (c = 0; c < size; c++)
     {
-        crc = CRC_TABLE_CCITT16[ ( crc ^ *( data ++ )) & 0x00FF ] ^ ( crc >> 8 );
+        crc = CRC_TABLE_CCITT16[(crc ^ * (data ++)) & 0x00FF ] ^ (crc >> 8);
     }
+
     return crc;
 }
 
@@ -80,15 +82,15 @@ unsigned short Checksum::Update_crc16( unsigned char *data, unsigned int size, u
  * Note: The checksum generated by this function is NOT according
  * to CCITT standard!
  *
- * @param *data		Points to the byte array from which checksum should
- * 					be calculated
- * @param size		Size of the byte array
+ * @param *data     Points to the byte array from which checksum should
+ *                  be calculated
+ * @param size      Size of the byte array
  *
  * @return CRC16 checksum
  */
 
-unsigned short Checksum::Crc16( unsigned char *data, unsigned int size )
+unsigned short Checksum::Crc16(unsigned char* data, unsigned int size)
 {
-    return( Update_crc16( data, size, 0xffff ) );
+    return (Update_crc16(data, size, 0xffff));
 }
 
diff --git a/source/RobotAPI/libraries/drivers/WeissHapticSensor/Checksum.h b/source/RobotAPI/libraries/drivers/WeissHapticSensor/Checksum.h
index 7603e1b69f4a71856b801a716c2454e18024ffca..2561f727b247456d73eef711a053220f96b3ecf6 100644
--- a/source/RobotAPI/libraries/drivers/WeissHapticSensor/Checksum.h
+++ b/source/RobotAPI/libraries/drivers/WeissHapticSensor/Checksum.h
@@ -4,8 +4,8 @@
 class Checksum
 {
 public:
-    static unsigned short Crc16( unsigned char *data, unsigned int size );
-    static unsigned short Update_crc16( unsigned char *data, unsigned int size, unsigned short crc );
+    static unsigned short Crc16(unsigned char* data, unsigned int size);
+    static unsigned short Update_crc16(unsigned char* data, unsigned int size, unsigned short crc);
 
 private:
     static const unsigned short CRC_TABLE_CCITT16[256];
diff --git a/source/RobotAPI/libraries/drivers/WeissHapticSensor/Response.h b/source/RobotAPI/libraries/drivers/WeissHapticSensor/Response.h
index 933f45af0cc5372578274f6a21316fddd13c7691..a6ea680edea82f600fa4e52349343ecb215869ba 100644
--- a/source/RobotAPI/libraries/drivers/WeissHapticSensor/Response.h
+++ b/source/RobotAPI/libraries/drivers/WeissHapticSensor/Response.h
@@ -7,21 +7,22 @@
 #include <stdexcept>
 #include <boost/format.hpp>
 #include <vector>
-#include <Core/core/logging/Logging.h>
+#include <ArmarXCore/core/logging/Logging.h>
 
-struct Response {
+struct Response
+{
 public:
-    Response(int res, unsigned char cmdId, status_t status, const std::vector<unsigned char> &data, unsigned int len)
+    Response(int res, unsigned char cmdId, status_t status, const std::vector<unsigned char>& data, unsigned int len)
         : res(res), cmdId(cmdId), status(status), data(data), len(len) {}
 
     unsigned int getUInt(int index)
     {
-        return (unsigned int)data[index] | ( (unsigned int)data[index + 1] << 8) | ( (unsigned int)data[index + 2] << 16) | ( (unsigned int)data[index + 3] << 24);
+        return (unsigned int)data[index] | ((unsigned int)data[index + 1] << 8) | ((unsigned int)data[index + 2] << 16) | ((unsigned int)data[index + 3] << 24);
     }
 
     unsigned short getShort(int index)
     {
-        return (unsigned short)data[index] | ( (unsigned short)data[index + 1] << 8);
+        return (unsigned short)data[index] | ((unsigned short)data[index + 1] << 8);
     }
     unsigned char getByte(int index)
     {
@@ -30,7 +31,8 @@ public:
 
     void ensureMinLength(int len)
     {
-        if ( res < len ) {
+        if (res < len)
+        {
             //std::strstream strStream;
             //strStream << "Response length is too short, should be = " << len << " (is " << res << ")";
             //throw std::runtime_error(strStream.str());
@@ -40,18 +42,21 @@ public:
 
     void ensureSuccess()
     {
-        if ( status != E_SUCCESS )
+        if (status != E_SUCCESS)
         {
             //std::strstream strStream;
             //strStream << "Command not successful: " << status_to_str( status );
             //throw std::runtime_error(strStream.str());
             std::stringstream ss;
             ss << " status != E_SUCCESS";
-            for(int i=0; i<(int)len; i++){
+
+            for (int i = 0; i < (int)len; i++)
+            {
                 ss << boost::format("%02X ") % (int)data[i];
             }
+
             ARMARX_ERROR_S << ss.str();
-            throw TransmissionException(str(boost::format("Command not successful: %1% (0x%2$02X)") % status_to_str( status ) % status));
+            throw TransmissionException(str(boost::format("Command not successful: %1% (0x%2$02X)") % status_to_str(status) % status));
         }
     }
 
@@ -61,42 +66,105 @@ public:
     std::vector<unsigned char> data;
     unsigned int len;
 
-    static const char* status_to_str( status_t status )
+    static const char* status_to_str(status_t status)
     {
-        switch( status )
+        switch (status)
         {
-            case E_SUCCESS:					return( "No error" );
-            case E_NOT_AVAILABLE:			return( "Service or data is not available" );
-            case E_NO_SENSOR:				return( "No sensor connected" );
-            case E_NOT_INITIALIZED:			return( "The device is not initialized" );
-            case E_ALREADY_RUNNING:			return( "Service is already running" );
-            case E_FEATURE_NOT_SUPPORTED:	return( "The requested feature is not supported" );
-            case E_INCONSISTENT_DATA:		return( "One or more dependent parameters mismatch" );
-            case E_TIMEOUT:					return( "Timeout error" );
-            case E_READ_ERROR:				return( "Error while reading from a device" );
-            case E_WRITE_ERROR:				return( "Error while writing to a device" );
-            case E_INSUFFICIENT_RESOURCES:	return( "No memory available" );
-            case E_CHECKSUM_ERROR:			return( "Checksum error" );
-            case E_NO_PARAM_EXPECTED:		return( "No parameters expected" );
-            case E_NOT_ENOUGH_PARAMS:		return( "Not enough parameters" );
-            case E_CMD_UNKNOWN:				return( "Unknown command" );
-            case E_CMD_FORMAT_ERROR:		return( "Command format error" );
-            case E_ACCESS_DENIED:			return( "Access denied" );
-            case E_ALREADY_OPEN:			return( "Interface already open" );
-            case E_CMD_FAILED:				return( "Command failed" );
-            case E_CMD_ABORTED:				return( "Command aborted" );
-            case E_INVALID_HANDLE:			return( "Invalid handle" );
-            case E_NOT_FOUND:				return( "Device not found" );
-            case E_NOT_OPEN:				return( "Device not open" );
-            case E_IO_ERROR:				return( "General I/O-Error" );
-            case E_INVALID_PARAMETER:		return( "Invalid parameter" );
-            case E_INDEX_OUT_OF_BOUNDS:		return( "Index out of bounds" );
-            case E_CMD_PENDING:				return( "Command is pending..." );
-            case E_OVERRUN:					return( "Data overrun" );
-            case E_RANGE_ERROR:				return( "Value out of range" );
-            case E_AXIS_BLOCKED:			return( "Axis is blocked" );
-            case E_FILE_EXISTS:				return( "File already exists" );
-            default:						return( "Internal error. Unknown error code." );
+            case E_SUCCESS:
+                return ("No error");
+
+            case E_NOT_AVAILABLE:
+                return ("Service or data is not available");
+
+            case E_NO_SENSOR:
+                return ("No sensor connected");
+
+            case E_NOT_INITIALIZED:
+                return ("The device is not initialized");
+
+            case E_ALREADY_RUNNING:
+                return ("Service is already running");
+
+            case E_FEATURE_NOT_SUPPORTED:
+                return ("The requested feature is not supported");
+
+            case E_INCONSISTENT_DATA:
+                return ("One or more dependent parameters mismatch");
+
+            case E_TIMEOUT:
+                return ("Timeout error");
+
+            case E_READ_ERROR:
+                return ("Error while reading from a device");
+
+            case E_WRITE_ERROR:
+                return ("Error while writing to a device");
+
+            case E_INSUFFICIENT_RESOURCES:
+                return ("No memory available");
+
+            case E_CHECKSUM_ERROR:
+                return ("Checksum error");
+
+            case E_NO_PARAM_EXPECTED:
+                return ("No parameters expected");
+
+            case E_NOT_ENOUGH_PARAMS:
+                return ("Not enough parameters");
+
+            case E_CMD_UNKNOWN:
+                return ("Unknown command");
+
+            case E_CMD_FORMAT_ERROR:
+                return ("Command format error");
+
+            case E_ACCESS_DENIED:
+                return ("Access denied");
+
+            case E_ALREADY_OPEN:
+                return ("Interface already open");
+
+            case E_CMD_FAILED:
+                return ("Command failed");
+
+            case E_CMD_ABORTED:
+                return ("Command aborted");
+
+            case E_INVALID_HANDLE:
+                return ("Invalid handle");
+
+            case E_NOT_FOUND:
+                return ("Device not found");
+
+            case E_NOT_OPEN:
+                return ("Device not open");
+
+            case E_IO_ERROR:
+                return ("General I/O-Error");
+
+            case E_INVALID_PARAMETER:
+                return ("Invalid parameter");
+
+            case E_INDEX_OUT_OF_BOUNDS:
+                return ("Index out of bounds");
+
+            case E_CMD_PENDING:
+                return ("Command is pending...");
+
+            case E_OVERRUN:
+                return ("Data overrun");
+
+            case E_RANGE_ERROR:
+                return ("Value out of range");
+
+            case E_AXIS_BLOCKED:
+                return ("Axis is blocked");
+
+            case E_FILE_EXISTS:
+                return ("File already exists");
+
+            default:
+                return ("Internal error. Unknown error code.");
         }
     }
 };
diff --git a/source/RobotAPI/libraries/drivers/WeissHapticSensor/SerialInterface.cpp b/source/RobotAPI/libraries/drivers/WeissHapticSensor/SerialInterface.cpp
index 387d2f5236177c7f4583460325209259bad95993..bdf17ddceb516bbe65fa07311767601770876f5b 100644
--- a/source/RobotAPI/libraries/drivers/WeissHapticSensor/SerialInterface.cpp
+++ b/source/RobotAPI/libraries/drivers/WeissHapticSensor/SerialInterface.cpp
@@ -15,98 +15,127 @@
 #include <boost/lexical_cast.hpp>
 #include <boost/format.hpp>
 
-static inline tcflag_t __bitrate_to_flag( unsigned int bitrate )
+static inline tcflag_t __bitrate_to_flag(unsigned int bitrate)
 {
-    switch( bitrate )
+    switch (bitrate)
     {
-        case   1200: return   B1200;
-        case   2400: return   B2400;
-        case   4800: return   B4800;
-        case   9600: return   B9600;
-        case  19200: return  B19200;
-        case  38400: return  B38400;
-        case  57600: return  B57600;
-        case 115200: return B115200;
-        case 230400: return B230400;
-        case 460800: return B460800;
-        default: return 0;
+        case   1200:
+            return   B1200;
+
+        case   2400:
+            return   B2400;
+
+        case   4800:
+            return   B4800;
+
+        case   9600:
+            return   B9600;
+
+        case  19200:
+            return  B19200;
+
+        case  38400:
+            return  B38400;
+
+        case  57600:
+            return  B57600;
+
+        case 115200:
+            return B115200;
+
+        case 230400:
+            return B230400;
+
+        case 460800:
+            return B460800;
+
+        default:
+            return 0;
     }
 }
 
 
-SerialInterface::SerialInterface(const char *device, unsigned int bitrate)
+SerialInterface::SerialInterface(const char* device, unsigned int bitrate)
 {
     this->device = device;
     this->bitrate = bitrate;
-	this->fd = -1;
+    this->fd = -1;
 }
 
-SerialInterface::~SerialInterface() {
+SerialInterface::~SerialInterface()
+{
 
 }
 
-int SerialInterface::open() {
+int SerialInterface::open()
+{
     // Convert bitrate to flag
     tcflag_t bitrate = __bitrate_to_flag(this->bitrate);
-    if ( bitrate == 0 )
+
+    if (bitrate == 0)
     {
-        fprintf( stderr, "Invalid bitrate '%d' for serial device\n", this->bitrate );
+        fprintf(stderr, "Invalid bitrate '%d' for serial device\n", this->bitrate);
         return -1;
     }
 
 
     // Open serial device
-    fd = ::open( device, O_RDWR | O_NOCTTY );
-    if ( fd < 0 )
+    fd = ::open(device, O_RDWR | O_NOCTTY);
+
+    if (fd < 0)
     {
-        fprintf( stderr, "Failed to open serial device '%s' (errno: %s)\n", device, strerror(errno) );
+        fprintf(stderr, "Failed to open serial device '%s' (errno: %s)\n", device, strerror(errno));
         return -1;
     }
+
     if (::ioctl(fd, TIOCEXCL))
     {
-        fprintf( stderr, "Failed to lock serial device '%s' (errno: %s)\n", device, strerror(errno) );
+        fprintf(stderr, "Failed to lock serial device '%s' (errno: %s)\n", device, strerror(errno));
         return -1;
     }
 
 
 
     // Check if device is a terminal device
-    if ( !isatty( fd ) )
+    if (!isatty(fd))
     {
-        fprintf( stderr, "Device '%s' is not a terminal device (errno: %s)!\n", device, strerror(errno) );
-        ::close( fd );
+        fprintf(stderr, "Device '%s' is not a terminal device (errno: %s)!\n", device, strerror(errno));
+        ::close(fd);
         return -1;
     }
 
     struct termios settings;
+
     // Set input flags
     settings.c_iflag =  IGNBRK          // Ignore BREAKS on Input
-                     |  IGNPAR;         // No Parity
-                                        // ICRNL: map CR to NL (otherwise a CR input on the other computer will not terminate input)
+                        |  IGNPAR;         // No Parity
+
+    // ICRNL: map CR to NL (otherwise a CR input on the other computer will not terminate input)
 
     // Set output flags
-    settings.c_oflag = 0;				// Raw output
+    settings.c_oflag = 0;               // Raw output
 
     // Set controlflags
     settings.c_cflag = bitrate
-                     | CS8              // 8 bits per byte
-                     | CSTOPB			// Stop bit
-                     | CREAD            // characters may be read
-                     | CLOCAL;          // ignore modem state, local connection
+                       | CS8              // 8 bits per byte
+                       | CSTOPB           // Stop bit
+                       | CREAD            // characters may be read
+                       | CLOCAL;          // ignore modem state, local connection
 
     // Set local flags
-    settings.c_lflag = 0;				// Other option: ICANON = enable canonical input
+    settings.c_lflag = 0;               // Other option: ICANON = enable canonical input
 
     // Set maximum wait time on input - cf. Linux Serial Programming HowTo, non-canonical mode
     // http://tldp.org/HOWTO/Serial-Programming-HOWTO/x115.html
-    settings.c_cc[VTIME] = 10;			// 0 means timer is not uses
+    settings.c_cc[VTIME] = 10;          // 0 means timer is not uses
 
     // Set minimum bytes to read
-    settings.c_cc[VMIN]  = 0;			// 1 means wait until at least 1 character is received
+    settings.c_cc[VMIN]  = 0;           // 1 means wait until at least 1 character is received
 
     // Now clean the modem line and activate the settings for the port
-    tcflush( fd, TCIFLUSH );
-    tcsetattr( fd, TCSANOW, &settings );
+    tcflush(fd, TCIFLUSH);
+
+    tcsetattr(fd, TCSANOW, &settings);
 
     connected = true;
 
@@ -115,16 +144,21 @@ int SerialInterface::open() {
 
 void SerialInterface::close()
 {
-    if(connected) ::close(fd);
+    if (connected)
+    {
+        ::close(fd);
+    }
+
     connected = false;
 }
 
-int SerialInterface::readInternal( unsigned char *buf, unsigned int len)
+int SerialInterface::readInternal(unsigned char* buf, unsigned int len)
 {
     int res;
 
-    res = blockingReadAll( buf, len );
-    if ( res < 0 )
+    res = blockingReadAll(buf, len);
+
+    if (res < 0)
     {
         std::cerr << "Failed to read from serial device" << std::endl;
     }
@@ -133,38 +167,44 @@ int SerialInterface::readInternal( unsigned char *buf, unsigned int len)
 
 }
 
-int SerialInterface::blockingReadAll(unsigned char *buf, unsigned int len)
+int SerialInterface::blockingReadAll(unsigned char* buf, unsigned int len)
 {
     int dataToRead = len;
+
     while (1)
     {
-        int res = ::read( fd, buf, dataToRead );
+        int res = ::read(fd, buf, dataToRead);
+
         if (res < 0)
         {
             return res;
         }
+
         dataToRead -= res;
         buf += res;
+
         if (dataToRead == 0)
         {
             return len;
         }
+
         if (dataToRead < 0)
         {
             throw new std::runtime_error("Internal error: dataToRead < 0");
         }
+
         usleep(1);
     }
 }
 
-int SerialInterface::writeInternal( unsigned char *buf, unsigned int len)
+int SerialInterface::writeInternal(unsigned char* buf, unsigned int len)
 {
-    return( ::write( fd, (void *) buf, len ) );
+    return (::write(fd, (void*) buf, len));
 }
 
 
 std::string SerialInterface::toString() const
 {
     return str(boost::format("SerialInterface(connected=%1%, device=%2%, bitrate=%3%, fd=%4%)")
-            % connected % device % bitrate % fd);
+               % connected % device % bitrate % fd);
 }
diff --git a/source/RobotAPI/libraries/drivers/WeissHapticSensor/SerialInterface.h b/source/RobotAPI/libraries/drivers/WeissHapticSensor/SerialInterface.h
index c64e501d085f0e752ec1ea8bd3f1e7bd018d3d01..33770d3b817c42b325e85b81e719c7bf68e6a005 100644
--- a/source/RobotAPI/libraries/drivers/WeissHapticSensor/SerialInterface.h
+++ b/source/RobotAPI/libraries/drivers/WeissHapticSensor/SerialInterface.h
@@ -5,9 +5,10 @@
 #include <iostream>
 
 
-class SerialInterface : public AbstractInterface {
+class SerialInterface : public AbstractInterface
+{
 public:
-    SerialInterface(const char *device, const unsigned int bitrate);
+    SerialInterface(const char* device, const unsigned int bitrate);
     virtual ~SerialInterface();
 
     virtual int open();
@@ -16,15 +17,15 @@ public:
     virtual std::string toString() const;
 
 protected:
-    virtual int readInternal( unsigned char *, unsigned int );
-    virtual int writeInternal( unsigned char *, unsigned int );
+    virtual int readInternal(unsigned char*, unsigned int);
+    virtual int writeInternal(unsigned char*, unsigned int);
 
 private:
-    const char *device;
+    const char* device;
     unsigned int bitrate;
     int fd;
 
-    int blockingReadAll(unsigned char *buf, unsigned int len);
+    int blockingReadAll(unsigned char* buf, unsigned int len);
 };
 
 #endif // SERIALINTERFACE_H
diff --git a/source/RobotAPI/libraries/drivers/WeissHapticSensor/TactileSensor.cpp b/source/RobotAPI/libraries/drivers/WeissHapticSensor/TactileSensor.cpp
index 639beb12b73aa2fba7b15b67e2b587804afad679..da246c4414726ac488c386e8266b4e4ab2997206 100644
--- a/source/RobotAPI/libraries/drivers/WeissHapticSensor/TactileSensor.cpp
+++ b/source/RobotAPI/libraries/drivers/WeissHapticSensor/TactileSensor.cpp
@@ -10,15 +10,16 @@ TactileSensor::TactileSensor(boost::shared_ptr<AbstractInterface> interface)
     this->interface = interface;
 }
 
-TactileSensor::~TactileSensor() {
+TactileSensor::~TactileSensor()
+{
     // TODO Auto-generated destructor stub
 }
 
-tac_matrix_info_t TactileSensor::getMatrixInformation( )
+tac_matrix_info_t TactileSensor::getMatrixInformation()
 {
     unsigned char payload[0];
 
-    Response response = interface->submitCmd( 0x30, payload, sizeof(payload), false );
+    Response response = interface->submitCmd(0x30, payload, sizeof(payload), false);
     response.ensureMinLength(12);
     response.ensureSuccess();
 
@@ -34,22 +35,25 @@ tac_matrix_info_t TactileSensor::getMatrixInformation( )
     return matrix_info;
 }
 
-void TactileSensor::printMatrixInfo( tac_matrix_info_t *mi )
+void TactileSensor::printMatrixInfo(tac_matrix_info_t* mi)
 {
     printf("res_x = %d, res_y = %d, cell_width = %d, cell_height = %d, fullscale = %X\n",
-        mi->res_x, mi->res_y, mi->cell_width, mi->cell_height, mi->fullscale);
+           mi->res_x, mi->res_y, mi->cell_width, mi->cell_height, mi->fullscale);
 }
 
-void TactileSensor::printMatrix ( short *matrix, int width, int height )
+void TactileSensor::printMatrix(short* matrix, int width, int height)
 {
     int x, y;
+
     for (y = 0; y < height; y++)
     {
         printf("%03X", matrix[y * width]);
+
         for (x = 1; x < width; x++)
         {
             printf(", %03X", matrix[y * width + x]);
         }
+
         printf("\n");
     }
 }
@@ -58,17 +62,19 @@ FrameData TactileSensor::readSingleFrame()
 {
     unsigned char payload[1];
     payload[0] = 0x00; // FLAGS = 0
-    Response response = interface->submitCmd( 0x20, payload, sizeof(payload), false );
+    Response response = interface->submitCmd(0x20, payload, sizeof(payload), false);
     return getFrameData(&response);
 }
 PeriodicFrameData TactileSensor::receicePeriodicFrame()
 {
     Response response = interface->receiveWithoutChecks();
-    if(response.cmdId == 0x21)
+
+    if (response.cmdId == 0x21)
     {
         response = interface->receiveWithoutChecks();
     }
-    if(response.cmdId == 0x00)
+
+    if (response.cmdId == 0x00)
     {
         return getPeriodicFrameData(&response);
     }
@@ -78,27 +84,29 @@ PeriodicFrameData TactileSensor::receicePeriodicFrame()
     }
 }
 
-PeriodicFrameData TactileSensor::getPeriodicFrameData(Response *response)
+PeriodicFrameData TactileSensor::getPeriodicFrameData(Response* response)
 {
     response->ensureMinLength(7);
 
-    unsigned int timestamp = response->getUInt( 0 );
+    unsigned int timestamp = response->getUInt(0);
     int offset = 5;
 
     int count = (response->len - offset) / 2;
     int i;
     boost::shared_ptr<std::vector<short> > data;
     data.reset(new std::vector<short>(count, 0));
+
     //short* data = new short[ count ];
-    for(i = 0; i < count; i++)
+    for (i = 0; i < count; i++)
     {
-        short value = response->getShort(i*2 + offset);
+        short value = response->getShort(i * 2 + offset);
         (*data)[i] = value;
     }
+
     return PeriodicFrameData(data, count, timestamp);
 }
 
-FrameData TactileSensor::getFrameData(Response *response)
+FrameData TactileSensor::getFrameData(Response* response)
 {
     response->ensureMinLength(7);
     response->ensureSuccess();
@@ -109,82 +117,94 @@ FrameData TactileSensor::getFrameData(Response *response)
     int i;
     boost::shared_ptr<std::vector<short> > data;
     data.reset(new std::vector<short>(count, 0));
-    for(i = 0; i < count; i++)
+
+    for (i = 0; i < count; i++)
     {
-        short value = response->getShort(i*2 + offset);
+        short value = response->getShort(i * 2 + offset);
         (*data)[i] = value;
     }
+
     return FrameData(data, count);
 }
 
-void TactileSensor::startPeriodicFrameAcquisition( unsigned short delay_ms )
+void TactileSensor::startPeriodicFrameAcquisition(unsigned short delay_ms)
 {
     unsigned char payload[3];
     payload[0] = 0x00; // FLAGS = 0
     payload[1] = delay_ms & 0xFF;
     payload[2] = (delay_ms >> 8) & 0xFF;
-    interface->fireAndForgetCmd( 0x21, payload, sizeof(payload), false );
+    interface->fireAndForgetCmd(0x21, payload, sizeof(payload), false);
 }
-void TactileSensor::stopPeriodicFrameAcquisition( void )
+void TactileSensor::stopPeriodicFrameAcquisition(void)
 {
-    while(1)
+    while (1)
     {
         unsigned char payload[0];
-        interface->fireAndForgetCmd( 0x22, payload, sizeof(payload), false );
+        interface->fireAndForgetCmd(0x22, payload, sizeof(payload), false);
         int waitCount = 10;
+
         while (waitCount > 0)
         {
             Response response = interface->receiveWithoutChecks();
-            if(response.cmdId == 0x22) {
+
+            if (response.cmdId == 0x22)
+            {
                 return;
             }
             else
             {
                 cout <<  boost::format("stopPeriodicFrameAcquisition :: Discarding Response with ID 0x%02X") % (int)response.cmdId << endl;
             }
+
             waitCount--;
         }
     }
 }
-void TactileSensor::tareSensorMatrix( unsigned char operation )
+void TactileSensor::tareSensorMatrix(unsigned char operation)
 {
     unsigned char payload[1];
     payload[0] = operation; // OPERATION: 0 = un-tare the sensor matrix using the currently set threshold value, 1 = tare the sensor matrix
-    Response response = interface->submitCmd( 0x23, payload, sizeof(payload), false );
+    Response response = interface->submitCmd(0x23, payload, sizeof(payload), false);
     response.ensureMinLength(2);
     response.ensureSuccess();
 }
-void TactileSensor::setAquisitionWindow( unsigned char x1, unsigned char y1, unsigned char x2, unsigned char y2 )
+void TactileSensor::setAquisitionWindow(unsigned char x1, unsigned char y1, unsigned char x2, unsigned char y2)
 {
     unsigned char payload[4];
     payload[0] = x1;
     payload[1] = y1;
     payload[2] = x2;
     payload[3] = y2;
-    Response response = interface->submitCmd( 0x31, payload, sizeof(payload), false );
+    Response response = interface->submitCmd(0x31, payload, sizeof(payload), false);
     response.ensureMinLength(2);
     response.ensureSuccess();
 }
-int TactileSensor::setAdvanvedAcquisitionMask( char *mask ) { return 0; }
-int TactileSensor::getAcquisitionMask( char **mask, int *mask_len ) { return 0; }
-void TactileSensor::setThreshold( short threshold )
+int TactileSensor::setAdvanvedAcquisitionMask(char* mask)
+{
+    return 0;
+}
+int TactileSensor::getAcquisitionMask(char** mask, int* mask_len)
+{
+    return 0;
+}
+void TactileSensor::setThreshold(short threshold)
 {
     unsigned char payload[2];
     payload[0] = threshold & 0xFF;
     payload[1] = (threshold >> 8) & 0xFF;
-    Response response = interface->submitCmd( 0x34, payload, sizeof(payload), false );
+    Response response = interface->submitCmd(0x34, payload, sizeof(payload), false);
     response.ensureMinLength(2);
     response.ensureSuccess();
 }
 unsigned short TactileSensor::getThreshold()
 {
     unsigned char payload[0];
-    Response response = interface->submitCmd( 0x35, payload, sizeof(payload), false );
+    Response response = interface->submitCmd(0x35, payload, sizeof(payload), false);
     response.ensureMinLength(2);
     response.ensureSuccess();
     return response.getShort(2);
 }
-void TactileSensor::setFrontEndGain( unsigned char gain )
+void TactileSensor::setFrontEndGain(unsigned char gain)
 {
     /*
      * Adjust the pressure sensitivity of a matrix by setting the gain of the Analog Front-End. The gain can
@@ -193,7 +213,7 @@ void TactileSensor::setFrontEndGain( unsigned char gain )
      */
     unsigned char payload[1];
     payload[0] = gain;
-    Response response = interface->submitCmd( 0x36, payload, sizeof(payload), false );
+    Response response = interface->submitCmd(0x36, payload, sizeof(payload), false);
     response.ensureMinLength(2);
     response.ensureSuccess();
 }
@@ -204,7 +224,7 @@ unsigned char TactileSensor::getFrontEndGain()
      * 255, where 0 is the most insensitive (lowest gain) and 255 is the most sensitive (highest gain) setting.
      */
     unsigned char payload[0];
-    Response response = interface->submitCmd( 0x37, payload, sizeof(payload), false );
+    Response response = interface->submitCmd(0x37, payload, sizeof(payload), false);
     response.ensureMinLength(3);
     response.ensureSuccess();
     unsigned char gain = response.getByte(2);
@@ -216,7 +236,7 @@ std::string TactileSensor::getSensorType()
      * Return a string containing the sensor type.
      */
     unsigned char payload[0];
-    Response response = interface->submitCmd( 0x38, payload, sizeof(payload), false );
+    Response response = interface->submitCmd(0x38, payload, sizeof(payload), false);
     response.ensureMinLength(2);
     response.ensureSuccess();
     std::string type = std::string((char*)response.data.data() + 2, response.len - 2);
@@ -225,7 +245,7 @@ std::string TactileSensor::getSensorType()
 float TactileSensor::readDeviceTemperature()
 {
     unsigned char payload[0];
-    Response response = interface->submitCmd( 0x46, payload, sizeof(payload), false );
+    Response response = interface->submitCmd(0x46, payload, sizeof(payload), false);
     response.ensureMinLength(2);
     short value = (short)response.getShort(2);
     return value * 0.1f;
@@ -233,7 +253,7 @@ float TactileSensor::readDeviceTemperature()
 tac_system_information_t TactileSensor::getSystemInformation()
 {
     unsigned char payload[0];
-    Response response = interface->submitCmd( 0x50, payload, sizeof(payload), false );
+    Response response = interface->submitCmd(0x50, payload, sizeof(payload), false);
     response.ensureMinLength(9);
     response.ensureSuccess();
     tac_system_information_t si;
@@ -250,45 +270,51 @@ void TactileSensor::printSystemInformation(tac_system_information_t si)
     int v3 = (si.fw_version & 0x00F0) >> 4;
     int v4 = (si.fw_version & 0x000F) >> 0;
     cout << boost::format("System Type=%1%, Hardware Revision=%2%, Firmware Version=%3%.%4%.%5%.%6% (0x%7$04X), Serial Number=%8%")
-        % (int)si.type % (int)si.hw_rev % v1 % v2 % v3 % v4 % si.fw_version % si.sn << endl;
+         % (int)si.type % (int)si.hw_rev % v1 % v2 % v3 % v4 % si.fw_version % si.sn << endl;
 }
 void TactileSensor::setDeviceTag(string tag)
 {
-    unsigned char *payload = (unsigned char*)tag.c_str();
-    Response response = interface->submitCmd( 0x51, payload, tag.length(), false );
+    unsigned char* payload = (unsigned char*)tag.c_str();
+    Response response = interface->submitCmd(0x51, payload, tag.length(), false);
     response.ensureMinLength(2);
     response.ensureSuccess();
 }
 string TactileSensor::getDeviceTag()
 {
     unsigned char payload[0];
-    Response response = interface->submitCmd( 0x52, payload, sizeof(payload), false );
+    Response response = interface->submitCmd(0x52, payload, sizeof(payload), false);
     response.ensureMinLength(2);
     response.ensureSuccess();
     std::string tag = std::string((char*)response.data.data() + 2, response.len - 2);
     return tag;
 }
 
-bool TactileSensor::tryGetDeviceTag(string &tag)
+bool TactileSensor::tryGetDeviceTag(string& tag)
 {
     unsigned char payload[0];
-    Response response = interface->submitCmd( 0x52, payload, sizeof(payload), false );
+    Response response = interface->submitCmd(0x52, payload, sizeof(payload), false);
     response.ensureMinLength(2);
+
     if (response.status == E_NOT_AVAILABLE)
     {
         return false;
     }
+
     response.ensureSuccess();
     tag = std::string((char*)response.data.data() + 2, response.len - 2);
     return true;
 }
-int TactileSensor::loop( char *data, int data_len ) { return 0; }
+int TactileSensor::loop(char* data, int data_len)
+{
+    return 0;
+}
 
 string TactileSensor::getInterfaceInfo()
 {
     return interface->toString();
 }
 
-ostream& operator<<(ostream &strm, const TactileSensor &a) {
-  return strm << a.interface;
+ostream& operator<<(ostream& strm, const TactileSensor& a)
+{
+    return strm << a.interface;
 }
diff --git a/source/RobotAPI/libraries/drivers/WeissHapticSensor/TactileSensor.h b/source/RobotAPI/libraries/drivers/WeissHapticSensor/TactileSensor.h
index 7f36b86cc7fe1f0fa99f71ab2671d3b8f3dfe144..131d10d765f90dead6133a7e4d7a2a7e203bc7ee 100644
--- a/source/RobotAPI/libraries/drivers/WeissHapticSensor/TactileSensor.h
+++ b/source/RobotAPI/libraries/drivers/WeissHapticSensor/TactileSensor.h
@@ -5,21 +5,21 @@
 using namespace std;
 #include <boost/shared_ptr.hpp>
 
-#define extract_short( array, index )				( (unsigned short)array[index] | ( (unsigned short)array[index + 1] << 8 ) )
-#define TAC_CHECK_RES( res, expected, resp )	{ \
-                                                    if ( res < expected ) { \
-                                                        dbgPrint( "Response length is too short, should be = %d (is %d)\n", expected, res ); \
-                                                        if ( res > 0 ) free( resp ); \
-                                                        return -1; \
-                                                    } \
-                                                    status_t status = cmd_get_response_status( resp ); \
-                                                    if ( status != E_SUCCESS ) \
-                                                    { \
-                                                        dbgPrint( "Command not successful: %s\n", status_to_str( status ) ); \
-                                                        free( resp ); \
-                                                        return -1; \
-                                                    } \
-                                                }
+#define extract_short( array, index )               ( (unsigned short)array[index] | ( (unsigned short)array[index + 1] << 8 ) )
+#define TAC_CHECK_RES( res, expected, resp )    { \
+        if ( res < expected ) { \
+            dbgPrint( "Response length is too short, should be = %d (is %d)\n", expected, res ); \
+            if ( res > 0 ) free( resp ); \
+            return -1; \
+        } \
+        status_t status = cmd_get_response_status( resp ); \
+        if ( status != E_SUCCESS ) \
+        { \
+            dbgPrint( "Command not successful: %s\n", status_to_str( status ) ); \
+            free( resp ); \
+            return -1; \
+        } \
+    }
 
 typedef struct
 {
@@ -58,26 +58,27 @@ public:
     unsigned int timestamp;
 };
 
-class TactileSensor {
+class TactileSensor
+{
 public:
     TactileSensor(boost::shared_ptr<AbstractInterface> interface);
     virtual ~TactileSensor();
 
-    tac_matrix_info_t getMatrixInformation(  );
-    static void printMatrixInfo( tac_matrix_info_t *mi );
+    tac_matrix_info_t getMatrixInformation();
+    static void printMatrixInfo(tac_matrix_info_t* mi);
     FrameData readSingleFrame();
-    static void printMatrix ( short *matrix, int width, int height );
+    static void printMatrix(short* matrix, int width, int height);
 
-    void startPeriodicFrameAcquisition( unsigned short delay_ms );
-    void stopPeriodicFrameAcquisition( void );
+    void startPeriodicFrameAcquisition(unsigned short delay_ms);
+    void stopPeriodicFrameAcquisition(void);
     PeriodicFrameData receicePeriodicFrame();
-    void tareSensorMatrix( unsigned char operation );
-    void setAquisitionWindow( unsigned char x1, unsigned char y1, unsigned char x2, unsigned char y2 );
-    int setAdvanvedAcquisitionMask( char *mask );
-    int getAcquisitionMask( char **mask, int *mask_len );
-    void setThreshold( short threshold );
+    void tareSensorMatrix(unsigned char operation);
+    void setAquisitionWindow(unsigned char x1, unsigned char y1, unsigned char x2, unsigned char y2);
+    int setAdvanvedAcquisitionMask(char* mask);
+    int getAcquisitionMask(char** mask, int* mask_len);
+    void setThreshold(short threshold);
     unsigned short getThreshold();
-    void setFrontEndGain( unsigned char gain );
+    void setFrontEndGain(unsigned char gain);
     unsigned char getFrontEndGain();
     string getSensorType();
     float readDeviceTemperature();
@@ -85,20 +86,20 @@ public:
     static void printSystemInformation(tac_system_information_t si);
     void setDeviceTag(string tag);
     string getDeviceTag();
-    bool tryGetDeviceTag(string &tag);
-    int loop( char *data, int data_len );
+    bool tryGetDeviceTag(string& tag);
+    int loop(char* data, int data_len);
 
     string getInterfaceInfo();
 
 private:
     boost::shared_ptr<AbstractInterface> interface;
-    FrameData getFrameData(Response *response);
-    PeriodicFrameData getPeriodicFrameData(Response *response);
+    FrameData getFrameData(Response* response);
+    PeriodicFrameData getPeriodicFrameData(Response* response);
 
 private:
     friend std::ostream& operator<<(std::ostream&, const TactileSensor&);
 };
 
-std::ostream& operator<<(std::ostream &strm, const TactileSensor &a);
+std::ostream& operator<<(std::ostream& strm, const TactileSensor& a);
 
 #endif // TACTILESENSOR_H
diff --git a/source/RobotAPI/libraries/drivers/WeissHapticSensor/TransmissionException.h b/source/RobotAPI/libraries/drivers/WeissHapticSensor/TransmissionException.h
index 93710f7ec2476bb1be56dfafc5757ab8277f4051..c50a5f0931c55b4a6ffe3fa9a4f1cdfc495e49a9 100644
--- a/source/RobotAPI/libraries/drivers/WeissHapticSensor/TransmissionException.h
+++ b/source/RobotAPI/libraries/drivers/WeissHapticSensor/TransmissionException.h
@@ -3,17 +3,19 @@
 
 #include <stdexcept>
 
-class TransmissionException : public std::runtime_error {
+class TransmissionException : public std::runtime_error
+{
 public:
     TransmissionException(std::string message)
-    : runtime_error(message)
+        : runtime_error(message)
     { }
 };
 
-class ChecksumErrorException : public TransmissionException {
+class ChecksumErrorException : public TransmissionException
+{
 public:
     ChecksumErrorException(std::string message)
-    : TransmissionException(message)
+        : TransmissionException(message)
     { }
 };
 
diff --git a/source/RobotAPI/libraries/drivers/WeissHapticSensor/Types.h b/source/RobotAPI/libraries/drivers/WeissHapticSensor/Types.h
index 1fec7ca5f2535af8cea1197b7e87ca326d7d317e..19275ae1226d6e996e1c389d4ea4e2152d253547 100644
--- a/source/RobotAPI/libraries/drivers/WeissHapticSensor/Types.h
+++ b/source/RobotAPI/libraries/drivers/WeissHapticSensor/Types.h
@@ -11,7 +11,8 @@ typedef struct
 } msg_t;
 
 
-typedef enum {
+typedef enum
+{
     E_SUCCESS = 0,              // No error
     E_NOT_AVAILABLE,            // Device, service or data is not available
     E_NO_SENSOR,                // No sensor connected
@@ -33,19 +34,19 @@ typedef enum {
     E_CMD_FAILED,               // Command failed
     E_CMD_ABORTED,              // Command aborted
     E_INVALID_HANDLE,           // invalid handle
-    E_NOT_FOUND,        		// device not found
-    E_NOT_OPEN,        			// device not open
+    E_NOT_FOUND,                // device not found
+    E_NOT_OPEN,                 // device not open
     E_IO_ERROR,                 // I/O error
     E_INVALID_PARAMETER,        // invalid parameter
     E_INDEX_OUT_OF_BOUNDS,      // index out of bounds
     E_CMD_PENDING,              // Command was received correctly, but the execution needs more time. If the command was completely processed, another status message is returned indicating the command's result
-    E_OVERRUN,					// Data overrun
-    E_RANGE_ERROR,				// Range error
-    E_AXIS_BLOCKED,				// Axis is blocked
-    E_FILE_EXISTS				// File already exists
+    E_OVERRUN,                  // Data overrun
+    E_RANGE_ERROR,              // Range error
+    E_AXIS_BLOCKED,             // Axis is blocked
+    E_FILE_EXISTS               // File already exists
 } status_t;
 
 
-const char* status_to_str( status_t status );
+const char* status_to_str(status_t status);
 
 #endif // TYPES_H
diff --git a/source/RobotAPI/libraries/drivers/WeissHapticSensor/WeissHapticSensor.cpp b/source/RobotAPI/libraries/drivers/WeissHapticSensor/WeissHapticSensor.cpp
index 32b44ac4749e7ad76dae442406d97fef4211889c..cb5d80f620055dd65932e3bb73b4f754fb613fb7 100644
--- a/source/RobotAPI/libraries/drivers/WeissHapticSensor/WeissHapticSensor.cpp
+++ b/source/RobotAPI/libraries/drivers/WeissHapticSensor/WeissHapticSensor.cpp
@@ -10,7 +10,7 @@ WeissHapticSensor::WeissHapticSensor(std::string device, int minimumReportInterv
 {
     sensorTask = new RunningTask<WeissHapticSensor>(this, &WeissHapticSensor::frameAcquisitionTaskLoop);
     boost::smatch match;
-    boost::regex_search( device, match, boost::regex("\\w+$") );
+    boost::regex_search(device, match, boost::regex("\\w+$"));
     this->deviceFileName = match[0];
 }
 
@@ -37,7 +37,8 @@ void WeissHapticSensor::connect()
 
     //sensor->setDeviceTag("Test Tag");
     string tag;
-    if(sensor->tryGetDeviceTag(tag))
+
+    if (sensor->tryGetDeviceTag(tag))
     {
         ARMARX_INFO << "[" << device << "] Got Device Tag: " << tag;
         this->tag = tag;
@@ -118,7 +119,7 @@ void WeissHapticSensor::frameAcquisitionTaskLoop()
     math::SlidingWindowVectorMedian slidingMedian(mi.res_x * mi.res_y, 21); // inter sample dely ~= 3,7ms, 11 samples ~== 40ms delay
 
 
-    while(!sensorTask->isStopped())
+    while (!sensorTask->isStopped())
     {
         //ARMARX_INFO << deactivateSpam(1) << this << ": receicePeriodicFrame";
 
@@ -130,14 +131,17 @@ void WeissHapticSensor::frameAcquisitionTaskLoop()
             //cout << end - start << endl;
 
             std::vector<float> sensorValues;
-            for(int i = 0; i < mi.res_x * mi.res_y; i++)
+
+            for (int i = 0; i < mi.res_x * mi.res_y; i++)
             {
                 sensorValues.push_back(data.data->at(i));
             }
+
             slidingMedian.addEntry(sensorValues);
 
             MatrixFloatPtr matrix = new MatrixFloat(mi.res_y, mi.res_x);
             std::vector<float> filteredSensorValues = slidingMedian.getMedian();
+
             for (int y = 0; y < mi.res_y; y++)
             {
                 for (int x = 0; x < mi.res_x; x++)
@@ -165,18 +169,19 @@ void WeissHapticSensor::frameAcquisitionTaskLoop()
             writeMatrixToJs(matrix, nowTimestamp);
 
             IceUtil::Time interval = now - lastFrameTime;
-            if(interval.toMilliSeconds() >= minimumReportIntervalMs)
+
+            if (interval.toMilliSeconds() >= minimumReportIntervalMs)
             {
                 listenerPrx->reportSensorValues(device, tag, matrix, nowTimestamp);
                 lastFrameTime = now;
             }
         }
-        catch(ChecksumErrorException)
+        catch (ChecksumErrorException)
         {
             ARMARX_WARNING << "Caught ChecksumErrorException on " << device << ", skipping frame";
         }
 
-        if(setDeviceTagScheduled)
+        if (setDeviceTagScheduled)
         {
             boost::mutex::scoped_lock lock(mutex);
             setDeviceTagScheduled = false;
@@ -191,6 +196,7 @@ void WeissHapticSensor::frameAcquisitionTaskLoop()
             ARMARX_INFO << "[" << device << "] Starting periodic frame aquisition";
             sensor->startPeriodicFrameAcquisition(0);
         }
+
         //usleep(3000);
 
         //usleep(3000);
@@ -204,7 +210,7 @@ void WeissHapticSensor::frameAcquisitionTaskLoop()
 void WeissHapticSensor::writeMatrixToJs(MatrixFloatPtr matrix, TimestampVariantPtr timestamp)
 {
     //std::cout << "writeMatrixToJs" << std::endl;
-    if(jsWriter != NULL)
+    if (jsWriter != NULL)
     {
         jsWriter->writeLine(str(boost::format("%s.data.push([%i, %s]);") % deviceFileName % timestamp->getTimestamp() % matrix->toJsonRowMajor()));
     }
diff --git a/source/RobotAPI/libraries/drivers/WeissHapticSensor/WeissHapticSensor.h b/source/RobotAPI/libraries/drivers/WeissHapticSensor/WeissHapticSensor.h
index 897f104364008ebbb264f6f31e808ad2b077ebf4..a90f2fc4ccbb39228c8fa7acd90c8756145110a8 100644
--- a/source/RobotAPI/libraries/drivers/WeissHapticSensor/WeissHapticSensor.h
+++ b/source/RobotAPI/libraries/drivers/WeissHapticSensor/WeissHapticSensor.h
@@ -1,17 +1,17 @@
 #ifndef WEISSHAPTICSENSOR_H
 #define WEISSHAPTICSENSOR_H
 
-#include <Core/core/services/tasks/RunningTask.h>
-#include <Core/core/system/ImportExportComponent.h>
+#include <ArmarXCore/core/services/tasks/RunningTask.h>
+#include <ArmarXCore/core/system/ImportExportComponent.h>
 #include "SerialInterface.h"
 #include "TactileSensor.h"
 #include <RobotAPI/interface/units/HapticUnit.h>
-#include <Core/util/variants/eigen3/Eigen3VariantObjectFactories.h>
-//#include <Core/util/variants/eigen3/Eigen3LibRegistry.h>
+#include <ArmarXCore/util/variants/eigen3/Eigen3VariantObjectFactories.h>
+//#include <ArmarXCore/util/variants/eigen3/Eigen3LibRegistry.h>
 #include "TextWriter.h"
-#include <Core/observers/variant/TimestampVariant.h>
+#include <ArmarXCore/observers/variant/TimestampVariant.h>
 #include <RobotAPI/libraries/core/math/SlidingWindowVectorMedian.h>
-#include <Core/util/variants/eigen3/MatrixVariant.h>
+#include <ArmarXCore/util/variants/eigen3/MatrixVariant.h>
 #include <boost/thread/mutex.hpp>
 
 namespace armarx
diff --git a/source/RobotAPI/libraries/drivers/WeissHapticSensor/WeissHapticUnit.cpp b/source/RobotAPI/libraries/drivers/WeissHapticSensor/WeissHapticUnit.cpp
index 24c1edda1132ec2290eba62c5ca4252e5a5906dc..eadc5b159629e074545992d36097e64a672396a6 100644
--- a/source/RobotAPI/libraries/drivers/WeissHapticSensor/WeissHapticUnit.cpp
+++ b/source/RobotAPI/libraries/drivers/WeissHapticSensor/WeissHapticUnit.cpp
@@ -1,149 +1,156 @@
-/*
- * This file is part of ArmarX.
- *
- * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
- *
- * ArmarX is distributed in the hope that it will be useful, but
- * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with this program. If not, see <http://www.gnu.org/licenses/>.
- *
- * @package    ArmarXCore::units
- * @author     Peter Kaiser
- * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
- *             GNU General Public License
- */
-
-#include "WeissHapticUnit.h"
-
-#include <boost/regex.hpp>
-#include <boost/filesystem.hpp>
-
-
-using namespace armarx;
-
-void WeissHapticUnit::onInitHapticUnit()
-{
-
-    std::vector<std::string> devices = getDevices();
-
-    for(std::vector<std::string>::iterator it = devices.begin(); it != devices.end(); ++it)
-    {
-        WeissHapticSensorPtr sensor(new WeissHapticSensor(*it, 20)); // minimumReportIntervalMs = 20, limit to maximum 50 frames/s
-        this->sensors.push_back(sensor);
-    }
-
-    std::cout << "Connect Interfaces" << std::endl;
-
-    for(std::vector<boost::shared_ptr<WeissHapticSensor> >::iterator it = sensors.begin(); it != sensors.end(); ++it)
-    {
-        (*it)->connect();
-    }
-
-}
-
-std::vector< std::string > WeissHapticUnit::getDevices()
-{
-    const std::string target_path( "/dev/" );
-    const boost::regex my_filter( "ttyACM[0-9]+" );
-
-    std::vector< std::string > files;
-
-    boost::filesystem::directory_iterator end_itr; // Default ctor yields past-the-end
-    for( boost::filesystem::directory_iterator i( target_path ); i != end_itr; ++i )
-    {
-        // Skip if not a file
-        //if( !boost::filesystem::is_( i->status() ) ) continue;
-
-        boost::smatch what;
-
-        // Skip if no match
-        if( !boost::regex_match( i->path().filename().string(), what, my_filter ) ) continue;
-
-
-        // File matches, store it
-        files.push_back( "/dev/" + i->path().filename().string() );
-    }
-    std::sort(files.begin(), files.end());
-
-    if(files.size() == 0)
-    {
-        ARMARX_WARNING << "No ACM-Interfaces found";
-    }
-    else
-    {
-        ARMARX_INFO << "Detected ACM-Interfaces: " << files.size();
-        for(std::string file : files)
-        {
-            ARMARX_INFO << "Found device: " << file;
-        }
-    }
-
-    return files;
-}
-
-void WeissHapticUnit::setDeviceTag(const string &deviceName, const string &tag, const Ice::Current &)
-{
-    for(WeissHapticSensorPtr sensor : sensors)
-    {
-        if(sensor->getDeviceName() == deviceName)
-        {
-            ARMARX_IMPORTANT << "scheduling to set new device tag for " << deviceName << ": " << tag;
-            sensor->scheduleSetDeviceTag(tag);
-            return;
-        }
-    }
-    ARMARX_WARNING << "device not found: " << deviceName;
-}
-
-void WeissHapticUnit::startLogging(const Ice::Current &)
-{
-    // @@@ TODO NotImplemented
-}
-
-void WeissHapticUnit::stopLogging(const Ice::Current &)
-{
-    // @@@ TODO NotImplemented
-}
-
-void WeissHapticUnit::onStartHapticUnit()
-{
-
-    for(std::vector<boost::shared_ptr<WeissHapticSensor> >::iterator it = sensors.begin(); it != sensors.end(); ++it)
-    {
-        (*it)->setListenerPrx(hapticTopicPrx);
-        (*it)->startSampling();
-    }
-
-}
-
-void WeissHapticUnit::onExitHapticUnit()
-{
-    for(std::vector<boost::shared_ptr<WeissHapticSensor> >::iterator it = sensors.begin(); it != sensors.end(); ++it)
-    {
-        (*it)->disconnect();
-    }
-}
-
-/*void WeissHapticUnit::onConnectComponent()
-{
-
-}*/
-
-void WeissHapticUnit::onDisconnectComponent()
-{
-}
-
-
-PropertyDefinitionsPtr WeissHapticUnit::createPropertyDefinitions()
-{
-    return PropertyDefinitionsPtr(new WeissHapticUnitPropertyDefinitions(getConfigIdentifier()));
-}
-
+/*
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as
+ * published by the Free Software Foundation; either version 2 of
+ * the License, or (at your option) any later version.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @package    ArmarXCore::units
+ * @author     Peter Kaiser
+ * @date       2014
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#include "WeissHapticUnit.h"
+
+#include <boost/regex.hpp>
+#include <boost/filesystem.hpp>
+
+
+using namespace armarx;
+
+void WeissHapticUnit::onInitHapticUnit()
+{
+
+    std::vector<std::string> devices = getDevices();
+
+    for (std::vector<std::string>::iterator it = devices.begin(); it != devices.end(); ++it)
+    {
+        WeissHapticSensorPtr sensor(new WeissHapticSensor(*it, 20)); // minimumReportIntervalMs = 20, limit to maximum 50 frames/s
+        this->sensors.push_back(sensor);
+    }
+
+    std::cout << "Connect Interfaces" << std::endl;
+
+    for (std::vector<boost::shared_ptr<WeissHapticSensor> >::iterator it = sensors.begin(); it != sensors.end(); ++it)
+    {
+        (*it)->connect();
+    }
+
+}
+
+std::vector< std::string > WeissHapticUnit::getDevices()
+{
+    const std::string target_path("/dev/");
+    const boost::regex my_filter("ttyACM[0-9]+");
+
+    std::vector< std::string > files;
+
+    boost::filesystem::directory_iterator end_itr; // Default ctor yields past-the-end
+
+    for (boost::filesystem::directory_iterator i(target_path); i != end_itr; ++i)
+    {
+        // Skip if not a file
+        //if( !boost::filesystem::is_( i->status() ) ) continue;
+
+        boost::smatch what;
+
+        // Skip if no match
+        if (!boost::regex_match(i->path().filename().string(), what, my_filter))
+        {
+            continue;
+        }
+
+
+        // File matches, store it
+        files.push_back("/dev/" + i->path().filename().string());
+    }
+
+    std::sort(files.begin(), files.end());
+
+    if (files.size() == 0)
+    {
+        ARMARX_WARNING << "No ACM-Interfaces found";
+    }
+    else
+    {
+        ARMARX_INFO << "Detected ACM-Interfaces: " << files.size();
+
+        for (std::string file : files)
+        {
+            ARMARX_INFO << "Found device: " << file;
+        }
+    }
+
+    return files;
+}
+
+void WeissHapticUnit::setDeviceTag(const string& deviceName, const string& tag, const Ice::Current&)
+{
+    for (WeissHapticSensorPtr sensor : sensors)
+    {
+        if (sensor->getDeviceName() == deviceName)
+        {
+            ARMARX_IMPORTANT << "scheduling to set new device tag for " << deviceName << ": " << tag;
+            sensor->scheduleSetDeviceTag(tag);
+            return;
+        }
+    }
+
+    ARMARX_WARNING << "device not found: " << deviceName;
+}
+
+void WeissHapticUnit::startLogging(const Ice::Current&)
+{
+    // @@@ TODO NotImplemented
+}
+
+void WeissHapticUnit::stopLogging(const Ice::Current&)
+{
+    // @@@ TODO NotImplemented
+}
+
+void WeissHapticUnit::onStartHapticUnit()
+{
+
+    for (std::vector<boost::shared_ptr<WeissHapticSensor> >::iterator it = sensors.begin(); it != sensors.end(); ++it)
+    {
+        (*it)->setListenerPrx(hapticTopicPrx);
+        (*it)->startSampling();
+    }
+
+}
+
+void WeissHapticUnit::onExitHapticUnit()
+{
+    for (std::vector<boost::shared_ptr<WeissHapticSensor> >::iterator it = sensors.begin(); it != sensors.end(); ++it)
+    {
+        (*it)->disconnect();
+    }
+}
+
+/*void WeissHapticUnit::onConnectComponent()
+{
+
+}*/
+
+void WeissHapticUnit::onDisconnectComponent()
+{
+}
+
+
+PropertyDefinitionsPtr WeissHapticUnit::createPropertyDefinitions()
+{
+    return PropertyDefinitionsPtr(new WeissHapticUnitPropertyDefinitions(getConfigIdentifier()));
+}
+
diff --git a/source/RobotAPI/libraries/drivers/WeissHapticSensor/WeissHapticUnit.h b/source/RobotAPI/libraries/drivers/WeissHapticSensor/WeissHapticUnit.h
index ff24168d0b939d42bb3e48755ba206e9331827fb..0c9f6651044c70748ba0dc7f90efd6df15627122 100644
--- a/source/RobotAPI/libraries/drivers/WeissHapticSensor/WeissHapticUnit.h
+++ b/source/RobotAPI/libraries/drivers/WeissHapticSensor/WeissHapticUnit.h
@@ -1,85 +1,88 @@
-/*
- * This file is part of ArmarX.
- *
- * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
- *
- * ArmarX is distributed in the hope that it will be useful, but
- * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with this program. If not, see <http://www.gnu.org/licenses/>.
- *
- * @package    Armar4::units
- * @author     Simon Ottenhaus <simon dot ottenhaus at kit dot edu>
- * @date       2014
- * @copyright  http://www.gnu.org/licenses/gpl.txt
- *             GNU General Public License
- */
-
-#ifndef ARMAR4_FT_UNIT_ARMAR4_H
-#define ARMAR4_FT_UNIT_ARMAR4_H
-
-#include <RobotAPI/components/units/HapticUnit.h>
-#include <RobotAPI/interface/units/WeissHapticUnit.h>
-#include <Core/core/system/ImportExportComponent.h>
-
-#include <string>
-#include "WeissHapticSensor.h"
-
-namespace armarx
-{
-    class WeissHapticUnitPropertyDefinitions : public HapticUnitPropertyDefinitions
-    {
-        public:
-            WeissHapticUnitPropertyDefinitions(std::string prefix):
-                HapticUnitPropertyDefinitions(prefix)
-            {
-            }
-    };
-    
-    class WeissHapticUnit :
-            virtual public WeissHapticUnitInterface,
-            virtual public HapticUnit
-    {
-        public:
-            virtual std::string getDefaultName() { return "WeissHapticUnit"; }
-            
-            virtual void onInitHapticUnit();
-            virtual void onStartHapticUnit();
-            virtual void onExitHapticUnit();
-            
-            //virtual void onConnectComponent();
-            virtual void onDisconnectComponent();
-            
-            virtual PropertyDefinitionsPtr createPropertyDefinitions();
-            
-        protected:
-            //void proceedSensorCategory(SensorCategoryDefinition<MatrixFloat> *category);
-
-            //std::map<std::string, MatrixFloatPtr> currentValues;
-            
-
-            
-            //HapticSensorProtocolMaster hapticProtocol;
-
-            //bool remoteSystemReady;
-
-    private:
-            std::vector< std::string > getDevices();
-
-            std::vector< boost::shared_ptr< WeissHapticSensor > > sensors;
-
-            // WeissHapticUnitInterface interface
-    public:
-            void setDeviceTag(const string &deviceName, const string &tag, const Ice::Current &);
-            void startLogging(const Ice::Current &);
-            void stopLogging(const Ice::Current &);
-    };
-}
-    
-#endif
+/*
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as
+ * published by the Free Software Foundation; either version 2 of
+ * the License, or (at your option) any later version.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @package    Armar4::units
+ * @author     Simon Ottenhaus <simon dot ottenhaus at kit dot edu>
+ * @date       2014
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#ifndef ARMAR4_FT_UNIT_ARMAR4_H
+#define ARMAR4_FT_UNIT_ARMAR4_H
+
+#include <RobotAPI/components/units/HapticUnit.h>
+#include <RobotAPI/interface/units/WeissHapticUnit.h>
+#include <ArmarXCore/core/system/ImportExportComponent.h>
+
+#include <string>
+#include "WeissHapticSensor.h"
+
+namespace armarx
+{
+    class WeissHapticUnitPropertyDefinitions : public HapticUnitPropertyDefinitions
+    {
+    public:
+        WeissHapticUnitPropertyDefinitions(std::string prefix):
+            HapticUnitPropertyDefinitions(prefix)
+        {
+        }
+    };
+
+    class WeissHapticUnit :
+        virtual public WeissHapticUnitInterface,
+        virtual public HapticUnit
+    {
+    public:
+        virtual std::string getDefaultName()
+        {
+            return "WeissHapticUnit";
+        }
+
+        virtual void onInitHapticUnit();
+        virtual void onStartHapticUnit();
+        virtual void onExitHapticUnit();
+
+        //virtual void onConnectComponent();
+        virtual void onDisconnectComponent();
+
+        virtual PropertyDefinitionsPtr createPropertyDefinitions();
+
+    protected:
+        //void proceedSensorCategory(SensorCategoryDefinition<MatrixFloat> *category);
+
+        //std::map<std::string, MatrixFloatPtr> currentValues;
+
+
+
+        //HapticSensorProtocolMaster hapticProtocol;
+
+        //bool remoteSystemReady;
+
+    private:
+        std::vector< std::string > getDevices();
+
+        std::vector< boost::shared_ptr< WeissHapticSensor > > sensors;
+
+        // WeissHapticUnitInterface interface
+    public:
+        void setDeviceTag(const string& deviceName, const string& tag, const Ice::Current&);
+        void startLogging(const Ice::Current&);
+        void stopLogging(const Ice::Current&);
+    };
+}
+
+#endif
diff --git a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/CMakeLists.txt b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/CMakeLists.txt
index b3623f33a11debc6b718bc5214226718f53dd308..b463b2a77cfcf797960cce6946d8ee11afbb737a 100644
--- a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/CMakeLists.txt
+++ b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/CMakeLists.txt
@@ -1,8 +1,8 @@
 armarx_set_target("LibIMU")
 
 set(LIB_NAME LibIMU)
-set(LIB_VERSION 0.0.1)
-set(LIB_SOVERSION 1)
+
+
 set(LIBS pthread)
 
 set(LIB_FILES
@@ -29,4 +29,4 @@ set(LIB_HEADERS
 )
 
 
-armarx_add_library("${LIB_NAME}" "${LIB_VERSION}" "${LIB_SOVERSION}" "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
+armarx_add_library("${LIB_NAME}"  "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
diff --git a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IIMUEventDispatcher.cpp b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IIMUEventDispatcher.cpp
old mode 100755
new mode 100644
index 92deccbc7b25866cc117d01d996814634078e701..92c0657631ca1b8d193586d71e14bbc13405401d
--- a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IIMUEventDispatcher.cpp
+++ b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IIMUEventDispatcher.cpp
@@ -3,7 +3,7 @@
  *
  *  Created on: Mar 16, 2014
  *      Author: Dr.-Ing. David Israel González Aguirre
- *      Mail:	david.gonzalez@kit.edu
+ *      Mail:   david.gonzalez@kit.edu
  */
 
 #include "IIMUEventDispatcher.h"
@@ -11,267 +11,289 @@
 
 namespace IMU
 {
-	IIMUEventDispatcher::IIMUEventDispatcher(CIMUDevice* pIMUDevice) :
-			m_DispatchingMode(eCoupled), m_MaximalPendingEvents(2), m_EventFlags(0XFFFF), m_pIMUDevice(pIMUDevice), m_LastStartTimeStamp(CTimeStamp::s_Zero), m_LastStopTimeStamp(CTimeStamp::s_Zero), m_LastCycleReferenceTimeStamp(CTimeStamp::s_Zero), m_LastFusedCycleReferenceTimeStamp(CTimeStamp::s_Zero), m_LastIntegratedStateReferenceTimeStamp(CTimeStamp::s_Zero), m_LastCustomEventReferenceTimeStamp(CTimeStamp::s_Zero)
-	{
-		pthread_mutex_init(&m_DispatchingModeMutex,NULL);
-		pthread_mutex_init(&m_MaximalPendingEventsMutex,NULL);
-		pthread_mutex_init(&m_EventFlagsMutex,NULL);
-		pthread_mutex_init(&m_IMUDeviceMutex,NULL);
-		pthread_mutex_init(&m_EventsQueueMutex,NULL);
-		pthread_mutex_init(&m_LastStartTimeStampMutex,NULL);
-		pthread_mutex_init(&m_LastStopTimeStampMutex,NULL);
-		pthread_mutex_init(&m_LastCycleReferenceTimeStampMutex,NULL);
-		pthread_mutex_init(&m_LastFusedCycleReferenceTimeStampMutex,NULL);
-		pthread_mutex_init(&m_LastIntegratedStateReferenceTimeStampMutex,NULL);
-		pthread_mutex_init(&m_LastCustomEventReferenceTimeStampMutex,NULL);
-	}
-
-	IIMUEventDispatcher::IIMUEventDispatcher() :
-			m_DispatchingMode(eCoupled), m_MaximalPendingEvents(2), m_EventFlags(0XFFFF), m_pIMUDevice(NULL), m_EventsQueue(), m_LastStartTimeStamp(CTimeStamp::s_Zero), m_LastStopTimeStamp(CTimeStamp::s_Zero), m_LastCycleReferenceTimeStamp(CTimeStamp::s_Zero), m_LastFusedCycleReferenceTimeStamp(CTimeStamp::s_Zero), m_LastIntegratedStateReferenceTimeStamp(CTimeStamp::s_Zero), m_LastCustomEventReferenceTimeStamp(CTimeStamp::s_Zero)
-	{
-		pthread_mutex_init(&m_DispatchingModeMutex,NULL);
-		pthread_mutex_init(&m_MaximalPendingEventsMutex,NULL);
-		pthread_mutex_init(&m_EventFlagsMutex,NULL);
-		pthread_mutex_init(&m_IMUDeviceMutex,NULL);
-		pthread_mutex_init(&m_EventsQueueMutex,NULL);
-		pthread_mutex_init(&m_LastStartTimeStampMutex,NULL);
-		pthread_mutex_init(&m_LastStopTimeStampMutex,NULL);
-		pthread_mutex_init(&m_LastCycleReferenceTimeStampMutex,NULL);
-		pthread_mutex_init(&m_LastFusedCycleReferenceTimeStampMutex,NULL);
-		pthread_mutex_init(&m_LastIntegratedStateReferenceTimeStampMutex,NULL);
-		pthread_mutex_init(&m_LastCustomEventReferenceTimeStampMutex,NULL);
-	}
-
-	IIMUEventDispatcher::~IIMUEventDispatcher()
-	{
-		if (m_pIMUDevice)
-			m_pIMUDevice->UnregisterEventDispatcher(this);
-	}
-
-	void IIMUEventDispatcher::SetIMU(CIMUDevice* pIMUDevice)
-	{
-		_MINIMAL___LOCK(m_IMUDeviceMutex)
-		m_pIMUDevice = pIMUDevice;
-		_MINIMAL_UNLOCK(m_IMUDeviceMutex)
-	}
-
-	uint32_t IIMUEventDispatcher::GetEventFlags()
-	{
-		_MINIMAL___LOCK(m_EventFlagsMutex)
-		const uint32_t EventFlagsCurrentState = m_EventFlags;
-		_MINIMAL_UNLOCK(m_EventFlagsMutex)
-		return EventFlagsCurrentState;
-	}
-
-	void IIMUEventDispatcher::SetDispatchingMode(const DispatchingMode Mode)
-	{
-		_MINIMAL___LOCK(m_DispatchingModeMutex)
-		m_DispatchingMode = Mode;
-		_MINIMAL_UNLOCK(m_DispatchingModeMutex)
-	}
-
-	IIMUEventDispatcher::DispatchingMode IIMUEventDispatcher::GetDispatchingMode()
-	{
-		_MINIMAL___LOCK(m_DispatchingModeMutex)
-		const DispatchingMode DispatchingModeCurrentState = m_DispatchingMode;
-		_MINIMAL_UNLOCK(m_DispatchingModeMutex)
-		return DispatchingModeCurrentState;
-	}
-
-	void IIMUEventDispatcher::SetMaximalPendingEvents(const uint32_t MaximalPendingEvents)
-	{
-		if ((MaximalPendingEvents > 1) && (MaximalPendingEvents != m_MaximalPendingEvents))
-		{
-			_MINIMAL___LOCK(m_MaximalPendingEventsMutex)
-			m_MaximalPendingEvents = MaximalPendingEvents;
-			_MINIMAL_UNLOCK(m_MaximalPendingEventsMutex)
-			if (m_DispatchingMode == eDecoupled)
-				PurgeEvents();
-		}
-	}
-
-	uint32_t IIMUEventDispatcher::GetMaximalPendingEvents()
-	{
-		_MINIMAL___LOCK(m_MaximalPendingEventsMutex)
-		const uint32_t MaximalPendingEventsCurrentState = m_MaximalPendingEvents;
-		_MINIMAL_UNLOCK(m_MaximalPendingEventsMutex)
-		return MaximalPendingEventsCurrentState;
-	}
-
-	void IIMUEventDispatcher::SetEventHandling(const CIMUEvent::EventType Type, const bool Enabled)
-	{
-		_MINIMAL___LOCK(m_EventFlagsMutex)
-		m_EventFlags = Enabled ? (m_EventFlags | Type) : (m_EventFlags & (~Type));
-		_MINIMAL_UNLOCK(m_EventFlagsMutex)
-	}
-
-	uint32_t IIMUEventDispatcher::GetEventHandlingFlags()
-	{
-		_MINIMAL___LOCK(m_EventFlagsMutex);
-		const uint32_t EventHandlingFlagsCurrentState = m_EventFlags;
-		_MINIMAL_UNLOCK(m_EventFlagsMutex);
-		return EventHandlingFlagsCurrentState;
-	}
-
-	void IIMUEventDispatcher::ReceiveEvent(const CIMUEvent& Event)
-	{
-		_MINIMAL___LOCK(m_EventFlagsMutex)
-		const bool HandelEvent = Event.GetEventType() & m_EventFlags;
-		_MINIMAL_UNLOCK(m_EventFlagsMutex)
-
-		if (HandelEvent)
-		{
-			if (m_DispatchingMode == eDecoupled)
-			{
-				_MINIMAL___LOCK(m_EventsQueueMutex)
-				if (m_EventsQueue.size() == m_MaximalPendingEvents)
-					m_EventsQueue.pop_front();
-				m_EventsQueue.push_back(Event);
-				_MINIMAL_UNLOCK(m_EventsQueueMutex)
-
-				switch(Event.GetEventType())
-				{
-					case CIMUEvent::eOnIMUCycle:
-						_MINIMAL___LOCK(m_LastCycleReferenceTimeStampMutex)
-						gettimeofday(&m_LastCycleReferenceTimeStamp,NULL);
-						_MINIMAL_UNLOCK(m_LastCycleReferenceTimeStampMutex)
-						return;
-					case CIMUEvent::eOnIMUFusedCycle:
-						_MINIMAL___LOCK(m_LastFusedCycleReferenceTimeStampMutex)
-						gettimeofday(&m_LastFusedCycleReferenceTimeStamp,NULL);
-						_MINIMAL_UNLOCK(m_LastFusedCycleReferenceTimeStampMutex)
-						return;
-					case CIMUEvent::eOnIMUIntegratedState:
-						_MINIMAL___LOCK(m_LastIntegratedStateReferenceTimeStampMutex)
-						gettimeofday(&m_LastIntegratedStateReferenceTimeStamp,NULL);
-						_MINIMAL_UNLOCK(m_LastIntegratedStateReferenceTimeStampMutex)
-						return;
-					case CIMUEvent::eOnIMUCustomEvent:
-						_MINIMAL___LOCK(m_LastCustomEventReferenceTimeStampMutex)
-						gettimeofday(&m_LastCustomEventReferenceTimeStamp,NULL);
-						_MINIMAL_UNLOCK(m_LastCustomEventReferenceTimeStampMutex)
-						return;
-					case CIMUEvent::eOnIMUStart:
-						_MINIMAL___LOCK(m_LastStartTimeStampMutex)
-						gettimeofday(&m_LastStartTimeStamp,NULL);
-						_MINIMAL_UNLOCK(m_LastStartTimeStampMutex)
-						return;
-					case CIMUEvent::eOnIMUStop:
-						_MINIMAL___LOCK(m_LastStopTimeStampMutex)
-						gettimeofday(&m_LastStopTimeStamp,NULL);
-						_MINIMAL_UNLOCK(m_LastStopTimeStampMutex)
-						return;
-				}
-			}
-			else
-				OnIMUEvent(Event);
-		}
-	}
-
-	bool IIMUEventDispatcher::ProcessPendingEvent()
-	{
-		_MINIMAL___LOCK(m_EventsQueueMutex)
-		if (m_EventsQueue.size())
-		{
-			OnIMUEvent(m_EventsQueue.front());
-			m_EventsQueue.pop_front();
-			_MINIMAL_UNLOCK(m_EventsQueueMutex)
-			return true;
-		}
-		else
-		{
-			_MINIMAL_UNLOCK(m_EventsQueueMutex)
-			return false;
-		}
-	}
-
-	void IIMUEventDispatcher::SetReferenceTimeStamps(const timeval& Reference)
-	{
-		_MINIMAL___LOCK(m_LastStartTimeStampMutex)
-		m_LastStartTimeStamp = Reference;
-		_MINIMAL_UNLOCK(m_LastStartTimeStampMutex)
-
-		_MINIMAL___LOCK(m_LastStopTimeStampMutex)
-		m_LastStopTimeStamp = Reference;
-		_MINIMAL_UNLOCK(m_LastStopTimeStampMutex)
-
-		_MINIMAL___LOCK(m_LastCycleReferenceTimeStampMutex)
-		m_LastCycleReferenceTimeStamp = Reference;
-		_MINIMAL_UNLOCK(m_LastCycleReferenceTimeStampMutex)
-
-		_MINIMAL___LOCK(m_LastFusedCycleReferenceTimeStampMutex)
-		m_LastFusedCycleReferenceTimeStamp = Reference;
-		_MINIMAL_UNLOCK(m_LastFusedCycleReferenceTimeStampMutex)
-
-		_MINIMAL___LOCK(m_LastIntegratedStateReferenceTimeStampMutex)
-		m_LastIntegratedStateReferenceTimeStamp = Reference;
-		_MINIMAL_UNLOCK(m_LastIntegratedStateReferenceTimeStampMutex)
-
-		_MINIMAL___LOCK(m_LastCustomEventReferenceTimeStampMutex)
-		m_LastCustomEventReferenceTimeStamp = Reference;
-		_MINIMAL_UNLOCK(m_LastCustomEventReferenceTimeStampMutex)
-	}
-
-	timeval IIMUEventDispatcher::GetLastStartTimeStamp()
-	{
-		_MINIMAL___LOCK(m_LastStartTimeStampMutex)
-		timeval TimeStampCurrentState = m_LastStartTimeStamp;
-		_MINIMAL_UNLOCK(m_LastStartTimeStampMutex)
-		return TimeStampCurrentState;
-	}
-
-	timeval IIMUEventDispatcher::GetLastStopTimeStamp()
-	{
-		_MINIMAL___LOCK(m_LastStopTimeStampMutex)
-		timeval TimeStampCurrentState = m_LastStopTimeStamp;
-		_MINIMAL_UNLOCK(m_LastStopTimeStampMutex)
-		return TimeStampCurrentState;
-	}
-
-	timeval IIMUEventDispatcher::GetLastCycleReferenceTimeStamp()
-	{
-		_MINIMAL___LOCK(m_LastCycleReferenceTimeStampMutex)
-		timeval TimeStampCurrentState = m_LastCycleReferenceTimeStamp;
-		_MINIMAL_UNLOCK(m_LastCycleReferenceTimeStampMutex)
-		return TimeStampCurrentState;
-	}
-
-	timeval IIMUEventDispatcher::GetLastFusedCycleReferenceTimeStamp()
-	{
-		_MINIMAL___LOCK(m_LastFusedCycleReferenceTimeStampMutex)
-		timeval TimeStampCurrentState = m_LastFusedCycleReferenceTimeStamp;
-		_MINIMAL_UNLOCK(m_LastFusedCycleReferenceTimeStampMutex)
-		return TimeStampCurrentState;
-	}
-
-	timeval IIMUEventDispatcher::GetLastIntegratedStateReferenceTimeStamp()
-	{
-		_MINIMAL___LOCK(m_LastIntegratedStateReferenceTimeStampMutex)
-		timeval TimeStampCurrentState = m_LastIntegratedStateReferenceTimeStamp;
-		_MINIMAL_UNLOCK(m_LastIntegratedStateReferenceTimeStampMutex)
-		return TimeStampCurrentState;
-	}
-
-	timeval IIMUEventDispatcher::GetLastCustomEventReferenceTimeStamp()
-	{
-		_MINIMAL___LOCK(m_LastCustomEventReferenceTimeStampMutex)
-		timeval TimeStampCurrentState = m_LastCustomEventReferenceTimeStamp;
-		_MINIMAL_UNLOCK(m_LastCustomEventReferenceTimeStampMutex)
-		return TimeStampCurrentState;
-	}
-
-	void IIMUEventDispatcher::PurgeEvents()
-	{
-		_MINIMAL___LOCK(m_EventsQueueMutex)
-		if (m_EventsQueue.size() >= m_MaximalPendingEvents)
-		{
-			const uint32_t TotalEventsToRemove = (uint32_t(m_EventsQueue.size()) - m_MaximalPendingEvents) + 1;
-			for(uint32_t i = 0 ; i < TotalEventsToRemove ; ++i)
-				m_EventsQueue.pop_front();
-		}
-		_MINIMAL_UNLOCK(m_EventsQueueMutex)
-	}
+    IIMUEventDispatcher::IIMUEventDispatcher(CIMUDevice* pIMUDevice) :
+        m_DispatchingMode(eCoupled), m_MaximalPendingEvents(2), m_EventFlags(0XFFFF), m_pIMUDevice(pIMUDevice), m_LastStartTimeStamp(CTimeStamp::s_Zero), m_LastStopTimeStamp(CTimeStamp::s_Zero), m_LastCycleReferenceTimeStamp(CTimeStamp::s_Zero), m_LastFusedCycleReferenceTimeStamp(CTimeStamp::s_Zero), m_LastIntegratedStateReferenceTimeStamp(CTimeStamp::s_Zero), m_LastCustomEventReferenceTimeStamp(CTimeStamp::s_Zero)
+    {
+        pthread_mutex_init(&m_DispatchingModeMutex, NULL);
+        pthread_mutex_init(&m_MaximalPendingEventsMutex, NULL);
+        pthread_mutex_init(&m_EventFlagsMutex, NULL);
+        pthread_mutex_init(&m_IMUDeviceMutex, NULL);
+        pthread_mutex_init(&m_EventsQueueMutex, NULL);
+        pthread_mutex_init(&m_LastStartTimeStampMutex, NULL);
+        pthread_mutex_init(&m_LastStopTimeStampMutex, NULL);
+        pthread_mutex_init(&m_LastCycleReferenceTimeStampMutex, NULL);
+        pthread_mutex_init(&m_LastFusedCycleReferenceTimeStampMutex, NULL);
+        pthread_mutex_init(&m_LastIntegratedStateReferenceTimeStampMutex, NULL);
+        pthread_mutex_init(&m_LastCustomEventReferenceTimeStampMutex, NULL);
+    }
+
+    IIMUEventDispatcher::IIMUEventDispatcher() :
+        m_DispatchingMode(eCoupled), m_MaximalPendingEvents(2), m_EventFlags(0XFFFF), m_pIMUDevice(NULL), m_EventsQueue(), m_LastStartTimeStamp(CTimeStamp::s_Zero), m_LastStopTimeStamp(CTimeStamp::s_Zero), m_LastCycleReferenceTimeStamp(CTimeStamp::s_Zero), m_LastFusedCycleReferenceTimeStamp(CTimeStamp::s_Zero), m_LastIntegratedStateReferenceTimeStamp(CTimeStamp::s_Zero), m_LastCustomEventReferenceTimeStamp(CTimeStamp::s_Zero)
+    {
+        pthread_mutex_init(&m_DispatchingModeMutex, NULL);
+        pthread_mutex_init(&m_MaximalPendingEventsMutex, NULL);
+        pthread_mutex_init(&m_EventFlagsMutex, NULL);
+        pthread_mutex_init(&m_IMUDeviceMutex, NULL);
+        pthread_mutex_init(&m_EventsQueueMutex, NULL);
+        pthread_mutex_init(&m_LastStartTimeStampMutex, NULL);
+        pthread_mutex_init(&m_LastStopTimeStampMutex, NULL);
+        pthread_mutex_init(&m_LastCycleReferenceTimeStampMutex, NULL);
+        pthread_mutex_init(&m_LastFusedCycleReferenceTimeStampMutex, NULL);
+        pthread_mutex_init(&m_LastIntegratedStateReferenceTimeStampMutex, NULL);
+        pthread_mutex_init(&m_LastCustomEventReferenceTimeStampMutex, NULL);
+    }
+
+    IIMUEventDispatcher::~IIMUEventDispatcher()
+    {
+        if (m_pIMUDevice)
+        {
+            m_pIMUDevice->UnregisterEventDispatcher(this);
+        }
+    }
+
+    void IIMUEventDispatcher::SetIMU(CIMUDevice* pIMUDevice)
+    {
+        _MINIMAL___LOCK(m_IMUDeviceMutex)
+        m_pIMUDevice = pIMUDevice;
+        _MINIMAL_UNLOCK(m_IMUDeviceMutex)
+    }
+
+    uint32_t IIMUEventDispatcher::GetEventFlags()
+    {
+        _MINIMAL___LOCK(m_EventFlagsMutex)
+        const uint32_t EventFlagsCurrentState = m_EventFlags;
+        _MINIMAL_UNLOCK(m_EventFlagsMutex)
+        return EventFlagsCurrentState;
+    }
+
+    void IIMUEventDispatcher::SetDispatchingMode(const DispatchingMode Mode)
+    {
+        _MINIMAL___LOCK(m_DispatchingModeMutex)
+        m_DispatchingMode = Mode;
+        _MINIMAL_UNLOCK(m_DispatchingModeMutex)
+    }
+
+    IIMUEventDispatcher::DispatchingMode IIMUEventDispatcher::GetDispatchingMode()
+    {
+        _MINIMAL___LOCK(m_DispatchingModeMutex)
+        const DispatchingMode DispatchingModeCurrentState = m_DispatchingMode;
+        _MINIMAL_UNLOCK(m_DispatchingModeMutex)
+        return DispatchingModeCurrentState;
+    }
+
+    void IIMUEventDispatcher::SetMaximalPendingEvents(const uint32_t MaximalPendingEvents)
+    {
+        if ((MaximalPendingEvents > 1) && (MaximalPendingEvents != m_MaximalPendingEvents))
+        {
+            _MINIMAL___LOCK(m_MaximalPendingEventsMutex)
+            m_MaximalPendingEvents = MaximalPendingEvents;
+            _MINIMAL_UNLOCK(m_MaximalPendingEventsMutex)
+
+            if (m_DispatchingMode == eDecoupled)
+            {
+                PurgeEvents();
+            }
+        }
+    }
+
+    uint32_t IIMUEventDispatcher::GetMaximalPendingEvents()
+    {
+        _MINIMAL___LOCK(m_MaximalPendingEventsMutex)
+        const uint32_t MaximalPendingEventsCurrentState = m_MaximalPendingEvents;
+        _MINIMAL_UNLOCK(m_MaximalPendingEventsMutex)
+        return MaximalPendingEventsCurrentState;
+    }
+
+    void IIMUEventDispatcher::SetEventHandling(const CIMUEvent::EventType Type, const bool Enabled)
+    {
+        _MINIMAL___LOCK(m_EventFlagsMutex)
+        m_EventFlags = Enabled ? (m_EventFlags | Type) : (m_EventFlags & (~Type));
+        _MINIMAL_UNLOCK(m_EventFlagsMutex)
+    }
+
+    uint32_t IIMUEventDispatcher::GetEventHandlingFlags()
+    {
+        _MINIMAL___LOCK(m_EventFlagsMutex);
+        const uint32_t EventHandlingFlagsCurrentState = m_EventFlags;
+        _MINIMAL_UNLOCK(m_EventFlagsMutex);
+        return EventHandlingFlagsCurrentState;
+    }
+
+    void IIMUEventDispatcher::ReceiveEvent(const CIMUEvent& Event)
+    {
+        _MINIMAL___LOCK(m_EventFlagsMutex)
+        const bool HandelEvent = Event.GetEventType() & m_EventFlags;
+        _MINIMAL_UNLOCK(m_EventFlagsMutex)
+
+        if (HandelEvent)
+        {
+            if (m_DispatchingMode == eDecoupled)
+            {
+                _MINIMAL___LOCK(m_EventsQueueMutex)
+
+                if (m_EventsQueue.size() == m_MaximalPendingEvents)
+                {
+                    m_EventsQueue.pop_front();
+                }
+
+                m_EventsQueue.push_back(Event);
+                _MINIMAL_UNLOCK(m_EventsQueueMutex)
+
+                switch (Event.GetEventType())
+                {
+                    case CIMUEvent::eOnIMUCycle:
+                        _MINIMAL___LOCK(m_LastCycleReferenceTimeStampMutex)
+                        gettimeofday(&m_LastCycleReferenceTimeStamp, NULL);
+                        _MINIMAL_UNLOCK(m_LastCycleReferenceTimeStampMutex)
+                        return;
+
+                    case CIMUEvent::eOnIMUFusedCycle:
+                        _MINIMAL___LOCK(m_LastFusedCycleReferenceTimeStampMutex)
+                        gettimeofday(&m_LastFusedCycleReferenceTimeStamp, NULL);
+                        _MINIMAL_UNLOCK(m_LastFusedCycleReferenceTimeStampMutex)
+                        return;
+
+                    case CIMUEvent::eOnIMUIntegratedState:
+                        _MINIMAL___LOCK(m_LastIntegratedStateReferenceTimeStampMutex)
+                        gettimeofday(&m_LastIntegratedStateReferenceTimeStamp, NULL);
+                        _MINIMAL_UNLOCK(m_LastIntegratedStateReferenceTimeStampMutex)
+                        return;
+
+                    case CIMUEvent::eOnIMUCustomEvent:
+                        _MINIMAL___LOCK(m_LastCustomEventReferenceTimeStampMutex)
+                        gettimeofday(&m_LastCustomEventReferenceTimeStamp, NULL);
+                        _MINIMAL_UNLOCK(m_LastCustomEventReferenceTimeStampMutex)
+                        return;
+
+                    case CIMUEvent::eOnIMUStart:
+                        _MINIMAL___LOCK(m_LastStartTimeStampMutex)
+                        gettimeofday(&m_LastStartTimeStamp, NULL);
+                        _MINIMAL_UNLOCK(m_LastStartTimeStampMutex)
+                        return;
+
+                    case CIMUEvent::eOnIMUStop:
+                        _MINIMAL___LOCK(m_LastStopTimeStampMutex)
+                        gettimeofday(&m_LastStopTimeStamp, NULL);
+                        _MINIMAL_UNLOCK(m_LastStopTimeStampMutex)
+                        return;
+                }
+            }
+            else
+            {
+                OnIMUEvent(Event);
+            }
+        }
+    }
+
+    bool IIMUEventDispatcher::ProcessPendingEvent()
+    {
+        _MINIMAL___LOCK(m_EventsQueueMutex)
+
+        if (m_EventsQueue.size())
+        {
+            OnIMUEvent(m_EventsQueue.front());
+            m_EventsQueue.pop_front();
+            _MINIMAL_UNLOCK(m_EventsQueueMutex)
+            return true;
+        }
+        else
+        {
+            _MINIMAL_UNLOCK(m_EventsQueueMutex)
+            return false;
+        }
+    }
+
+    void IIMUEventDispatcher::SetReferenceTimeStamps(const timeval& Reference)
+    {
+        _MINIMAL___LOCK(m_LastStartTimeStampMutex)
+        m_LastStartTimeStamp = Reference;
+        _MINIMAL_UNLOCK(m_LastStartTimeStampMutex)
+
+        _MINIMAL___LOCK(m_LastStopTimeStampMutex)
+        m_LastStopTimeStamp = Reference;
+        _MINIMAL_UNLOCK(m_LastStopTimeStampMutex)
+
+        _MINIMAL___LOCK(m_LastCycleReferenceTimeStampMutex)
+        m_LastCycleReferenceTimeStamp = Reference;
+        _MINIMAL_UNLOCK(m_LastCycleReferenceTimeStampMutex)
+
+        _MINIMAL___LOCK(m_LastFusedCycleReferenceTimeStampMutex)
+        m_LastFusedCycleReferenceTimeStamp = Reference;
+        _MINIMAL_UNLOCK(m_LastFusedCycleReferenceTimeStampMutex)
+
+        _MINIMAL___LOCK(m_LastIntegratedStateReferenceTimeStampMutex)
+        m_LastIntegratedStateReferenceTimeStamp = Reference;
+        _MINIMAL_UNLOCK(m_LastIntegratedStateReferenceTimeStampMutex)
+
+        _MINIMAL___LOCK(m_LastCustomEventReferenceTimeStampMutex)
+        m_LastCustomEventReferenceTimeStamp = Reference;
+        _MINIMAL_UNLOCK(m_LastCustomEventReferenceTimeStampMutex)
+    }
+
+    timeval IIMUEventDispatcher::GetLastStartTimeStamp()
+    {
+        _MINIMAL___LOCK(m_LastStartTimeStampMutex)
+        timeval TimeStampCurrentState = m_LastStartTimeStamp;
+        _MINIMAL_UNLOCK(m_LastStartTimeStampMutex)
+        return TimeStampCurrentState;
+    }
+
+    timeval IIMUEventDispatcher::GetLastStopTimeStamp()
+    {
+        _MINIMAL___LOCK(m_LastStopTimeStampMutex)
+        timeval TimeStampCurrentState = m_LastStopTimeStamp;
+        _MINIMAL_UNLOCK(m_LastStopTimeStampMutex)
+        return TimeStampCurrentState;
+    }
+
+    timeval IIMUEventDispatcher::GetLastCycleReferenceTimeStamp()
+    {
+        _MINIMAL___LOCK(m_LastCycleReferenceTimeStampMutex)
+        timeval TimeStampCurrentState = m_LastCycleReferenceTimeStamp;
+        _MINIMAL_UNLOCK(m_LastCycleReferenceTimeStampMutex)
+        return TimeStampCurrentState;
+    }
+
+    timeval IIMUEventDispatcher::GetLastFusedCycleReferenceTimeStamp()
+    {
+        _MINIMAL___LOCK(m_LastFusedCycleReferenceTimeStampMutex)
+        timeval TimeStampCurrentState = m_LastFusedCycleReferenceTimeStamp;
+        _MINIMAL_UNLOCK(m_LastFusedCycleReferenceTimeStampMutex)
+        return TimeStampCurrentState;
+    }
+
+    timeval IIMUEventDispatcher::GetLastIntegratedStateReferenceTimeStamp()
+    {
+        _MINIMAL___LOCK(m_LastIntegratedStateReferenceTimeStampMutex)
+        timeval TimeStampCurrentState = m_LastIntegratedStateReferenceTimeStamp;
+        _MINIMAL_UNLOCK(m_LastIntegratedStateReferenceTimeStampMutex)
+        return TimeStampCurrentState;
+    }
+
+    timeval IIMUEventDispatcher::GetLastCustomEventReferenceTimeStamp()
+    {
+        _MINIMAL___LOCK(m_LastCustomEventReferenceTimeStampMutex)
+        timeval TimeStampCurrentState = m_LastCustomEventReferenceTimeStamp;
+        _MINIMAL_UNLOCK(m_LastCustomEventReferenceTimeStampMutex)
+        return TimeStampCurrentState;
+    }
+
+    void IIMUEventDispatcher::PurgeEvents()
+    {
+        _MINIMAL___LOCK(m_EventsQueueMutex)
+
+        if (m_EventsQueue.size() >= m_MaximalPendingEvents)
+        {
+            const uint32_t TotalEventsToRemove = (uint32_t(m_EventsQueue.size()) - m_MaximalPendingEvents) + 1;
+
+            for (uint32_t i = 0 ; i < TotalEventsToRemove ; ++i)
+            {
+                m_EventsQueue.pop_front();
+            }
+        }
+
+        _MINIMAL_UNLOCK(m_EventsQueueMutex)
+    }
 
 }
 
diff --git a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IIMUEventDispatcher.h b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IIMUEventDispatcher.h
old mode 100755
new mode 100644
index 2693fca7afa038a4043c4b90bd74ab25854f6c4f..d5a073128d0fa9726e3e7fc47a43d38b854c1b28
--- a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IIMUEventDispatcher.h
+++ b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IIMUEventDispatcher.h
@@ -3,7 +3,7 @@
  *
  *  Created on: Mar 16, 2014
  *      Author: Dr.-Ing. David Israel González Aguirre
- *      Mail:	david.gonzalez@kit.edu
+ *      Mail:   david.gonzalez@kit.edu
  */
 
 #ifndef IIMUEVENTDISPATCHER_H_
@@ -15,86 +15,86 @@
 
 namespace IMU
 {
-	class CIMUDevice;
-	class IIMUEventDispatcher
-	{
-		public:
-
-			enum DispatchingMode
-			{
-				eCoupled, eDecoupled
-			};
-
-			IIMUEventDispatcher(CIMUDevice* pIMUDevice);
-			IIMUEventDispatcher();
-
-			virtual ~IIMUEventDispatcher();
-
-			void SetIMU(CIMUDevice* pIMUDevice);
-
-			uint32_t GetEventFlags();
-
-			void SetDispatchingMode(const DispatchingMode Mode);
-			DispatchingMode GetDispatchingMode();
-
-			void SetMaximalPendingEvents(const uint32_t MaximalPendingEvents);
-			uint32_t GetMaximalPendingEvents();
-
-			void SetEventHandling(const CIMUEvent::EventType Type, const bool Enabled);
-			uint32_t GetEventHandlingFlags();
-
-			void ReceiveEvent(const CIMUEvent& Event);
-
-			inline uint32_t GetTotalPendingEvents()
-			{
-				return uint32_t(m_EventsQueue.size());
-			}
-
-			inline bool HasPendingEvents()
-			{
-				return m_EventsQueue.size();
-			}
-
-			bool ProcessPendingEvent();
-
-			void SetReferenceTimeStamps(const timeval& Reference);
-
-			timeval GetLastStartTimeStamp();
-			timeval GetLastStopTimeStamp();
-			timeval GetLastCycleReferenceTimeStamp();
-			timeval GetLastFusedCycleReferenceTimeStamp();
-			timeval GetLastIntegratedStateReferenceTimeStamp();
-			timeval GetLastCustomEventReferenceTimeStamp();
-
-			virtual void OnIMUEvent(const CIMUEvent& Event) = 0;
-
-		private:
-
-			void PurgeEvents();
-
-			DispatchingMode m_DispatchingMode;
-			pthread_mutex_t m_DispatchingModeMutex;
-			uint32_t m_MaximalPendingEvents;
-			pthread_mutex_t m_MaximalPendingEventsMutex;
-			uint32_t m_EventFlags;
-			pthread_mutex_t m_EventFlagsMutex;
-			CIMUDevice* m_pIMUDevice;
-			pthread_mutex_t m_IMUDeviceMutex;
-			std::list<CIMUEvent> m_EventsQueue;
-			pthread_mutex_t m_EventsQueueMutex;
-			timeval m_LastStartTimeStamp;
-			pthread_mutex_t m_LastStartTimeStampMutex;
-			timeval m_LastStopTimeStamp;
-			pthread_mutex_t m_LastStopTimeStampMutex;
-			timeval m_LastCycleReferenceTimeStamp;
-			pthread_mutex_t m_LastCycleReferenceTimeStampMutex;
-			timeval m_LastFusedCycleReferenceTimeStamp;
-			pthread_mutex_t m_LastFusedCycleReferenceTimeStampMutex;
-			timeval m_LastIntegratedStateReferenceTimeStamp;
-			pthread_mutex_t m_LastIntegratedStateReferenceTimeStampMutex;
-			timeval m_LastCustomEventReferenceTimeStamp;
-			pthread_mutex_t m_LastCustomEventReferenceTimeStampMutex;
-	};
+    class CIMUDevice;
+    class IIMUEventDispatcher
+    {
+    public:
+
+        enum DispatchingMode
+        {
+            eCoupled, eDecoupled
+        };
+
+        IIMUEventDispatcher(CIMUDevice* pIMUDevice);
+        IIMUEventDispatcher();
+
+        virtual ~IIMUEventDispatcher();
+
+        void SetIMU(CIMUDevice* pIMUDevice);
+
+        uint32_t GetEventFlags();
+
+        void SetDispatchingMode(const DispatchingMode Mode);
+        DispatchingMode GetDispatchingMode();
+
+        void SetMaximalPendingEvents(const uint32_t MaximalPendingEvents);
+        uint32_t GetMaximalPendingEvents();
+
+        void SetEventHandling(const CIMUEvent::EventType Type, const bool Enabled);
+        uint32_t GetEventHandlingFlags();
+
+        void ReceiveEvent(const CIMUEvent& Event);
+
+        inline uint32_t GetTotalPendingEvents()
+        {
+            return uint32_t(m_EventsQueue.size());
+        }
+
+        inline bool HasPendingEvents()
+        {
+            return m_EventsQueue.size();
+        }
+
+        bool ProcessPendingEvent();
+
+        void SetReferenceTimeStamps(const timeval& Reference);
+
+        timeval GetLastStartTimeStamp();
+        timeval GetLastStopTimeStamp();
+        timeval GetLastCycleReferenceTimeStamp();
+        timeval GetLastFusedCycleReferenceTimeStamp();
+        timeval GetLastIntegratedStateReferenceTimeStamp();
+        timeval GetLastCustomEventReferenceTimeStamp();
+
+        virtual void OnIMUEvent(const CIMUEvent& Event) = 0;
+
+    private:
+
+        void PurgeEvents();
+
+        DispatchingMode m_DispatchingMode;
+        pthread_mutex_t m_DispatchingModeMutex;
+        uint32_t m_MaximalPendingEvents;
+        pthread_mutex_t m_MaximalPendingEventsMutex;
+        uint32_t m_EventFlags;
+        pthread_mutex_t m_EventFlagsMutex;
+        CIMUDevice* m_pIMUDevice;
+        pthread_mutex_t m_IMUDeviceMutex;
+        std::list<CIMUEvent> m_EventsQueue;
+        pthread_mutex_t m_EventsQueueMutex;
+        timeval m_LastStartTimeStamp;
+        pthread_mutex_t m_LastStartTimeStampMutex;
+        timeval m_LastStopTimeStamp;
+        pthread_mutex_t m_LastStopTimeStampMutex;
+        timeval m_LastCycleReferenceTimeStamp;
+        pthread_mutex_t m_LastCycleReferenceTimeStampMutex;
+        timeval m_LastFusedCycleReferenceTimeStamp;
+        pthread_mutex_t m_LastFusedCycleReferenceTimeStampMutex;
+        timeval m_LastIntegratedStateReferenceTimeStamp;
+        pthread_mutex_t m_LastIntegratedStateReferenceTimeStampMutex;
+        timeval m_LastCustomEventReferenceTimeStamp;
+        pthread_mutex_t m_LastCustomEventReferenceTimeStampMutex;
+    };
 }
 
 #endif
diff --git a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMU.h b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMU.h
old mode 100755
new mode 100644
index 205cc8b596aec2f0247e3e9f81224735c87eca76..0eb554c34a855467d284dc3108c94e0027a0c459
--- a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMU.h
+++ b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMU.h
@@ -3,7 +3,7 @@
  *
  *  Created on: Mar 17, 2014
  *      Author: Dr.-Ing. David Israel González Aguirre
- *      Mail:	david.gonzalez@kit.edu
+ *      Mail:   david.gonzalez@kit.edu
  */
 
 #ifndef IMU_H_
diff --git a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUDeducedReckoning.cpp b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUDeducedReckoning.cpp
old mode 100755
new mode 100644
index c386a4fdb8c2ab8ece76ce0f212743da9ba50480..0a1a7f7c3e1cd43a64fe6fb0e1f7d6b2dc8ad27d
--- a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUDeducedReckoning.cpp
+++ b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUDeducedReckoning.cpp
@@ -3,169 +3,188 @@
  *
  *  Created on: Mar 16, 2014
  *      Author: Dr.-Ing. David Israel González Aguirre
- *      Mail:	david.gonzalez@kit.edu
+ *      Mail:   david.gonzalez@kit.edu
  */
 
 #include "IMUDeducedReckoning.h"
 
 namespace IMU
 {
-	CIMUDeducedReckoning::CIMUDeducedReckoning(const bool IsVerbose) :
-			IIMUEventDispatcher(), m_IsVerbose(IsVerbose), m_G(IMU::CGeolocationInformation::GetGravitationalAcceleration())
-	{
-		SetEventHandling(CIMUEvent::eOnIMUStart,true);
-		SetEventHandling(CIMUEvent::eOnIMUStop,true);
-		SetEventHandling(CIMUEvent::eOnIMUCycle,false);
-		SetEventHandling(CIMUEvent::eOnIMUFusedCycle,true);
-		SetEventHandling(CIMUEvent::eOnIMUIntegratedState,false);
-		SetEventHandling(CIMUEvent::eOnIMUCustomEvent,true);
-	}
-
-	CIMUDeducedReckoning::~CIMUDeducedReckoning()
-	{
-	}
-
-	void CIMUDeducedReckoning::OnIMUEvent(const CIMUEvent& Event)
-	{
-		switch(Event.GetEventType())
-		{
-			case CIMUEvent::eOnIMUCycle:
-				OnIMUCycle(Event.GetTimeStamp(),Event.GetIMU());
-			break;
-			case CIMUEvent::eOnIMUFusedCycle:
-				OnIMUFusedCycle(Event.GetTimeStamp(),Event.GetIMU());
-			break;
-			case CIMUEvent::eOnIMUIntegratedState:
-				OnIMUIntegratedState(Event.GetTimeStamp(),Event.GetIMU());
-			break;
-			case CIMUEvent::eOnIMUCustomEvent:
-				OnIMUCustomEvent(Event);
-			break;
-			case CIMUEvent::eOnIMUStart:
-				OnIMUStart(Event.GetTimeStamp(),Event.GetIMU());
-			break;
-			case CIMUEvent::eOnIMUStop:
-				OnIMUStop(Event.GetTimeStamp(),Event.GetIMU());
-			break;
-		}
-	}
-
-	void CIMUDeducedReckoning::OnIMUStart(const timeval& TimeStamp, const CIMUDevice* pIMUDevice)
-	{
-		if (m_IsVerbose)
-		{
-			std::cout << "OnIMUStart(IMU Device ID = " << pIMUDevice->GetDeviceId() << ((GetDispatchingMode() == eCoupled) ? " Coupled" : " Decoupled") << ")" << std::endl;
-			std::cout << "\t[ Global time  = " << CTimeStamp::GetElapsedSeconds(TimeStamp,pIMUDevice->GetReferenceTimeStamp()) << " s]" << std::endl;
-			std::cout << "\t[ Latency  = " << CTimeStamp::GetElapsedMicroseconds(TimeStamp,GetLastStartTimeStamp()) << "]" << std::endl;
-			if (GetDispatchingMode() == eDecoupled)
-			{
-				std::cout << "\t[ Pending Events  = " << GetTotalPendingEvents() << "]" << std::endl;
-				std::cout << "\t[ Maximal Pending Events  = " << GetMaximalPendingEvents() << "]" << std::endl;
-			}
-		}
-	}
-
-	void CIMUDeducedReckoning::OnIMUStop(const timeval& TimeStamp, const CIMUDevice* pIMUDevice)
-	{
-		if (m_IsVerbose)
-		{
-			std::cout << "OnIMUStop(IMU Device ID = " << pIMUDevice->GetDeviceId() << ((GetDispatchingMode() == eCoupled) ? " Coupled" : " Decoupled") << ")" << std::endl;
-			std::cout << "\t[ Global time  = " << CTimeStamp::GetElapsedSeconds(TimeStamp,pIMUDevice->GetReferenceTimeStamp()) << " s]" << std::endl;
-			std::cout << "\t[ Latency  = " << CTimeStamp::GetElapsedMicroseconds(TimeStamp,GetLastStopTimeStamp()) << "]" << std::endl;
-			if (GetDispatchingMode() == eDecoupled)
-			{
-				std::cout << "\t[ Pending Events  = " << GetTotalPendingEvents() << "]" << std::endl;
-				std::cout << "\t[ Maximal Pending Events  = " << GetMaximalPendingEvents() << "]" << std::endl;
-			}
-		}
-	}
-
-	void CIMUDeducedReckoning::OnIMUCycle(const timeval& TimeStamp, const CIMUDevice* pIMUDevice)
-	{
-		const IMUState CurrentState = pIMUDevice->GetIMUState();
-		if (m_IsVerbose)
-		{
-			std::cout << "OnIMUCycle(IMU Device ID = 0x" << std::hex << pIMUDevice->GetDeviceId() << ((GetDispatchingMode() == eCoupled) ? " Coupled" : " Decoupled") << std::dec << ")" << std::endl;
-			std::cout << "\t[ Global time  = " << CTimeStamp::GetElapsedSeconds(TimeStamp,pIMUDevice->GetReferenceTimeStamp()) << " s]" << std::endl;
-			std::cout << "\t[ Latency  = " << CTimeStamp::GetElapsedMicroseconds(TimeStamp,GetLastCycleReferenceTimeStamp()) << " µs]" << std::endl;
-			if (GetDispatchingMode() == eDecoupled)
-			{
-				std::cout << "\t[ Pending Events  = " << GetTotalPendingEvents() << "]" << std::endl;
-				std::cout << "\t[ Maximal Pending Events  = " << GetMaximalPendingEvents() << "]" << std::endl;
-			}
-			std::cout << "\t[ Cycle  = " << CurrentState.m_ControlData.m_MessageCounter << "]" << std::endl;
-			std::cout << "\t[ Acceleration  = [" << CurrentState.m_PhysicalData.m_Acceleration[0] << "," << CurrentState.m_PhysicalData.m_Acceleration[1] << "," << CurrentState.m_PhysicalData.m_Acceleration[2] << "]" << std::endl;
-			std::cout << "\t[ Acceleration Magnitude = [" << std::abs(CurrentState.m_PhysicalData.m_AccelerationMagnitud - m_G) * 1000.0f << " mm/s^2]" << std::endl;
-			std::cout << "\t[ Gyroscope Rotation  = [" << CurrentState.m_PhysicalData.m_GyroscopeRotation[0] << "," << CurrentState.m_PhysicalData.m_GyroscopeRotation[1] << "," << CurrentState.m_PhysicalData.m_GyroscopeRotation[2] << "]" << std::endl;
-			std::cout << "\t[ Magnetic Rotation  = [" << CurrentState.m_PhysicalData.m_MagneticRotation[0] << "," << CurrentState.m_PhysicalData.m_MagneticRotation[1] << "," << CurrentState.m_PhysicalData.m_MagneticRotation[2] << "]" << std::endl;
-			std::cout << "\t[ Quaternion Rotation  = [" << CurrentState.m_PhysicalData.m_QuaternionRotation[0] << "," << CurrentState.m_PhysicalData.m_QuaternionRotation[1] << "," << CurrentState.m_PhysicalData.m_QuaternionRotation[2] << "," << CurrentState.m_PhysicalData.m_QuaternionRotation[3] << "]" << std::endl;
-		}
-		memcpy(m_OrientationQuaternion,CurrentState.m_PhysicalData.m_QuaternionRotation,sizeof(float) * 4);
-		memcpy(m_MagneticRotation,CurrentState.m_PhysicalData.m_MagneticRotation,sizeof(float) * 3);
-		memcpy(m_GyroscopeRotation,CurrentState.m_PhysicalData.m_GyroscopeRotation,sizeof(float) * 3);
-		memcpy(m_Accelaration,CurrentState.m_PhysicalData.m_Acceleration,sizeof(float) * 3);
-	}
-
-	void CIMUDeducedReckoning::OnIMUFusedCycle(const timeval& TimeStamp, const CIMUDevice* pIMUDevice)
-	{
-		const IMUState CurrentState = pIMUDevice->GetIMUState();
-		if (m_IsVerbose)
-		{
-			std::cout << "OnIMUFusedCycle(IMU Device ID = 0x" << std::hex << pIMUDevice->GetDeviceId() << ((GetDispatchingMode() == eCoupled) ? " Coupled" : " Decoupled") << std::dec << ")" << std::endl;
-			std::cout << "\t[ Global time  = " << CTimeStamp::GetElapsedSeconds(TimeStamp,pIMUDevice->GetReferenceTimeStamp()) << " s]" << std::endl;
-			std::cout << "\t[ Latency  = " << CTimeStamp::GetElapsedMicroseconds(TimeStamp,GetLastFusedCycleReferenceTimeStamp()) << " µs]" << std::endl;
-			if (GetDispatchingMode() == eDecoupled)
-			{
-				std::cout << "\t[ Pending Events  = " << GetTotalPendingEvents() << "]" << std::endl;
-				std::cout << "\t[ Maximal Pending Events  = " << GetMaximalPendingEvents() << "]" << std::endl;
-			}
-			std::cout << "\t[ Cycle  = " << CurrentState.m_ControlData.m_MessageCounter << "]" << std::endl;
-			std::cout << "\t[ Acceleration  = [" << CurrentState.m_PhysicalData.m_Acceleration[0] << "," << CurrentState.m_PhysicalData.m_Acceleration[1] << "," << CurrentState.m_PhysicalData.m_Acceleration[2] << "]" << std::endl;
-			std::cout << "\t[ Acceleration Magnitude = [" << std::abs(CurrentState.m_PhysicalData.m_AccelerationMagnitud - m_G) * 1000.0f << " mm/s^2]" << std::endl;
-			std::cout << "\t[ Gyroscope Rotation  = [" << CurrentState.m_PhysicalData.m_GyroscopeRotation[0] << "," << CurrentState.m_PhysicalData.m_GyroscopeRotation[1] << "," << CurrentState.m_PhysicalData.m_GyroscopeRotation[2] << "]" << std::endl;
-			std::cout << "\t[ Magnetic Rotation  = [" << CurrentState.m_PhysicalData.m_MagneticRotation[0] << "," << CurrentState.m_PhysicalData.m_MagneticRotation[1] << "," << CurrentState.m_PhysicalData.m_MagneticRotation[2] << "]" << std::endl;
-			std::cout << "\t[ Quaternion Rotation  = [" << CurrentState.m_PhysicalData.m_QuaternionRotation[0] << "," << CurrentState.m_PhysicalData.m_QuaternionRotation[1] << "," << CurrentState.m_PhysicalData.m_QuaternionRotation[2] << "," << CurrentState.m_PhysicalData.m_QuaternionRotation[3] << "]" << std::endl;
-		}
-		memcpy(m_OrientationQuaternion,CurrentState.m_PhysicalData.m_QuaternionRotation,sizeof(float) * 4);
-		memcpy(m_MagneticRotation,CurrentState.m_PhysicalData.m_MagneticRotation,sizeof(float) * 3);
-		memcpy(m_GyroscopeRotation,CurrentState.m_PhysicalData.m_GyroscopeRotation,sizeof(float) * 3);
-		memcpy(m_Accelaration,CurrentState.m_PhysicalData.m_Acceleration,sizeof(float) * 3);
-	}
-
-	void CIMUDeducedReckoning::OnIMUIntegratedState(const timeval& TimeStamp, const CIMUDevice* pIMUDevice)
-	{
-		const IMUState CurrentState = pIMUDevice->GetIMUState();
-		if (m_IsVerbose)
-		{
-			std::cout << "OnIMUStateUpdate(IMU Device ID = 0x" << std::hex << pIMUDevice->GetDeviceId() << ((GetDispatchingMode() == eCoupled) ? " Coupled" : " Decoupled") << std::dec << ")" << std::endl;
-			std::cout << "\t[ Global time  = " << CTimeStamp::GetElapsedSeconds(TimeStamp,pIMUDevice->GetReferenceTimeStamp()) << " s]" << std::endl;
-			std::cout << "\t[ Latency = " << CTimeStamp::GetElapsedMicroseconds(TimeStamp,GetLastIntegratedStateReferenceTimeStamp()) << " µs]" << std::endl;
-			if (GetDispatchingMode() == eDecoupled)
-			{
-				std::cout << "\t[ Pending Events  = " << GetTotalPendingEvents() << "]" << std::endl;
-				std::cout << "\t[ Maximal Pending Events  = " << GetMaximalPendingEvents() << "]" << std::endl;
-			}
-			std::cout << "\t[ Cycle  = " << CurrentState.m_ControlData.m_MessageCounter << "]" << std::endl;
-			std::cout << "\t[ Acceleration  = [" << CurrentState.m_PhysicalData.m_Acceleration[0] << "," << CurrentState.m_PhysicalData.m_Acceleration[1] << "," << CurrentState.m_PhysicalData.m_Acceleration[2] << "]" << std::endl;
-			std::cout << "\t[ Acceleration Magnitude = [" << std::abs(CurrentState.m_PhysicalData.m_AccelerationMagnitud - m_G) * 1000.0f << " mm/s^2]" << std::endl;
-			std::cout << "\t[ Gyroscope Rotation  = [" << CurrentState.m_PhysicalData.m_GyroscopeRotation[0] << "," << CurrentState.m_PhysicalData.m_GyroscopeRotation[1] << "," << CurrentState.m_PhysicalData.m_GyroscopeRotation[2] << "]" << std::endl;
-			std::cout << "\t[ Magnetic Rotation  = [" << CurrentState.m_PhysicalData.m_MagneticRotation[0] << "," << CurrentState.m_PhysicalData.m_MagneticRotation[1] << "," << CurrentState.m_PhysicalData.m_MagneticRotation[2] << "]" << std::endl;
-			std::cout << "\t[ Quaternion Rotation  = [" << CurrentState.m_PhysicalData.m_QuaternionRotation[0] << "," << CurrentState.m_PhysicalData.m_QuaternionRotation[1] << "," << CurrentState.m_PhysicalData.m_QuaternionRotation[2] << "," << CurrentState.m_PhysicalData.m_QuaternionRotation[3] << "]" << std::endl;
-		}
-	}
-
-	void CIMUDeducedReckoning::OnIMUCustomEvent(const CIMUEvent& CustomEvent)
-	{
-		if (m_IsVerbose)
-		{
-			std::cout << "OnIMUCustomEvent(IMU Device ID = 0x" << std::hex << CustomEvent.GetIMU()->GetDeviceId() << ((GetDispatchingMode() == eCoupled) ? " Coupled" : " Decoupled") << std::dec << ")" << std::endl;
-			std::cout << "\t[ Latency  = " << CTimeStamp::GetElapsedMicroseconds(CustomEvent.GetTimeStamp(),CustomEvent.GetIMU()->GetReferenceTimeStamp()) << " µs]" << std::endl;
-			std::cout << "\t[ Latency  = " << CTimeStamp::GetElapsedMicroseconds(CustomEvent.GetTimeStamp(),GetLastCustomEventReferenceTimeStamp()) << " µs]" << std::endl;
-			if (GetDispatchingMode() == eDecoupled)
-			{
-				std::cout << "\t[ Pending Events  = " << GetTotalPendingEvents() << "]" << std::endl;
-				std::cout << "\t[ Maximal Pending Events  = " << GetMaximalPendingEvents() << "]" << std::endl;
-			}
-		}
-	}
+    CIMUDeducedReckoning::CIMUDeducedReckoning(const bool IsVerbose) :
+        IIMUEventDispatcher(), m_IsVerbose(IsVerbose), m_G(IMU::CGeolocationInformation::GetGravitationalAcceleration())
+    {
+        SetEventHandling(CIMUEvent::eOnIMUStart, true);
+        SetEventHandling(CIMUEvent::eOnIMUStop, true);
+        SetEventHandling(CIMUEvent::eOnIMUCycle, false);
+        SetEventHandling(CIMUEvent::eOnIMUFusedCycle, true);
+        SetEventHandling(CIMUEvent::eOnIMUIntegratedState, false);
+        SetEventHandling(CIMUEvent::eOnIMUCustomEvent, true);
+    }
+
+    CIMUDeducedReckoning::~CIMUDeducedReckoning()
+    {
+    }
+
+    void CIMUDeducedReckoning::OnIMUEvent(const CIMUEvent& Event)
+    {
+        switch (Event.GetEventType())
+        {
+            case CIMUEvent::eOnIMUCycle:
+                OnIMUCycle(Event.GetTimeStamp(), Event.GetIMU());
+                break;
+
+            case CIMUEvent::eOnIMUFusedCycle:
+                OnIMUFusedCycle(Event.GetTimeStamp(), Event.GetIMU());
+                break;
+
+            case CIMUEvent::eOnIMUIntegratedState:
+                OnIMUIntegratedState(Event.GetTimeStamp(), Event.GetIMU());
+                break;
+
+            case CIMUEvent::eOnIMUCustomEvent:
+                OnIMUCustomEvent(Event);
+                break;
+
+            case CIMUEvent::eOnIMUStart:
+                OnIMUStart(Event.GetTimeStamp(), Event.GetIMU());
+                break;
+
+            case CIMUEvent::eOnIMUStop:
+                OnIMUStop(Event.GetTimeStamp(), Event.GetIMU());
+                break;
+        }
+    }
+
+    void CIMUDeducedReckoning::OnIMUStart(const timeval& TimeStamp, const CIMUDevice* pIMUDevice)
+    {
+        if (m_IsVerbose)
+        {
+            std::cout << "OnIMUStart(IMU Device ID = " << pIMUDevice->GetDeviceId() << ((GetDispatchingMode() == eCoupled) ? " Coupled" : " Decoupled") << ")" << std::endl;
+            std::cout << "\t[ Global time  = " << CTimeStamp::GetElapsedSeconds(TimeStamp, pIMUDevice->GetReferenceTimeStamp()) << " s]" << std::endl;
+            std::cout << "\t[ Latency  = " << CTimeStamp::GetElapsedMicroseconds(TimeStamp, GetLastStartTimeStamp()) << "]" << std::endl;
+
+            if (GetDispatchingMode() == eDecoupled)
+            {
+                std::cout << "\t[ Pending Events  = " << GetTotalPendingEvents() << "]" << std::endl;
+                std::cout << "\t[ Maximal Pending Events  = " << GetMaximalPendingEvents() << "]" << std::endl;
+            }
+        }
+    }
+
+    void CIMUDeducedReckoning::OnIMUStop(const timeval& TimeStamp, const CIMUDevice* pIMUDevice)
+    {
+        if (m_IsVerbose)
+        {
+            std::cout << "OnIMUStop(IMU Device ID = " << pIMUDevice->GetDeviceId() << ((GetDispatchingMode() == eCoupled) ? " Coupled" : " Decoupled") << ")" << std::endl;
+            std::cout << "\t[ Global time  = " << CTimeStamp::GetElapsedSeconds(TimeStamp, pIMUDevice->GetReferenceTimeStamp()) << " s]" << std::endl;
+            std::cout << "\t[ Latency  = " << CTimeStamp::GetElapsedMicroseconds(TimeStamp, GetLastStopTimeStamp()) << "]" << std::endl;
+
+            if (GetDispatchingMode() == eDecoupled)
+            {
+                std::cout << "\t[ Pending Events  = " << GetTotalPendingEvents() << "]" << std::endl;
+                std::cout << "\t[ Maximal Pending Events  = " << GetMaximalPendingEvents() << "]" << std::endl;
+            }
+        }
+    }
+
+    void CIMUDeducedReckoning::OnIMUCycle(const timeval& TimeStamp, const CIMUDevice* pIMUDevice)
+    {
+        const IMUState CurrentState = pIMUDevice->GetIMUState();
+
+        if (m_IsVerbose)
+        {
+            std::cout << "OnIMUCycle(IMU Device ID = 0x" << std::hex << pIMUDevice->GetDeviceId() << ((GetDispatchingMode() == eCoupled) ? " Coupled" : " Decoupled") << std::dec << ")" << std::endl;
+            std::cout << "\t[ Global time  = " << CTimeStamp::GetElapsedSeconds(TimeStamp, pIMUDevice->GetReferenceTimeStamp()) << " s]" << std::endl;
+            std::cout << "\t[ Latency  = " << CTimeStamp::GetElapsedMicroseconds(TimeStamp, GetLastCycleReferenceTimeStamp()) << " µs]" << std::endl;
+
+            if (GetDispatchingMode() == eDecoupled)
+            {
+                std::cout << "\t[ Pending Events  = " << GetTotalPendingEvents() << "]" << std::endl;
+                std::cout << "\t[ Maximal Pending Events  = " << GetMaximalPendingEvents() << "]" << std::endl;
+            }
+
+            std::cout << "\t[ Cycle  = " << CurrentState.m_ControlData.m_MessageCounter << "]" << std::endl;
+            std::cout << "\t[ Acceleration  = [" << CurrentState.m_PhysicalData.m_Acceleration[0] << "," << CurrentState.m_PhysicalData.m_Acceleration[1] << "," << CurrentState.m_PhysicalData.m_Acceleration[2] << "]" << std::endl;
+            std::cout << "\t[ Acceleration Magnitude = [" << std::abs(CurrentState.m_PhysicalData.m_AccelerationMagnitud - m_G) * 1000.0f << " mm/s^2]" << std::endl;
+            std::cout << "\t[ Gyroscope Rotation  = [" << CurrentState.m_PhysicalData.m_GyroscopeRotation[0] << "," << CurrentState.m_PhysicalData.m_GyroscopeRotation[1] << "," << CurrentState.m_PhysicalData.m_GyroscopeRotation[2] << "]" << std::endl;
+            std::cout << "\t[ Magnetic Rotation  = [" << CurrentState.m_PhysicalData.m_MagneticRotation[0] << "," << CurrentState.m_PhysicalData.m_MagneticRotation[1] << "," << CurrentState.m_PhysicalData.m_MagneticRotation[2] << "]" << std::endl;
+            std::cout << "\t[ Quaternion Rotation  = [" << CurrentState.m_PhysicalData.m_QuaternionRotation[0] << "," << CurrentState.m_PhysicalData.m_QuaternionRotation[1] << "," << CurrentState.m_PhysicalData.m_QuaternionRotation[2] << "," << CurrentState.m_PhysicalData.m_QuaternionRotation[3] << "]" << std::endl;
+        }
+
+        memcpy(m_OrientationQuaternion, CurrentState.m_PhysicalData.m_QuaternionRotation, sizeof(float) * 4);
+        memcpy(m_MagneticRotation, CurrentState.m_PhysicalData.m_MagneticRotation, sizeof(float) * 3);
+        memcpy(m_GyroscopeRotation, CurrentState.m_PhysicalData.m_GyroscopeRotation, sizeof(float) * 3);
+        memcpy(m_Accelaration, CurrentState.m_PhysicalData.m_Acceleration, sizeof(float) * 3);
+    }
+
+    void CIMUDeducedReckoning::OnIMUFusedCycle(const timeval& TimeStamp, const CIMUDevice* pIMUDevice)
+    {
+        const IMUState CurrentState = pIMUDevice->GetIMUState();
+
+        if (m_IsVerbose)
+        {
+            std::cout << "OnIMUFusedCycle(IMU Device ID = 0x" << std::hex << pIMUDevice->GetDeviceId() << ((GetDispatchingMode() == eCoupled) ? " Coupled" : " Decoupled") << std::dec << ")" << std::endl;
+            std::cout << "\t[ Global time  = " << CTimeStamp::GetElapsedSeconds(TimeStamp, pIMUDevice->GetReferenceTimeStamp()) << " s]" << std::endl;
+            std::cout << "\t[ Latency  = " << CTimeStamp::GetElapsedMicroseconds(TimeStamp, GetLastFusedCycleReferenceTimeStamp()) << " µs]" << std::endl;
+
+            if (GetDispatchingMode() == eDecoupled)
+            {
+                std::cout << "\t[ Pending Events  = " << GetTotalPendingEvents() << "]" << std::endl;
+                std::cout << "\t[ Maximal Pending Events  = " << GetMaximalPendingEvents() << "]" << std::endl;
+            }
+
+            std::cout << "\t[ Cycle  = " << CurrentState.m_ControlData.m_MessageCounter << "]" << std::endl;
+            std::cout << "\t[ Acceleration  = [" << CurrentState.m_PhysicalData.m_Acceleration[0] << "," << CurrentState.m_PhysicalData.m_Acceleration[1] << "," << CurrentState.m_PhysicalData.m_Acceleration[2] << "]" << std::endl;
+            std::cout << "\t[ Acceleration Magnitude = [" << std::abs(CurrentState.m_PhysicalData.m_AccelerationMagnitud - m_G) * 1000.0f << " mm/s^2]" << std::endl;
+            std::cout << "\t[ Gyroscope Rotation  = [" << CurrentState.m_PhysicalData.m_GyroscopeRotation[0] << "," << CurrentState.m_PhysicalData.m_GyroscopeRotation[1] << "," << CurrentState.m_PhysicalData.m_GyroscopeRotation[2] << "]" << std::endl;
+            std::cout << "\t[ Magnetic Rotation  = [" << CurrentState.m_PhysicalData.m_MagneticRotation[0] << "," << CurrentState.m_PhysicalData.m_MagneticRotation[1] << "," << CurrentState.m_PhysicalData.m_MagneticRotation[2] << "]" << std::endl;
+            std::cout << "\t[ Quaternion Rotation  = [" << CurrentState.m_PhysicalData.m_QuaternionRotation[0] << "," << CurrentState.m_PhysicalData.m_QuaternionRotation[1] << "," << CurrentState.m_PhysicalData.m_QuaternionRotation[2] << "," << CurrentState.m_PhysicalData.m_QuaternionRotation[3] << "]" << std::endl;
+        }
+
+        memcpy(m_OrientationQuaternion, CurrentState.m_PhysicalData.m_QuaternionRotation, sizeof(float) * 4);
+        memcpy(m_MagneticRotation, CurrentState.m_PhysicalData.m_MagneticRotation, sizeof(float) * 3);
+        memcpy(m_GyroscopeRotation, CurrentState.m_PhysicalData.m_GyroscopeRotation, sizeof(float) * 3);
+        memcpy(m_Accelaration, CurrentState.m_PhysicalData.m_Acceleration, sizeof(float) * 3);
+    }
+
+    void CIMUDeducedReckoning::OnIMUIntegratedState(const timeval& TimeStamp, const CIMUDevice* pIMUDevice)
+    {
+        const IMUState CurrentState = pIMUDevice->GetIMUState();
+
+        if (m_IsVerbose)
+        {
+            std::cout << "OnIMUStateUpdate(IMU Device ID = 0x" << std::hex << pIMUDevice->GetDeviceId() << ((GetDispatchingMode() == eCoupled) ? " Coupled" : " Decoupled") << std::dec << ")" << std::endl;
+            std::cout << "\t[ Global time  = " << CTimeStamp::GetElapsedSeconds(TimeStamp, pIMUDevice->GetReferenceTimeStamp()) << " s]" << std::endl;
+            std::cout << "\t[ Latency = " << CTimeStamp::GetElapsedMicroseconds(TimeStamp, GetLastIntegratedStateReferenceTimeStamp()) << " µs]" << std::endl;
+
+            if (GetDispatchingMode() == eDecoupled)
+            {
+                std::cout << "\t[ Pending Events  = " << GetTotalPendingEvents() << "]" << std::endl;
+                std::cout << "\t[ Maximal Pending Events  = " << GetMaximalPendingEvents() << "]" << std::endl;
+            }
+
+            std::cout << "\t[ Cycle  = " << CurrentState.m_ControlData.m_MessageCounter << "]" << std::endl;
+            std::cout << "\t[ Acceleration  = [" << CurrentState.m_PhysicalData.m_Acceleration[0] << "," << CurrentState.m_PhysicalData.m_Acceleration[1] << "," << CurrentState.m_PhysicalData.m_Acceleration[2] << "]" << std::endl;
+            std::cout << "\t[ Acceleration Magnitude = [" << std::abs(CurrentState.m_PhysicalData.m_AccelerationMagnitud - m_G) * 1000.0f << " mm/s^2]" << std::endl;
+            std::cout << "\t[ Gyroscope Rotation  = [" << CurrentState.m_PhysicalData.m_GyroscopeRotation[0] << "," << CurrentState.m_PhysicalData.m_GyroscopeRotation[1] << "," << CurrentState.m_PhysicalData.m_GyroscopeRotation[2] << "]" << std::endl;
+            std::cout << "\t[ Magnetic Rotation  = [" << CurrentState.m_PhysicalData.m_MagneticRotation[0] << "," << CurrentState.m_PhysicalData.m_MagneticRotation[1] << "," << CurrentState.m_PhysicalData.m_MagneticRotation[2] << "]" << std::endl;
+            std::cout << "\t[ Quaternion Rotation  = [" << CurrentState.m_PhysicalData.m_QuaternionRotation[0] << "," << CurrentState.m_PhysicalData.m_QuaternionRotation[1] << "," << CurrentState.m_PhysicalData.m_QuaternionRotation[2] << "," << CurrentState.m_PhysicalData.m_QuaternionRotation[3] << "]" << std::endl;
+        }
+    }
+
+    void CIMUDeducedReckoning::OnIMUCustomEvent(const CIMUEvent& CustomEvent)
+    {
+        if (m_IsVerbose)
+        {
+            std::cout << "OnIMUCustomEvent(IMU Device ID = 0x" << std::hex << CustomEvent.GetIMU()->GetDeviceId() << ((GetDispatchingMode() == eCoupled) ? " Coupled" : " Decoupled") << std::dec << ")" << std::endl;
+            std::cout << "\t[ Latency  = " << CTimeStamp::GetElapsedMicroseconds(CustomEvent.GetTimeStamp(), CustomEvent.GetIMU()->GetReferenceTimeStamp()) << " µs]" << std::endl;
+            std::cout << "\t[ Latency  = " << CTimeStamp::GetElapsedMicroseconds(CustomEvent.GetTimeStamp(), GetLastCustomEventReferenceTimeStamp()) << " µs]" << std::endl;
+
+            if (GetDispatchingMode() == eDecoupled)
+            {
+                std::cout << "\t[ Pending Events  = " << GetTotalPendingEvents() << "]" << std::endl;
+                std::cout << "\t[ Maximal Pending Events  = " << GetMaximalPendingEvents() << "]" << std::endl;
+            }
+        }
+    }
 }
diff --git a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUDeducedReckoning.h b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUDeducedReckoning.h
old mode 100755
new mode 100644
index d2617867402ba6e95a3369190de635114737bf9b..8315bb663a9718436cd326c5dca62c42ac66df38
--- a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUDeducedReckoning.h
+++ b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUDeducedReckoning.h
@@ -3,7 +3,7 @@
  *
  *  Created on: Mar 16, 2014
  *      Author: Dr.-Ing. David Israel González Aguirre
- *      Mail:	david.gonzalez@kit.edu
+ *      Mail:   david.gonzalez@kit.edu
  */
 
 #ifndef IMUDEDUCEDRECKONING_H_
@@ -15,52 +15,52 @@
 
 namespace IMU
 {
-	class CIMUDeducedReckoning : public IIMUEventDispatcher
-	{
-		public:
+    class CIMUDeducedReckoning : public IIMUEventDispatcher
+    {
+    public:
 
-			CIMUDeducedReckoning(const bool IsVerbose);
-			virtual ~CIMUDeducedReckoning();
+        CIMUDeducedReckoning(const bool IsVerbose);
+        virtual ~CIMUDeducedReckoning();
 
-			inline const float* GetOrientationQuaternion() const
-			{
-				return m_OrientationQuaternion;
-			}
+        inline const float* GetOrientationQuaternion() const
+        {
+            return m_OrientationQuaternion;
+        }
 
-			inline const float* GetMagneticRotation() const
-			{
-				return m_MagneticRotation;
-			}
+        inline const float* GetMagneticRotation() const
+        {
+            return m_MagneticRotation;
+        }
 
-			inline const float* GetGyroscopeRotation() const
-			{
-				return m_GyroscopeRotation;
-			}
+        inline const float* GetGyroscopeRotation() const
+        {
+            return m_GyroscopeRotation;
+        }
 
-			inline const float* GetAccelaration() const
-			{
-				return m_Accelaration;
-			}
+        inline const float* GetAccelaration() const
+        {
+            return m_Accelaration;
+        }
 
-		protected:
+    protected:
 
-			virtual void OnIMUEvent(const CIMUEvent& Event);
+        virtual void OnIMUEvent(const CIMUEvent& Event);
 
-			void OnIMUStart(const timeval& TimeStamp, const CIMUDevice* pIMUDevice);
-			void OnIMUStop(const timeval& TimeStamp, const CIMUDevice* pIMUDevice);
-			void OnIMUFusedCycle(const timeval& TimeStamp, const CIMUDevice* pIMUDevice);
-			void OnIMUCycle(const timeval& TimeStamp, const CIMUDevice* pIMUDevice);
-			void OnIMUIntegratedState(const timeval& TimeStamp, const CIMUDevice* pIMUDevice);
-			void OnIMUCustomEvent(const CIMUEvent& CustomEvent);
+        void OnIMUStart(const timeval& TimeStamp, const CIMUDevice* pIMUDevice);
+        void OnIMUStop(const timeval& TimeStamp, const CIMUDevice* pIMUDevice);
+        void OnIMUFusedCycle(const timeval& TimeStamp, const CIMUDevice* pIMUDevice);
+        void OnIMUCycle(const timeval& TimeStamp, const CIMUDevice* pIMUDevice);
+        void OnIMUIntegratedState(const timeval& TimeStamp, const CIMUDevice* pIMUDevice);
+        void OnIMUCustomEvent(const CIMUEvent& CustomEvent);
 
-			const bool m_IsVerbose;
-			const float m_G;
+        const bool m_IsVerbose;
+        const float m_G;
 
-			float m_OrientationQuaternion[4];
-			float m_MagneticRotation[3];
-			float m_GyroscopeRotation[3];
-			float m_Accelaration[3];
-	};
+        float m_OrientationQuaternion[4];
+        float m_MagneticRotation[3];
+        float m_GyroscopeRotation[3];
+        float m_Accelaration[3];
+    };
 }
 
 #endif
diff --git a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUDevice.cpp b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUDevice.cpp
old mode 100755
new mode 100644
index 77336df645c8aac6b4b561ae4700b92b39a8a8d6..2a69eeb8d2336b3b585e29bd2653effd25586e50
--- a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUDevice.cpp
+++ b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUDevice.cpp
@@ -3,7 +3,7 @@
  *
  *  Created on: Mar 16, 2014
  *      Author: Dr.-Ing. David Israel González Aguirre
- *      Mail:	david.gonzalez@kit.edu
+ *      Mail:   david.gonzalez@kit.edu
  */
 
 #include "IMUDevice.h"
@@ -11,559 +11,646 @@
 
 namespace IMU
 {
-	CIMUDevice::CIMUDevice() :
-			m_DeviceId(0), m_SamplingFrequency(SamplingFrequency(0)), m_PeriodMicroSeconds(0), m_FusionStrategy(eNoFusion), m_SamplesPerFusion(0), m_CollectedFusionSamples(0), m_IsActive(false), m_IsDispatching(false), m_IsInitialized(false), m_pInternalThreadHandel(0), m_IMUEventDispatchers(), m_ReferenceTimeStamp(CTimeStamp::s_Zero), m_LastFrameTimeStamp(CTimeStamp::s_Zero)
+    CIMUDevice::CIMUDevice() :
+        m_DeviceId(0), m_SamplingFrequency(SamplingFrequency(0)), m_PeriodMicroSeconds(0), m_FusionStrategy(eNoFusion), m_SamplesPerFusion(0), m_CollectedFusionSamples(0), m_IsActive(false), m_IsDispatching(false), m_IsInitialized(false), m_pInternalThreadHandel(0), m_IMUEventDispatchers(), m_ReferenceTimeStamp(CTimeStamp::s_Zero), m_LastFrameTimeStamp(CTimeStamp::s_Zero)
 
 #ifdef _IMU_USE_XSENS_DEVICE_
 
-			        , m_pXsensMTiModule(NULL)
+        , m_pXsensMTiModule(NULL)
 #endif
 
-	{
-		pthread_mutex_init(&m_IsActiveMutex,NULL);
-		pthread_mutex_init(&m_IsDispatchingMutex,NULL);
-		pthread_mutex_init(&m_EventDispatchersMutex,NULL);
-		pthread_mutex_init(&m_DeviceMutex,NULL);
-	}
-
-	CIMUDevice::~CIMUDevice()
-	{
-		FinalizeModuleDevice();
-	}
-
-	uint64_t CIMUDevice::GetDeviceId() const
-	{
-		return m_DeviceId;
-	}
-
-	bool CIMUDevice::Connect(const std::string& PortName, const SamplingFrequency Frequency)
-	{
-		if (m_IsInitialized)
-			return true;
-
-		if (!PortName.length())
-		{
-			std::cerr << "[IMU Error: Cannot connect to empty port name!]\n\t[Operation result: (PortName.length()==0)]\n[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
-			return false;
-		}
-
-		m_IsInitialized = InitializeDevice(PortName,Frequency);
-
-		return m_IsInitialized;
-	}
-
-	bool CIMUDevice::Start(const bool Blocking)
-	{
-		if (m_IsInitialized && (!m_IsActive))
-		{
-			const int Result = pthread_create(&m_pInternalThreadHandel,NULL,CIMUDevice::ThreadLoop,(void*) this);
-			if (Result == 0)
-			{
-				while(Blocking && !m_IsActive)
-					pthread_yield();
-				return true;
-			}
-		}
-		return false;
-	}
-
-	void CIMUDevice::Stop(const bool Blocking)
-	{
-		if (m_IsActive)
-		{
-			_MINIMAL___LOCK(m_IsActiveMutex)
-			m_IsActive = false;
-			_MINIMAL_UNLOCK(m_IsActiveMutex)
-			pthread_join(m_pInternalThreadHandel,NULL);
-			while(Blocking && m_IsDispatching)
-				pthread_yield();
-		}
-	}
-
-	bool CIMUDevice::SetFusion(const FusionStrategy Strategy, const ushort SamplesPerFusion)
-	{
-		if (SamplesPerFusion > 1)
-		{
-			if ((m_FusionStrategy != Strategy) || (m_SamplesPerFusion != SamplesPerFusion))
-			{
-				m_FusionStrategy = Strategy;
-				m_SamplesPerFusion = SamplesPerFusion;
-				m_CollectedFusionSamples = 0;
-			}
-			return true;
-		}
-		else
-		{
-			std::cerr << "[IMU Device error: Cannot set fusion with less than 2 samples per fusion!]\n\t[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
-			return false;
-		}
-	}
-
-	bool CIMUDevice::IsActive() const
-	{
-		return m_IsActive;
-	}
-
-	bool CIMUDevice::RegisterEventDispatcher(IIMUEventDispatcher* pIMUEventDispatcher)
-	{
-		if (pIMUEventDispatcher)
-		{
-			_MINIMAL___LOCK(m_EventDispatchersMutex)
-			if (m_IMUEventDispatchers.find(pIMUEventDispatcher) == m_IMUEventDispatchers.end())
-			{
-				pIMUEventDispatcher->SetIMU(this);
-				pIMUEventDispatcher->SetReferenceTimeStamps(m_ReferenceTimeStamp);
-				std::pair<std::set<IIMUEventDispatcher*>::iterator, bool> Result = m_IMUEventDispatchers.insert(pIMUEventDispatcher);
-				_MINIMAL_UNLOCK(m_EventDispatchersMutex)
-				return Result.second;
-			}
-			_MINIMAL_UNLOCK(m_EventDispatchersMutex)
-		}
-		return false;
-	}
-
-	bool CIMUDevice::UnregisterEventDispatcher(IIMUEventDispatcher* pIMUEventDispatcher)
-	{
-		if (pIMUEventDispatcher)
-		{
-			_MINIMAL___LOCK(m_EventDispatchersMutex)
-			std::set<IIMUEventDispatcher*>::iterator ppElement = m_IMUEventDispatchers.find(pIMUEventDispatcher);
-			if (ppElement != m_IMUEventDispatchers.end())
-			{
-				pIMUEventDispatcher->SetIMU(NULL);
-				m_IMUEventDispatchers.erase(ppElement);
-				_MINIMAL_UNLOCK(m_EventDispatchersMutex)
-				return true;
-			}
-			_MINIMAL_UNLOCK(m_EventDispatchersMutex)
-		}
-		return false;
-	}
-
-	void CIMUDevice::UnregisterEventDispatchers()
-	{
-		if (m_IMUEventDispatchers.size())
-		{
-			_MINIMAL___LOCK(m_EventDispatchersMutex)
-			for(std::set<IIMUEventDispatcher*>::iterator ppElement = m_IMUEventDispatchers.begin() ; ppElement != m_IMUEventDispatchers.end() ; ++ppElement)
-				(*ppElement)->SetIMU(NULL);
-			m_IMUEventDispatchers.clear();
-			_MINIMAL_UNLOCK(m_EventDispatchersMutex)
-		}
-	}
+    {
+        pthread_mutex_init(&m_IsActiveMutex, NULL);
+        pthread_mutex_init(&m_IsDispatchingMutex, NULL);
+        pthread_mutex_init(&m_EventDispatchersMutex, NULL);
+        pthread_mutex_init(&m_DeviceMutex, NULL);
+    }
+
+    CIMUDevice::~CIMUDevice()
+    {
+        FinalizeModuleDevice();
+    }
+
+    uint64_t CIMUDevice::GetDeviceId() const
+    {
+        return m_DeviceId;
+    }
+
+    bool CIMUDevice::Connect(const std::string& PortName, const SamplingFrequency Frequency)
+    {
+        if (m_IsInitialized)
+        {
+            return true;
+        }
+
+        if (!PortName.length())
+        {
+            std::cerr << "[IMU Error: Cannot connect to empty port name!]\n\t[Operation result: (PortName.length()==0)]\n[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
+            return false;
+        }
+
+        m_IsInitialized = InitializeDevice(PortName, Frequency);
+
+        return m_IsInitialized;
+    }
+
+    bool CIMUDevice::Start(const bool Blocking)
+    {
+        if (m_IsInitialized && (!m_IsActive))
+        {
+            const int Result = pthread_create(&m_pInternalThreadHandel, NULL, CIMUDevice::ThreadLoop, (void*) this);
+
+            if (Result == 0)
+            {
+                while (Blocking && !m_IsActive)
+                {
+                    pthread_yield();
+                }
+
+                return true;
+            }
+        }
+
+        return false;
+    }
+
+    void CIMUDevice::Stop(const bool Blocking)
+    {
+        if (m_IsActive)
+        {
+            _MINIMAL___LOCK(m_IsActiveMutex)
+            m_IsActive = false;
+            _MINIMAL_UNLOCK(m_IsActiveMutex)
+            pthread_join(m_pInternalThreadHandel, NULL);
+
+            while (Blocking && m_IsDispatching)
+            {
+                pthread_yield();
+            }
+        }
+    }
+
+    bool CIMUDevice::SetFusion(const FusionStrategy Strategy, const ushort SamplesPerFusion)
+    {
+        if (SamplesPerFusion > 1)
+        {
+            if ((m_FusionStrategy != Strategy) || (m_SamplesPerFusion != SamplesPerFusion))
+            {
+                m_FusionStrategy = Strategy;
+                m_SamplesPerFusion = SamplesPerFusion;
+                m_CollectedFusionSamples = 0;
+            }
+
+            return true;
+        }
+        else
+        {
+            std::cerr << "[IMU Device error: Cannot set fusion with less than 2 samples per fusion!]\n\t[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
+            return false;
+        }
+    }
+
+    bool CIMUDevice::IsActive() const
+    {
+        return m_IsActive;
+    }
+
+    bool CIMUDevice::RegisterEventDispatcher(IIMUEventDispatcher* pIMUEventDispatcher)
+    {
+        if (pIMUEventDispatcher)
+        {
+            _MINIMAL___LOCK(m_EventDispatchersMutex)
+
+            if (m_IMUEventDispatchers.find(pIMUEventDispatcher) == m_IMUEventDispatchers.end())
+            {
+                pIMUEventDispatcher->SetIMU(this);
+                pIMUEventDispatcher->SetReferenceTimeStamps(m_ReferenceTimeStamp);
+                std::pair<std::set<IIMUEventDispatcher*>::iterator, bool> Result = m_IMUEventDispatchers.insert(pIMUEventDispatcher);
+                _MINIMAL_UNLOCK(m_EventDispatchersMutex)
+                return Result.second;
+            }
+
+            _MINIMAL_UNLOCK(m_EventDispatchersMutex)
+        }
+
+        return false;
+    }
+
+    bool CIMUDevice::UnregisterEventDispatcher(IIMUEventDispatcher* pIMUEventDispatcher)
+    {
+        if (pIMUEventDispatcher)
+        {
+            _MINIMAL___LOCK(m_EventDispatchersMutex)
+            std::set<IIMUEventDispatcher*>::iterator ppElement = m_IMUEventDispatchers.find(pIMUEventDispatcher);
+
+            if (ppElement != m_IMUEventDispatchers.end())
+            {
+                pIMUEventDispatcher->SetIMU(NULL);
+                m_IMUEventDispatchers.erase(ppElement);
+                _MINIMAL_UNLOCK(m_EventDispatchersMutex)
+                return true;
+            }
+
+            _MINIMAL_UNLOCK(m_EventDispatchersMutex)
+        }
+
+        return false;
+    }
+
+    void CIMUDevice::UnregisterEventDispatchers()
+    {
+        if (m_IMUEventDispatchers.size())
+        {
+            _MINIMAL___LOCK(m_EventDispatchersMutex)
+
+            for (std::set<IIMUEventDispatcher*>::iterator ppElement = m_IMUEventDispatchers.begin() ; ppElement != m_IMUEventDispatchers.end() ; ++ppElement)
+            {
+                (*ppElement)->SetIMU(NULL);
+            }
+
+            m_IMUEventDispatchers.clear();
+            _MINIMAL_UNLOCK(m_EventDispatchersMutex)
+        }
+    }
 
 #ifdef _IMU_USE_XSENS_DEVICE_
 
-	bool CIMUDevice::InitializeXsensDevice(const std::string& PortName, const SamplingFrequency Frequency)
-	{
-		if (m_IsInitialized)
-			return true;
-
-		m_pXsensMTiModule = new Xsens::CXsensMTiModule();
-
-		if (m_pXsensMTiModule->openPort(PortName.c_str()) != MTRV_OK)
-		{
-			std::cerr << "[IMU Device error: Cannot open port!]\n\t[Operation result: " << m_pXsensMTiModule->getLastRetVal() << "]\n\t[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
-			DestroyXsensModuleDevice();
-			return false;
-		}
-
-		if (m_pXsensMTiModule->writeMessage(MID_GOTOCONFIG) != MTRV_OK)
-		{
-			std::cerr << "[IMU Device error: Cannot set configuration state!]\n\t[Operation result: " << m_pXsensMTiModule->getLastRetVal() << "]\n\t[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
-			DestroyXsensModuleDevice();
-			return false;
-		}
-
-		if (m_pXsensMTiModule->setDeviceMode(OUTPUTMODE_CALIB | OUTPUTMODE_ORIENT,OUTPUTSETTINGS_ORIENTMODE_QUATERNION | OUTPUTSETTINGS_TIMESTAMP_SAMPLECNT) != MTRV_OK)
-		{
-			std::cerr << "[IMU Device error: Cannot set output mode!]\n\t[Operation result: " << m_pXsensMTiModule->getLastRetVal() << "]\n\t[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
-			DestroyXsensModuleDevice();
-			return false;
-		}
-
-		if (m_pXsensMTiModule->setSetting(MID_SETPERIOD,Frequency,LEN_PERIOD) != MTRV_OK)
-		{
-			std::cerr << "[IMU Device error: Cannot set sampling period!]\n\t[Operation result: " << m_pXsensMTiModule->getLastRetVal() << "]\n\t[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
-			DestroyXsensModuleDevice();
-			return false;
-		}
-
-		unsigned long DeviceId;
-		if (m_pXsensMTiModule->reqSetting(MID_REQDID,DeviceId) != MTRV_OK)
-		{
-			std::cerr << "[IMU Device error: Cannot get device ID!]\n\t[Operation result: " << m_pXsensMTiModule->getLastRetVal() << "]\n\t[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
-			DestroyXsensModuleDevice();
-			return false;
-		}
-		m_DeviceId = DeviceId;
-
-		if (m_pXsensMTiModule->writeMessage(MID_GOTOMEASUREMENT) != MTRV_OK)
-		{
-			std::cerr << "[IMU Device error: Cannot enter measurement state!]\n\t[Operation result: " << m_pXsensMTiModule->getLastRetVal() << "]\n\t[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
-			DestroyXsensModuleDevice();
-			return false;
-		}
-
-		return true;
-	}
-
-	void CIMUDevice::FinalizeXsensModuleDevice()
-	{
-		if (m_IsInitialized)
-		{
-			while(m_IsActive || m_IsDispatching)
-				pthread_yield();
-
-			_MINIMAL___LOCK(m_DeviceMutex)
-			DestroyXsensModuleDevice();
-			_MINIMAL_UNLOCK(m_DeviceMutex)
-		}
-	}
-
-	void CIMUDevice::DestroyXsensModuleDevice()
-	{
-		if (m_pXsensMTiModule)
-		{
-			if (m_pXsensMTiModule->isPortOpen())
-				m_pXsensMTiModule->close();
-			delete m_pXsensMTiModule;
-			m_pXsensMTiModule = NULL;
-			m_DeviceId = 0;
-		}
-	}
+    bool CIMUDevice::InitializeXsensDevice(const std::string& PortName, const SamplingFrequency Frequency)
+    {
+        if (m_IsInitialized)
+        {
+            return true;
+        }
+
+        m_pXsensMTiModule = new Xsens::CXsensMTiModule();
+
+        if (m_pXsensMTiModule->openPort(PortName.c_str()) != MTRV_OK)
+        {
+            std::cerr << "[IMU Device error: Cannot open port!]\n\t[Operation result: " << m_pXsensMTiModule->getLastRetVal() << "]\n\t[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
+            DestroyXsensModuleDevice();
+            return false;
+        }
+
+        if (m_pXsensMTiModule->writeMessage(MID_GOTOCONFIG) != MTRV_OK)
+        {
+            std::cerr << "[IMU Device error: Cannot set configuration state!]\n\t[Operation result: " << m_pXsensMTiModule->getLastRetVal() << "]\n\t[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
+            DestroyXsensModuleDevice();
+            return false;
+        }
+
+        if (m_pXsensMTiModule->setDeviceMode(OUTPUTMODE_CALIB | OUTPUTMODE_ORIENT, OUTPUTSETTINGS_ORIENTMODE_QUATERNION | OUTPUTSETTINGS_TIMESTAMP_SAMPLECNT) != MTRV_OK)
+        {
+            std::cerr << "[IMU Device error: Cannot set output mode!]\n\t[Operation result: " << m_pXsensMTiModule->getLastRetVal() << "]\n\t[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
+            DestroyXsensModuleDevice();
+            return false;
+        }
+
+        if (m_pXsensMTiModule->setSetting(MID_SETPERIOD, Frequency, LEN_PERIOD) != MTRV_OK)
+        {
+            std::cerr << "[IMU Device error: Cannot set sampling period!]\n\t[Operation result: " << m_pXsensMTiModule->getLastRetVal() << "]\n\t[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
+            DestroyXsensModuleDevice();
+            return false;
+        }
+
+        unsigned long DeviceId;
+
+        if (m_pXsensMTiModule->reqSetting(MID_REQDID, DeviceId) != MTRV_OK)
+        {
+            std::cerr << "[IMU Device error: Cannot get device ID!]\n\t[Operation result: " << m_pXsensMTiModule->getLastRetVal() << "]\n\t[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
+            DestroyXsensModuleDevice();
+            return false;
+        }
+
+        m_DeviceId = DeviceId;
+
+        if (m_pXsensMTiModule->writeMessage(MID_GOTOMEASUREMENT) != MTRV_OK)
+        {
+            std::cerr << "[IMU Device error: Cannot enter measurement state!]\n\t[Operation result: " << m_pXsensMTiModule->getLastRetVal() << "]\n\t[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
+            DestroyXsensModuleDevice();
+            return false;
+        }
+
+        return true;
+    }
+
+    void CIMUDevice::FinalizeXsensModuleDevice()
+    {
+        if (m_IsInitialized)
+        {
+            while (m_IsActive || m_IsDispatching)
+            {
+                pthread_yield();
+            }
+
+            _MINIMAL___LOCK(m_DeviceMutex)
+            DestroyXsensModuleDevice();
+            _MINIMAL_UNLOCK(m_DeviceMutex)
+        }
+    }
+
+    void CIMUDevice::DestroyXsensModuleDevice()
+    {
+        if (m_pXsensMTiModule)
+        {
+            if (m_pXsensMTiModule->isPortOpen())
+            {
+                m_pXsensMTiModule->close();
+            }
+
+            delete m_pXsensMTiModule;
+            m_pXsensMTiModule = NULL;
+            m_DeviceId = 0;
+        }
+    }
 
 #endif
 
-	bool CIMUDevice::LoadCurrentState()
-	{
+    bool CIMUDevice::LoadCurrentState()
+    {
 
-		_MINIMAL___LOCK(m_DeviceMutex)
+        _MINIMAL___LOCK(m_DeviceMutex)
 
 #ifdef _IMU_USE_XSENS_DEVICE_
 
-		if (m_pXsensMTiModule->readDataMessage(m_XsensMTiFrame.m_Data,m_XsensMTiFrame.m_DataLength) == MTRV_OK)
-			if (m_pXsensMTiModule->getValue(VALUE_CALIB_ACC,m_XsensMTiFrame.m_IMUState.m_PhysicalData.m_Acceleration,m_XsensMTiFrame.m_Data) == MTRV_OK)
-				if (m_pXsensMTiModule->getValue(VALUE_CALIB_GYR,m_XsensMTiFrame.m_IMUState.m_PhysicalData.m_GyroscopeRotation,m_XsensMTiFrame.m_Data) == MTRV_OK)
-					if (m_pXsensMTiModule->getValue(VALUE_CALIB_MAG,m_XsensMTiFrame.m_IMUState.m_PhysicalData.m_MagneticRotation,m_XsensMTiFrame.m_Data) == MTRV_OK)
-						if (m_pXsensMTiModule->getValue(VALUE_ORIENT_QUAT,m_XsensMTiFrame.m_IMUState.m_PhysicalData.m_QuaternionRotation,m_XsensMTiFrame.m_Data) == MTRV_OK)
-							if (m_pXsensMTiModule->getValue(VALUE_SAMPLECNT,m_XsensMTiFrame.m_IMUState.m_ControlData.m_CurrentSampleCount,m_XsensMTiFrame.m_Data) == MTRV_OK)
-							{
-								if (m_XsensMTiFrame.m_IMUState.m_ControlData.m_PreviousSampleCount != -1)
-									m_XsensMTiFrame.m_IMUState.m_ControlData.m_IsConsecutive = ((m_XsensMTiFrame.m_IMUState.m_ControlData.m_PreviousSampleCount + 1) % 65536) == m_XsensMTiFrame.m_IMUState.m_ControlData.m_CurrentSampleCount;
-								m_XsensMTiFrame.m_IMUState.m_ControlData.m_PreviousSampleCount = m_XsensMTiFrame.m_IMUState.m_ControlData.m_CurrentSampleCount;
-								m_XsensMTiFrame.m_IMUState.m_ControlData.m_MessageCounter++;
-								gettimeofday(&m_XsensMTiFrame.m_IMUState.m_ControlData.m_TimeStamp,NULL);
-								m_LastFrameTimeStamp = m_XsensMTiFrame.m_IMUState.m_ControlData.m_TimeStamp;
-
-								m_XsensMTiFrame.m_IMUState.m_PhysicalData.UpdateAccelerationMagnitud();
-
-								_MINIMAL_UNLOCK(m_DeviceMutex)
-								return true;
-							}
-							else
-								std::cerr << "[IMU Device error: Fail to get sample count!]\n\t[Operation result: " << m_pXsensMTiModule->getLastRetVal() << "]\n\t[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
-						else
-							std::cerr << "[IMU Device error: Fail to get quaternion rotation!]\n\t[Operation result: " << m_pXsensMTiModule->getLastRetVal() << "]\n\t[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
-					else
-						std::cerr << "[IMU Device error: Fail to get magnetic rotation!]\n\t[Operation result: " << m_pXsensMTiModule->getLastRetVal() << "]\n\t[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
-				else
-					std::cerr << "[IMU Device error: Fail to get gyroscope rotation!]\n\t[Operation result: " << m_pXsensMTiModule->getLastRetVal() << "]\n\t[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
-			else
-				std::cerr << "[IMU Device error: Fail to get acceleration vector!]\n\t[Operation result: " << m_pXsensMTiModule->getLastRetVal() << "]\n\t[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
-		else
-			std::cerr << "[IMU Device error: Fail to read message!]\n\t[Operation result: " << m_pXsensMTiModule->getLastRetVal() << "]\n\t[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
+        if (m_pXsensMTiModule->readDataMessage(m_XsensMTiFrame.m_Data, m_XsensMTiFrame.m_DataLength) == MTRV_OK)
+            if (m_pXsensMTiModule->getValue(VALUE_CALIB_ACC, m_XsensMTiFrame.m_IMUState.m_PhysicalData.m_Acceleration, m_XsensMTiFrame.m_Data) == MTRV_OK)
+                if (m_pXsensMTiModule->getValue(VALUE_CALIB_GYR, m_XsensMTiFrame.m_IMUState.m_PhysicalData.m_GyroscopeRotation, m_XsensMTiFrame.m_Data) == MTRV_OK)
+                    if (m_pXsensMTiModule->getValue(VALUE_CALIB_MAG, m_XsensMTiFrame.m_IMUState.m_PhysicalData.m_MagneticRotation, m_XsensMTiFrame.m_Data) == MTRV_OK)
+                        if (m_pXsensMTiModule->getValue(VALUE_ORIENT_QUAT, m_XsensMTiFrame.m_IMUState.m_PhysicalData.m_QuaternionRotation, m_XsensMTiFrame.m_Data) == MTRV_OK)
+                            if (m_pXsensMTiModule->getValue(VALUE_SAMPLECNT, m_XsensMTiFrame.m_IMUState.m_ControlData.m_CurrentSampleCount, m_XsensMTiFrame.m_Data) == MTRV_OK)
+                            {
+                                if (m_XsensMTiFrame.m_IMUState.m_ControlData.m_PreviousSampleCount != -1)
+                                {
+                                    m_XsensMTiFrame.m_IMUState.m_ControlData.m_IsConsecutive = ((m_XsensMTiFrame.m_IMUState.m_ControlData.m_PreviousSampleCount + 1) % 65536) == m_XsensMTiFrame.m_IMUState.m_ControlData.m_CurrentSampleCount;
+                                }
+
+                                m_XsensMTiFrame.m_IMUState.m_ControlData.m_PreviousSampleCount = m_XsensMTiFrame.m_IMUState.m_ControlData.m_CurrentSampleCount;
+                                m_XsensMTiFrame.m_IMUState.m_ControlData.m_MessageCounter++;
+                                gettimeofday(&m_XsensMTiFrame.m_IMUState.m_ControlData.m_TimeStamp, NULL);
+                                m_LastFrameTimeStamp = m_XsensMTiFrame.m_IMUState.m_ControlData.m_TimeStamp;
+
+                                m_XsensMTiFrame.m_IMUState.m_PhysicalData.UpdateAccelerationMagnitud();
+
+                                _MINIMAL_UNLOCK(m_DeviceMutex)
+                                return true;
+                            }
+                            else
+                            {
+                                std::cerr << "[IMU Device error: Fail to get sample count!]\n\t[Operation result: " << m_pXsensMTiModule->getLastRetVal() << "]\n\t[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
+                            }
+                        else
+                        {
+                            std::cerr << "[IMU Device error: Fail to get quaternion rotation!]\n\t[Operation result: " << m_pXsensMTiModule->getLastRetVal() << "]\n\t[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
+                        }
+                    else
+                    {
+                        std::cerr << "[IMU Device error: Fail to get magnetic rotation!]\n\t[Operation result: " << m_pXsensMTiModule->getLastRetVal() << "]\n\t[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
+                    }
+                else
+                {
+                    std::cerr << "[IMU Device error: Fail to get gyroscope rotation!]\n\t[Operation result: " << m_pXsensMTiModule->getLastRetVal() << "]\n\t[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
+                }
+            else
+            {
+                std::cerr << "[IMU Device error: Fail to get acceleration vector!]\n\t[Operation result: " << m_pXsensMTiModule->getLastRetVal() << "]\n\t[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
+            }
+        else
+        {
+            std::cerr << "[IMU Device error: Fail to read message!]\n\t[Operation result: " << m_pXsensMTiModule->getLastRetVal() << "]\n\t[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
+        }
 
 #endif
 
-		_MINIMAL_UNLOCK(m_DeviceMutex)
-
-		return false;
-	}
-
-	bool CIMUDevice::MeanFuseCurrentState()
-	{
-		IncorporateCurrentStateMeanFusion();
-		if (m_CollectedFusionSamples == m_SamplesPerFusion)
-		{
-			MeanFusion();
-			return true;
-		}
-		return false;
-	}
-
-	void CIMUDevice::IncorporateCurrentStateMeanFusion()
-	{
-		m_FusedPhysicalData.m_Acceleration[0] += m_XsensMTiFrame.m_IMUState.m_PhysicalData.m_Acceleration[0];
-		m_FusedPhysicalData.m_Acceleration[1] += m_XsensMTiFrame.m_IMUState.m_PhysicalData.m_Acceleration[1];
-		m_FusedPhysicalData.m_Acceleration[2] += m_XsensMTiFrame.m_IMUState.m_PhysicalData.m_Acceleration[2];
-		++m_CollectedFusionSamples;
-	}
-
-	void CIMUDevice::MeanFusion()
-	{
-		//Execution the fusion
-		const float NormalizationFactor = 1.0f / float(m_CollectedFusionSamples);
-		m_FusedIMUState.m_PhysicalData.m_Acceleration[0] = m_FusedPhysicalData.m_Acceleration[0] * NormalizationFactor;
-		m_FusedIMUState.m_PhysicalData.m_Acceleration[1] = m_FusedPhysicalData.m_Acceleration[1] * NormalizationFactor;
-		m_FusedIMUState.m_PhysicalData.m_Acceleration[2] = m_FusedPhysicalData.m_Acceleration[2] * NormalizationFactor;
-
-		//Derivated from fusion
-		m_FusedIMUState.m_PhysicalData.UpdateAccelerationMagnitud();
-
-		//Reset counters and accumulators
-		memset(m_FusedPhysicalData.m_Acceleration,0,sizeof(float) * 3);
-		m_CollectedFusionSamples = 0;
-	}
-
-	bool CIMUDevice::GaussianFuseCurrentState()
-	{
-		IncorporateCurrentStateGaussianFusion();
-		if (m_CollectedFusionSamples == m_SamplesPerFusion)
-		{
-			GaussianFusion();
-			return true;
-		}
-		return false;
-	}
-
-	void CIMUDevice::IncorporateCurrentStateGaussianFusion()
-	{
-		m_FusedPhysicalData.m_Acceleration[0] += m_XsensMTiFrame.m_IMUState.m_PhysicalData.m_Acceleration[0];
-		m_FusedPhysicalData.m_Acceleration[1] += m_XsensMTiFrame.m_IMUState.m_PhysicalData.m_Acceleration[1];
-		m_FusedPhysicalData.m_Acceleration[2] += m_XsensMTiFrame.m_IMUState.m_PhysicalData.m_Acceleration[2];
-
-		++m_CollectedFusionSamples;
-	}
-
-	void CIMUDevice::GaussianFusion()
-	{
-		//Execution the fusion
-		const float NormalizationFactor = 1.0f / float(m_CollectedFusionSamples);
-		m_FusedIMUState.m_PhysicalData.m_Acceleration[0] = m_FusedPhysicalData.m_Acceleration[0] * NormalizationFactor;
-		m_FusedIMUState.m_PhysicalData.m_Acceleration[1] = m_FusedPhysicalData.m_Acceleration[1] * NormalizationFactor;
-		m_FusedIMUState.m_PhysicalData.m_Acceleration[2] = m_FusedPhysicalData.m_Acceleration[2] * NormalizationFactor;
-
-		//Derivated from fusion
-		m_FusedIMUState.m_PhysicalData.UpdateAccelerationMagnitud();
-
-		//Reset counters and accumulators
-		memset(m_FusedPhysicalData.m_Acceleration,0,sizeof(float) * 3);
-		m_CollectedFusionSamples = 0;
-	}
-
-	bool CIMUDevice::IntegrateCurrentState()
-	{
-		if (m_FusionStrategy == eNoFusion)
-		{
-			return IntegrateWithOutFusion();
-		}
-		else
-		{
-			return IntegrateWithFusion();
-		}
-	}
-
-	bool CIMUDevice::IntegrateWithOutFusion()
-	{
-		return true;
-	}
-
-	bool CIMUDevice::IntegrateWithFusion()
-	{
-		return true;
-	}
-
-	bool CIMUDevice::InitializeDevice(const std::string& PortName, const SamplingFrequency Frequency)
-	{
-
-		_MINIMAL___LOCK(m_DeviceMutex)
+        _MINIMAL_UNLOCK(m_DeviceMutex)
+
+        return false;
+    }
+
+    bool CIMUDevice::MeanFuseCurrentState()
+    {
+        IncorporateCurrentStateMeanFusion();
+
+        if (m_CollectedFusionSamples == m_SamplesPerFusion)
+        {
+            MeanFusion();
+            return true;
+        }
+
+        return false;
+    }
+
+    void CIMUDevice::IncorporateCurrentStateMeanFusion()
+    {
+        m_FusedPhysicalData.m_Acceleration[0] += m_XsensMTiFrame.m_IMUState.m_PhysicalData.m_Acceleration[0];
+        m_FusedPhysicalData.m_Acceleration[1] += m_XsensMTiFrame.m_IMUState.m_PhysicalData.m_Acceleration[1];
+        m_FusedPhysicalData.m_Acceleration[2] += m_XsensMTiFrame.m_IMUState.m_PhysicalData.m_Acceleration[2];
+        ++m_CollectedFusionSamples;
+    }
+
+    void CIMUDevice::MeanFusion()
+    {
+        //Execution the fusion
+        const float NormalizationFactor = 1.0f / float(m_CollectedFusionSamples);
+        m_FusedIMUState.m_PhysicalData.m_Acceleration[0] = m_FusedPhysicalData.m_Acceleration[0] * NormalizationFactor;
+        m_FusedIMUState.m_PhysicalData.m_Acceleration[1] = m_FusedPhysicalData.m_Acceleration[1] * NormalizationFactor;
+        m_FusedIMUState.m_PhysicalData.m_Acceleration[2] = m_FusedPhysicalData.m_Acceleration[2] * NormalizationFactor;
+
+        //Derivated from fusion
+        m_FusedIMUState.m_PhysicalData.UpdateAccelerationMagnitud();
+
+        //Reset counters and accumulators
+        memset(m_FusedPhysicalData.m_Acceleration, 0, sizeof(float) * 3);
+        m_CollectedFusionSamples = 0;
+    }
+
+    bool CIMUDevice::GaussianFuseCurrentState()
+    {
+        IncorporateCurrentStateGaussianFusion();
+
+        if (m_CollectedFusionSamples == m_SamplesPerFusion)
+        {
+            GaussianFusion();
+            return true;
+        }
+
+        return false;
+    }
+
+    void CIMUDevice::IncorporateCurrentStateGaussianFusion()
+    {
+        m_FusedPhysicalData.m_Acceleration[0] += m_XsensMTiFrame.m_IMUState.m_PhysicalData.m_Acceleration[0];
+        m_FusedPhysicalData.m_Acceleration[1] += m_XsensMTiFrame.m_IMUState.m_PhysicalData.m_Acceleration[1];
+        m_FusedPhysicalData.m_Acceleration[2] += m_XsensMTiFrame.m_IMUState.m_PhysicalData.m_Acceleration[2];
+
+        ++m_CollectedFusionSamples;
+    }
+
+    void CIMUDevice::GaussianFusion()
+    {
+        //Execution the fusion
+        const float NormalizationFactor = 1.0f / float(m_CollectedFusionSamples);
+        m_FusedIMUState.m_PhysicalData.m_Acceleration[0] = m_FusedPhysicalData.m_Acceleration[0] * NormalizationFactor;
+        m_FusedIMUState.m_PhysicalData.m_Acceleration[1] = m_FusedPhysicalData.m_Acceleration[1] * NormalizationFactor;
+        m_FusedIMUState.m_PhysicalData.m_Acceleration[2] = m_FusedPhysicalData.m_Acceleration[2] * NormalizationFactor;
+
+        //Derivated from fusion
+        m_FusedIMUState.m_PhysicalData.UpdateAccelerationMagnitud();
+
+        //Reset counters and accumulators
+        memset(m_FusedPhysicalData.m_Acceleration, 0, sizeof(float) * 3);
+        m_CollectedFusionSamples = 0;
+    }
+
+    bool CIMUDevice::IntegrateCurrentState()
+    {
+        if (m_FusionStrategy == eNoFusion)
+        {
+            return IntegrateWithOutFusion();
+        }
+        else
+        {
+            return IntegrateWithFusion();
+        }
+    }
+
+    bool CIMUDevice::IntegrateWithOutFusion()
+    {
+        return true;
+    }
+
+    bool CIMUDevice::IntegrateWithFusion()
+    {
+        return true;
+    }
+
+    bool CIMUDevice::InitializeDevice(const std::string& PortName, const SamplingFrequency Frequency)
+    {
+
+        _MINIMAL___LOCK(m_DeviceMutex)
 
 #ifdef _IMU_USE_XSENS_DEVICE_
 
-		if (InitializeXsensDevice(PortName,Frequency))
-		{
-			m_SamplingFrequency = Frequency;
-			const int Cylces = 0X1C200 / int(m_SamplingFrequency);
-			m_PeriodMicroSeconds = int(round((1000000.0f * _IMU_DEVICE_DEFAUL_CHECK_PERIOD_FACTOR_) / float(Cylces)));
-			_MINIMAL_UNLOCK(m_DeviceMutex)
-			return true;
-		}
-		else
-		{
-			_MINIMAL_UNLOCK(m_DeviceMutex)
-			return false;
-		}
+        if (InitializeXsensDevice(PortName, Frequency))
+        {
+            m_SamplingFrequency = Frequency;
+            const int Cylces = 0X1C200 / int(m_SamplingFrequency);
+            m_PeriodMicroSeconds = int(round((1000000.0f * _IMU_DEVICE_DEFAUL_CHECK_PERIOD_FACTOR_) / float(Cylces)));
+            _MINIMAL_UNLOCK(m_DeviceMutex)
+            return true;
+        }
+        else
+        {
+            _MINIMAL_UNLOCK(m_DeviceMutex)
+            return false;
+        }
 
 #endif
 
-	}
+    }
 
-	void CIMUDevice::FinalizeModuleDevice()
-	{
-		Stop(true);
+    void CIMUDevice::FinalizeModuleDevice()
+    {
+        Stop(true);
 
 #ifdef _IMU_USE_XSENS_DEVICE_
 
-		FinalizeXsensModuleDevice();
+        FinalizeXsensModuleDevice();
 
 #endif
 
-		UnregisterEventDispatchers();
-
-	}
-
-	void CIMUDevice::ShouldYield()
-	{
-		const long int RemainingTime = m_PeriodMicroSeconds - CTimeStamp::GetElapsedMicroseconds(m_LastFrameTimeStamp);
-		if (RemainingTime > 0)
-			usleep(__useconds_t(RemainingTime));
-	}
-
-	bool CIMUDevice::DispatchCylcle()
-	{
-		if (LoadCurrentState())
-		{
-			SendEvent(CIMUEvent(m_LastFrameTimeStamp,CIMUEvent::eOnIMUCycle,this));
-			switch(m_FusionStrategy)
-			{
-				case eMeanFusion:
-					if (MeanFuseCurrentState())
-					{
-						SendEvent(CIMUEvent(m_LastFrameTimeStamp,CIMUEvent::eOnIMUFusedCycle,this,m_FusedIMUState));
-						if (IntegrateCurrentState())
-							SendEvent(CIMUEvent(m_LastFrameTimeStamp,CIMUEvent::eOnIMUIntegratedState,this,m_IntegratedIMUState));
-					}
-				break;
-				case eGaussianFusion:
-					if (GaussianFuseCurrentState())
-					{
-						SendEvent(CIMUEvent(m_LastFrameTimeStamp,CIMUEvent::eOnIMUIntegratedState,this,m_FusedIMUState));
-						if (IntegrateCurrentState())
-							SendEvent(CIMUEvent(m_LastFrameTimeStamp,CIMUEvent::eOnIMUIntegratedState,this,m_IntegratedIMUState));
-					}
-				break;
-				case eNoFusion:
-					if (IntegrateCurrentState())
-						SendEvent(CIMUEvent(m_LastFrameTimeStamp,CIMUEvent::eOnIMUIntegratedState,this,m_IntegratedIMUState));
-				break;
-			}
-			return true;
-		}
-		return false;
-	}
-
-	void CIMUDevice::SendEvent(const CIMUEvent& Event)
-	{
-		_MINIMAL___LOCK(m_EventDispatchersMutex)
-		const unsigned long int TotalDispatchers = m_IMUEventDispatchers.size();
-		if (TotalDispatchers)
-		{
-			if (TotalDispatchers == 1)
-				(*m_IMUEventDispatchers.begin())->ReceiveEvent(Event);
-			else
-				for(std::set<IIMUEventDispatcher*>::iterator ppIIMUEventDispatcher = m_IMUEventDispatchers.begin() ; ppIIMUEventDispatcher != m_IMUEventDispatchers.end() ; ++ppIIMUEventDispatcher)
-					(*ppIIMUEventDispatcher)->ReceiveEvent(Event);
-		}
-		_MINIMAL_UNLOCK(m_EventDispatchersMutex)
-	}
-
-	void CIMUDevice::SetReferenceTimeStamps()
-	{
-		_MINIMAL___LOCK(m_EventDispatchersMutex)
-		gettimeofday(&m_ReferenceTimeStamp,NULL);
-		gettimeofday(&m_LastFrameTimeStamp,NULL);
-		if (m_IMUEventDispatchers.size())
-			for(std::set<IIMUEventDispatcher*>::iterator ppIIMUEventDispatcher = m_IMUEventDispatchers.begin() ; ppIIMUEventDispatcher != m_IMUEventDispatchers.end() ; ++ppIIMUEventDispatcher)
-				(*ppIIMUEventDispatcher)->SetReferenceTimeStamps(m_ReferenceTimeStamp);
-		_MINIMAL_UNLOCK(m_EventDispatchersMutex)
-	}
-
-	bool CIMUDevice::SetThreadRunnigMode(const ThreadPolicyType ThreadPolicy, const float NormalizedPriority)
-	{
-		if (m_IsActive)
-		{
-			int Policy = -1;
-			struct sched_param SchedulingParameters;
-			if (pthread_getschedparam(m_pInternalThreadHandel,&Policy,&SchedulingParameters) == 0)
-			{
-				const int MaximalPriority = sched_get_priority_max(ThreadPolicy);
-				const int MinimalPriority = sched_get_priority_min(ThreadPolicy);
-				const int PriorityRange = MaximalPriority - MinimalPriority;
-				const int Priority = int(round(float(PriorityRange) * NormalizedPriority + float(MinimalPriority)));
-				SchedulingParameters.sched_priority = Priority;
-				const int Result = pthread_setschedparam(m_pInternalThreadHandel,ThreadPolicy,&SchedulingParameters);
-				switch(Result)
-				{
-					case 0:
-						return true;
-					break;
-					case EINVAL:
-						std::cerr << "[IMU Device error: SetThreadRunnigMode() returns EINVAL!]\n[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
-					break;
-					case ENOTSUP:
-						std::cerr << "[IMU Device error: SetThreadRunnigMode() returns ENOTSUP!]\n[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
-					break;
-					case EPERM:
-						std::cerr << "[IMU Device error: SetThreadRunnigMode() returns EPERM!]\n[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
-					break;
-					case ESRCH:
-						std::cerr << "[IMU Device error: SetThreadRunnigMode() returns ESRCH!]\n[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
-					break;
-				}
-			}
-			return false;
-		}
-		else
-		{
-			std::cerr << "[IMU Device error: SetThreadRunnigMode() cannot set running mode while thread is not active!]\n[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
-			return false;
-		}
-	}
-
-	void* CIMUDevice::ThreadLoop(void* pData)
-	{
-		if (pData)
-		{
-
-			CIMUDevice* pIMUDevice = (CIMUDevice*) pData;
-
-			_MINIMAL___LOCK(pIMUDevice->m_IsActiveMutex)
-			pIMUDevice->m_IsActive = true;
-			_MINIMAL_UNLOCK(pIMUDevice->m_IsActiveMutex)
-
-			pIMUDevice->SetReferenceTimeStamps();
-
-			pIMUDevice->SendEvent(CIMUEvent(CIMUEvent::eOnIMUStart,pIMUDevice));
-
-			while(pIMUDevice->m_IsActive)
-			{
-				pIMUDevice->ShouldYield();
-
-				_MINIMAL___LOCK(pIMUDevice->m_IsDispatchingMutex)
-				pIMUDevice->m_IsDispatching = true;
-
-				const bool DispatchingResult = pIMUDevice->DispatchCylcle();
-
-				pIMUDevice->m_IsDispatching = false;
-				_MINIMAL_UNLOCK(pIMUDevice->m_IsDispatchingMutex)
-
-				if (!DispatchingResult)
-				{
-					std::cerr << "[IMU Device error: DispatchCylcle() returns false!]\n[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
-					break;
-				}
-
-			}
-			if (pIMUDevice->m_IsActive)
-			{
-				_MINIMAL___LOCK(pIMUDevice->m_IsActiveMutex)
-				pIMUDevice->m_IsActive = false;
-				_MINIMAL_UNLOCK(pIMUDevice->m_IsActiveMutex)
-			}
-
-			pIMUDevice->SendEvent(CIMUEvent(CIMUEvent::eOnIMUStop,pIMUDevice));
-		}
-		return NULL;
-	}
+        UnregisterEventDispatchers();
+
+    }
+
+    void CIMUDevice::ShouldYield()
+    {
+        const long int RemainingTime = m_PeriodMicroSeconds - CTimeStamp::GetElapsedMicroseconds(m_LastFrameTimeStamp);
+
+        if (RemainingTime > 0)
+        {
+            usleep(__useconds_t(RemainingTime));
+        }
+    }
+
+    bool CIMUDevice::DispatchCylcle()
+    {
+        if (LoadCurrentState())
+        {
+            SendEvent(CIMUEvent(m_LastFrameTimeStamp, CIMUEvent::eOnIMUCycle, this));
+
+            switch (m_FusionStrategy)
+            {
+                case eMeanFusion:
+                    if (MeanFuseCurrentState())
+                    {
+                        SendEvent(CIMUEvent(m_LastFrameTimeStamp, CIMUEvent::eOnIMUFusedCycle, this, m_FusedIMUState));
+
+                        if (IntegrateCurrentState())
+                        {
+                            SendEvent(CIMUEvent(m_LastFrameTimeStamp, CIMUEvent::eOnIMUIntegratedState, this, m_IntegratedIMUState));
+                        }
+                    }
+
+                    break;
+
+                case eGaussianFusion:
+                    if (GaussianFuseCurrentState())
+                    {
+                        SendEvent(CIMUEvent(m_LastFrameTimeStamp, CIMUEvent::eOnIMUIntegratedState, this, m_FusedIMUState));
+
+                        if (IntegrateCurrentState())
+                        {
+                            SendEvent(CIMUEvent(m_LastFrameTimeStamp, CIMUEvent::eOnIMUIntegratedState, this, m_IntegratedIMUState));
+                        }
+                    }
+
+                    break;
+
+                case eNoFusion:
+                    if (IntegrateCurrentState())
+                    {
+                        SendEvent(CIMUEvent(m_LastFrameTimeStamp, CIMUEvent::eOnIMUIntegratedState, this, m_IntegratedIMUState));
+                    }
+
+                    break;
+            }
+
+            return true;
+        }
+
+        return false;
+    }
+
+    void CIMUDevice::SendEvent(const CIMUEvent& Event)
+    {
+        _MINIMAL___LOCK(m_EventDispatchersMutex)
+        const unsigned long int TotalDispatchers = m_IMUEventDispatchers.size();
+
+        if (TotalDispatchers)
+        {
+            if (TotalDispatchers == 1)
+            {
+                (*m_IMUEventDispatchers.begin())->ReceiveEvent(Event);
+            }
+            else
+                for (std::set<IIMUEventDispatcher*>::iterator ppIIMUEventDispatcher = m_IMUEventDispatchers.begin() ; ppIIMUEventDispatcher != m_IMUEventDispatchers.end() ; ++ppIIMUEventDispatcher)
+                {
+                    (*ppIIMUEventDispatcher)->ReceiveEvent(Event);
+                }
+        }
+
+        _MINIMAL_UNLOCK(m_EventDispatchersMutex)
+    }
+
+    void CIMUDevice::SetReferenceTimeStamps()
+    {
+        _MINIMAL___LOCK(m_EventDispatchersMutex)
+        gettimeofday(&m_ReferenceTimeStamp, NULL);
+        gettimeofday(&m_LastFrameTimeStamp, NULL);
+
+        if (m_IMUEventDispatchers.size())
+            for (std::set<IIMUEventDispatcher*>::iterator ppIIMUEventDispatcher = m_IMUEventDispatchers.begin() ; ppIIMUEventDispatcher != m_IMUEventDispatchers.end() ; ++ppIIMUEventDispatcher)
+            {
+                (*ppIIMUEventDispatcher)->SetReferenceTimeStamps(m_ReferenceTimeStamp);
+            }
+
+        _MINIMAL_UNLOCK(m_EventDispatchersMutex)
+    }
+
+    bool CIMUDevice::SetThreadRunnigMode(const ThreadPolicyType ThreadPolicy, const float NormalizedPriority)
+    {
+        if (m_IsActive)
+        {
+            int Policy = -1;
+            struct sched_param SchedulingParameters;
+
+            if (pthread_getschedparam(m_pInternalThreadHandel, &Policy, &SchedulingParameters) == 0)
+            {
+                const int MaximalPriority = sched_get_priority_max(ThreadPolicy);
+                const int MinimalPriority = sched_get_priority_min(ThreadPolicy);
+                const int PriorityRange = MaximalPriority - MinimalPriority;
+                const int Priority = int(round(float(PriorityRange) * NormalizedPriority + float(MinimalPriority)));
+                SchedulingParameters.sched_priority = Priority;
+                const int Result = pthread_setschedparam(m_pInternalThreadHandel, ThreadPolicy, &SchedulingParameters);
+
+                switch (Result)
+                {
+                    case 0:
+                        return true;
+                        break;
+
+                    case EINVAL:
+                        std::cerr << "[IMU Device error: SetThreadRunnigMode() returns EINVAL!]\n[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
+                        break;
+
+                    case ENOTSUP:
+                        std::cerr << "[IMU Device error: SetThreadRunnigMode() returns ENOTSUP!]\n[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
+                        break;
+
+                    case EPERM:
+                        std::cerr << "[IMU Device error: SetThreadRunnigMode() returns EPERM!]\n[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
+                        break;
+
+                    case ESRCH:
+                        std::cerr << "[IMU Device error: SetThreadRunnigMode() returns ESRCH!]\n[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
+                        break;
+                }
+            }
+
+            return false;
+        }
+        else
+        {
+            std::cerr << "[IMU Device error: SetThreadRunnigMode() cannot set running mode while thread is not active!]\n[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
+            return false;
+        }
+    }
+
+    void* CIMUDevice::ThreadLoop(void* pData)
+    {
+        if (pData)
+        {
+
+            CIMUDevice* pIMUDevice = (CIMUDevice*) pData;
+
+            _MINIMAL___LOCK(pIMUDevice->m_IsActiveMutex)
+            pIMUDevice->m_IsActive = true;
+            _MINIMAL_UNLOCK(pIMUDevice->m_IsActiveMutex)
+
+            pIMUDevice->SetReferenceTimeStamps();
+
+            pIMUDevice->SendEvent(CIMUEvent(CIMUEvent::eOnIMUStart, pIMUDevice));
+
+            while (pIMUDevice->m_IsActive)
+            {
+                pIMUDevice->ShouldYield();
+
+                _MINIMAL___LOCK(pIMUDevice->m_IsDispatchingMutex)
+                pIMUDevice->m_IsDispatching = true;
+
+                const bool DispatchingResult = pIMUDevice->DispatchCylcle();
+
+                pIMUDevice->m_IsDispatching = false;
+                _MINIMAL_UNLOCK(pIMUDevice->m_IsDispatchingMutex)
+
+                if (!DispatchingResult)
+                {
+                    std::cerr << "[IMU Device error: DispatchCylcle() returns false!]\n[Source location: " << __FILE__ << ":" << __LINE__ << "]" << std::endl;
+                    break;
+                }
+
+            }
+
+            if (pIMUDevice->m_IsActive)
+            {
+                _MINIMAL___LOCK(pIMUDevice->m_IsActiveMutex)
+                pIMUDevice->m_IsActive = false;
+                _MINIMAL_UNLOCK(pIMUDevice->m_IsActiveMutex)
+            }
+
+            pIMUDevice->SendEvent(CIMUEvent(CIMUEvent::eOnIMUStop, pIMUDevice));
+        }
+
+        return NULL;
+    }
 }
diff --git a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUDevice.h b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUDevice.h
old mode 100755
new mode 100644
index ff37a7d3d9de28038ca765cf83eebf03b5ef9be8..0eccbad7e60cea8d40ccc3559dd83bd22b31eed1
--- a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUDevice.h
+++ b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUDevice.h
@@ -3,7 +3,7 @@
  *
  *  Created on: Mar 16, 2014
  *      Author: Dr.-Ing. David Israel González Aguirre
- *      Mail:	david.gonzalez@kit.edu
+ *      Mail:   david.gonzalez@kit.edu
  */
 
 #ifndef IMUDEVICE_H_
@@ -28,192 +28,192 @@
 
 namespace IMU
 {
-	//Forward definition
-	class IIMUEventDispatcher;
-
-	/*!
-	 \class CIMUDevice
-	 \ingroup IMU
-	 \brief This class contains the the devices module and the thread for read the measurements.
-
-	 CIMUDevice encapsulates the device details for the rest of the library and applications.
-	 This also includes a thread which is in charge of generate the IMU events
-	 */
-	class CIMUDevice
-	{
-		public:
-
-			/*!
-			 \brief Enum specifying the running thread policy.
-			 */
-			enum ThreadPolicyType
-			{
-				eRealTime = SCHED_FIFO, eRoundRobinPriorityBased = SCHED_RR, eBatch = SCHED_BATCH, eIdle = SCHED_IDLE
-			};
-
-			/*!
-			 \brief Enum specifying the supported sampling frequencies.
-			 */
-			enum SamplingFrequency
-			{
-				eSamplingFrequency_10HZ = 0x2D00,
-				eSamplingFrequency_12HZ = 0x2580,
-				eSamplingFrequency_15HZ = 0x1E00,
-				eSamplingFrequency_16HZ = 0x1C20,
-				eSamplingFrequency_18HZ = 0x1900,
-				eSamplingFrequency_20HZ = 0x1680,
-				eSamplingFrequency_24HZ = 0x12C0,
-				eSamplingFrequency_25HZ = 0x1200,
-				eSamplingFrequency_30HZ = 0x0F00,
-				eSamplingFrequency_32HZ = 0x0E10,
-				eSamplingFrequency_36HZ = 0x0C80,
-				eSamplingFrequency_40HZ = 0x0B40,
-				eSamplingFrequency_45HZ = 0x0A00,
-				eSamplingFrequency_48HZ = 0x0960,
-				eSamplingFrequency_50HZ = 0x0900,
-				eSamplingFrequency_60HZ = 0x0780,
-				eSamplingFrequency_64HZ = 0x0708,
-				eSamplingFrequency_72HZ = 0x0640,
-				eSamplingFrequency_75HZ = 0x0600,
-				eSamplingFrequency_80HZ = 0x05A0,
-				eSamplingFrequency_90HZ = 0x0500,
-				eSamplingFrequency_96HZ = 0x04B0,
-				eSamplingFrequency_100HZ = 0x0480,
-				eSamplingFrequency_120HZ = 0x03C0,
-				eSamplingFrequency_128HZ = 0x0384,
-				eSamplingFrequency_144HZ = 0x0320,
-				eSamplingFrequency_150HZ = 0x0300,
-				eSamplingFrequency_160HZ = 0x02D0,
-				eSamplingFrequency_180HZ = 0x0280,
-				eSamplingFrequency_192HZ = 0x0258,
-				eSamplingFrequency_200HZ = 0x0240,
-				eSamplingFrequency_225HZ = 0x0200,
-				eSamplingFrequency_240HZ = 0x01E0,
-				eSamplingFrequency_256HZ = 0x01C2,
-				eSamplingFrequency_288HZ = 0x0190,
-				eSamplingFrequency_300HZ = 0x0180,
-				eSamplingFrequency_320HZ = 0x0168,
-				eSamplingFrequency_360HZ = 0x0140,
-				eSamplingFrequency_384HZ = 0x012C,
-				eSamplingFrequency_400HZ = 0x0120,
-				eSamplingFrequency_450HZ = 0x0100,
-				eSamplingFrequency_480HZ = 0x00F0,
-				eSamplingFrequency_512HZ = 0x00E1
-			};
-
-			enum FusionStrategy
-			{
-				eNoFusion, eMeanFusion, eGaussianFusion
-			};
-
-			/*!
-			 \brief The default constructor.
-			 The default constructor sets all member variables to zero, i.e. after construction no valid device nor thread are represented.
-			 */
-			CIMUDevice();
-
-			/*!
-			 \brief The destructor.
-			 */
-			virtual ~CIMUDevice();
-
-			uint64_t GetDeviceId() const;
-
-			inline IMUState GetIMUState() const
-			{
+    //Forward definition
+    class IIMUEventDispatcher;
+
+    /*!
+     \class CIMUDevice
+     \ingroup IMU
+     \brief This class contains the the devices module and the thread for read the measurements.
+
+     CIMUDevice encapsulates the device details for the rest of the library and applications.
+     This also includes a thread which is in charge of generate the IMU events
+     */
+    class CIMUDevice
+    {
+    public:
+
+        /*!
+         \brief Enum specifying the running thread policy.
+         */
+        enum ThreadPolicyType
+        {
+            eRealTime = SCHED_FIFO, eRoundRobinPriorityBased = SCHED_RR, eBatch = SCHED_BATCH, eIdle = SCHED_IDLE
+        };
+
+        /*!
+         \brief Enum specifying the supported sampling frequencies.
+         */
+        enum SamplingFrequency
+        {
+            eSamplingFrequency_10HZ = 0x2D00,
+            eSamplingFrequency_12HZ = 0x2580,
+            eSamplingFrequency_15HZ = 0x1E00,
+            eSamplingFrequency_16HZ = 0x1C20,
+            eSamplingFrequency_18HZ = 0x1900,
+            eSamplingFrequency_20HZ = 0x1680,
+            eSamplingFrequency_24HZ = 0x12C0,
+            eSamplingFrequency_25HZ = 0x1200,
+            eSamplingFrequency_30HZ = 0x0F00,
+            eSamplingFrequency_32HZ = 0x0E10,
+            eSamplingFrequency_36HZ = 0x0C80,
+            eSamplingFrequency_40HZ = 0x0B40,
+            eSamplingFrequency_45HZ = 0x0A00,
+            eSamplingFrequency_48HZ = 0x0960,
+            eSamplingFrequency_50HZ = 0x0900,
+            eSamplingFrequency_60HZ = 0x0780,
+            eSamplingFrequency_64HZ = 0x0708,
+            eSamplingFrequency_72HZ = 0x0640,
+            eSamplingFrequency_75HZ = 0x0600,
+            eSamplingFrequency_80HZ = 0x05A0,
+            eSamplingFrequency_90HZ = 0x0500,
+            eSamplingFrequency_96HZ = 0x04B0,
+            eSamplingFrequency_100HZ = 0x0480,
+            eSamplingFrequency_120HZ = 0x03C0,
+            eSamplingFrequency_128HZ = 0x0384,
+            eSamplingFrequency_144HZ = 0x0320,
+            eSamplingFrequency_150HZ = 0x0300,
+            eSamplingFrequency_160HZ = 0x02D0,
+            eSamplingFrequency_180HZ = 0x0280,
+            eSamplingFrequency_192HZ = 0x0258,
+            eSamplingFrequency_200HZ = 0x0240,
+            eSamplingFrequency_225HZ = 0x0200,
+            eSamplingFrequency_240HZ = 0x01E0,
+            eSamplingFrequency_256HZ = 0x01C2,
+            eSamplingFrequency_288HZ = 0x0190,
+            eSamplingFrequency_300HZ = 0x0180,
+            eSamplingFrequency_320HZ = 0x0168,
+            eSamplingFrequency_360HZ = 0x0140,
+            eSamplingFrequency_384HZ = 0x012C,
+            eSamplingFrequency_400HZ = 0x0120,
+            eSamplingFrequency_450HZ = 0x0100,
+            eSamplingFrequency_480HZ = 0x00F0,
+            eSamplingFrequency_512HZ = 0x00E1
+        };
+
+        enum FusionStrategy
+        {
+            eNoFusion, eMeanFusion, eGaussianFusion
+        };
+
+        /*!
+         \brief The default constructor.
+         The default constructor sets all member variables to zero, i.e. after construction no valid device nor thread are represented.
+         */
+        CIMUDevice();
+
+        /*!
+         \brief The destructor.
+         */
+        virtual ~CIMUDevice();
+
+        uint64_t GetDeviceId() const;
+
+        inline IMUState GetIMUState() const
+        {
 
 #ifdef _IMU_USE_XSENS_DEVICE_
 
-				return m_XsensMTiFrame.m_IMUState;
+            return m_XsensMTiFrame.m_IMUState;
 
 #endif
 
-			}
+        }
 
-			bool Connect(const std::string& PortName, const SamplingFrequency Frequency);
+        bool Connect(const std::string& PortName, const SamplingFrequency Frequency);
 
-			bool Start(const bool Blocking = true);
+        bool Start(const bool Blocking = true);
 
-			bool SetThreadRunnigMode(const ThreadPolicyType ThreadPolicy, const float NormalizedPriority);
+        bool SetThreadRunnigMode(const ThreadPolicyType ThreadPolicy, const float NormalizedPriority);
 
-			void Stop(const bool Blocking = true);
+        void Stop(const bool Blocking = true);
 
-			bool SetFusion(const FusionStrategy Strategy, const ushort SamplesPerFusion);
+        bool SetFusion(const FusionStrategy Strategy, const ushort SamplesPerFusion);
 
-			bool IsActive() const;
+        bool IsActive() const;
 
-			bool RegisterEventDispatcher(IIMUEventDispatcher* pIMUEventDispatcher);
+        bool RegisterEventDispatcher(IIMUEventDispatcher* pIMUEventDispatcher);
 
-			bool UnregisterEventDispatcher(IIMUEventDispatcher* pIMUEventDispatcher);
+        bool UnregisterEventDispatcher(IIMUEventDispatcher* pIMUEventDispatcher);
 
-			inline const timeval& GetReferenceTimeStamp() const
-			{
-				return m_ReferenceTimeStamp;
-			}
+        inline const timeval& GetReferenceTimeStamp() const
+        {
+            return m_ReferenceTimeStamp;
+        }
 
-		protected:
+    protected:
 
-			bool LoadCurrentState();
+        bool LoadCurrentState();
 
-			bool MeanFuseCurrentState();
-			void IncorporateCurrentStateMeanFusion();
-			void MeanFusion();
+        bool MeanFuseCurrentState();
+        void IncorporateCurrentStateMeanFusion();
+        void MeanFusion();
 
-			bool GaussianFuseCurrentState();
-			void IncorporateCurrentStateGaussianFusion();
-			void GaussianFusion();
+        bool GaussianFuseCurrentState();
+        void IncorporateCurrentStateGaussianFusion();
+        void GaussianFusion();
 
-			bool IntegrateCurrentState();
-			bool IntegrateWithOutFusion();
-			bool IntegrateWithFusion();
+        bool IntegrateCurrentState();
+        bool IntegrateWithOutFusion();
+        bool IntegrateWithFusion();
 
-		private:
+    private:
 
-			void UnregisterEventDispatchers();
+        void UnregisterEventDispatchers();
 
-			bool InitializeDevice(const std::string& PortName, const SamplingFrequency Frequency);
-			void FinalizeModuleDevice();
-			void ShouldYield();
-			bool DispatchCylcle();
-			void SendEvent(const CIMUEvent& Event);
-			void SetReferenceTimeStamps();
+        bool InitializeDevice(const std::string& PortName, const SamplingFrequency Frequency);
+        void FinalizeModuleDevice();
+        void ShouldYield();
+        bool DispatchCylcle();
+        void SendEvent(const CIMUEvent& Event);
+        void SetReferenceTimeStamps();
 
-			static void* ThreadLoop(void* pData);
+        static void* ThreadLoop(void* pData);
 
-			uint64_t m_DeviceId;
-			SamplingFrequency m_SamplingFrequency;
-			int m_PeriodMicroSeconds;
-			FusionStrategy m_FusionStrategy;
-			int m_SamplesPerFusion;
-			int m_CollectedFusionSamples;
-			volatile bool m_IsActive;
-			volatile bool m_IsDispatching;
-			bool m_IsInitialized;
-			pthread_t m_pInternalThreadHandel;
-			pthread_mutex_t m_IsActiveMutex;
-			pthread_mutex_t m_IsDispatchingMutex;
-			pthread_mutex_t m_EventDispatchersMutex;
-			pthread_mutex_t m_DeviceMutex;
-			std::set<IIMUEventDispatcher*> m_IMUEventDispatchers;
-			timeval m_ReferenceTimeStamp;
-			timeval m_LastFrameTimeStamp;
+        uint64_t m_DeviceId;
+        SamplingFrequency m_SamplingFrequency;
+        int m_PeriodMicroSeconds;
+        FusionStrategy m_FusionStrategy;
+        int m_SamplesPerFusion;
+        int m_CollectedFusionSamples;
+        volatile bool m_IsActive;
+        volatile bool m_IsDispatching;
+        bool m_IsInitialized;
+        pthread_t m_pInternalThreadHandel;
+        pthread_mutex_t m_IsActiveMutex;
+        pthread_mutex_t m_IsDispatchingMutex;
+        pthread_mutex_t m_EventDispatchersMutex;
+        pthread_mutex_t m_DeviceMutex;
+        std::set<IIMUEventDispatcher*> m_IMUEventDispatchers;
+        timeval m_ReferenceTimeStamp;
+        timeval m_LastFrameTimeStamp;
 
-			IMUState::PhysicalData m_FusedPhysicalData;
-			IMUState m_FusedIMUState;
-			IMUState m_IntegratedIMUState;
+        IMUState::PhysicalData m_FusedPhysicalData;
+        IMUState m_FusedIMUState;
+        IMUState m_IntegratedIMUState;
 
 #ifdef _IMU_USE_XSENS_DEVICE_
 
-			bool InitializeXsensDevice(const std::string& PortName, const SamplingFrequency Frequency);
-			void FinalizeXsensModuleDevice();
-			void DestroyXsensModuleDevice();
+        bool InitializeXsensDevice(const std::string& PortName, const SamplingFrequency Frequency);
+        void FinalizeXsensModuleDevice();
+        void DestroyXsensModuleDevice();
 
-			Xsens::CXsensMTiModule* m_pXsensMTiModule;
-			Xsens::XsensMTiFrame m_XsensMTiFrame;
+        Xsens::CXsensMTiModule* m_pXsensMTiModule;
+        Xsens::XsensMTiFrame m_XsensMTiFrame;
 
 #endif
 
-	};
+    };
 }
 
 #endif
diff --git a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUEvent.cpp b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUEvent.cpp
old mode 100755
new mode 100644
index 5a2aaef79521e8e7b64fd464b73287cf8b6f8a2d..c2a97a2091b8070061c0c173551b00e1501b6e17
--- a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUEvent.cpp
+++ b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUEvent.cpp
@@ -2,8 +2,8 @@
  * IMUEvent.cpp
  *
  *  Created on: Mar 16, 2014
- *     Author:	Dr.-Ing. David Israel González Aguirre
- *      Mail:	david.gonzalez@kit.edu
+ *     Author:  Dr.-Ing. David Israel González Aguirre
+ *      Mail:   david.gonzalez@kit.edu
  */
 
 #include "IMUEvent.h"
@@ -11,44 +11,44 @@
 
 namespace IMU
 {
-	uint32_t CIMUEvent::s_IdCounter = 0;
-	pthread_mutex_t CIMUEvent::s_IdCounterMutex = PTHREAD_MUTEX_INITIALIZER;
-
-	CIMUEvent::CIMUEvent(const timeval& TimeStamp, const EventType EventType, const CIMUDevice* pIMUDevice, const IMUState& EventState) :
-	m_Id(CreatId()) ,
-m_TimeStamp	(TimeStamp), m_EventType(EventType), m_pIMUDevice(pIMUDevice), m_IMUState(EventState)
-	{
-	}
-
-	CIMUEvent::CIMUEvent(const timeval& TimeStamp, const EventType EventType, const CIMUDevice* pIMUDevice) :
-			m_Id(CreatId()), m_TimeStamp(TimeStamp), m_EventType(EventType), m_pIMUDevice(pIMUDevice), m_IMUState(pIMUDevice->GetIMUState())
-	{
-	}
-
-	CIMUEvent::CIMUEvent(const EventType EventType, const CIMUDevice* pIMUDevice) :
-			m_Id(CreatId()), m_TimeStamp(CTimeStamp::GetCurrentTimeStamp()), m_EventType(EventType), m_pIMUDevice(pIMUDevice), m_IMUState(pIMUDevice->GetIMUState())
-	{
-	}
-
-	CIMUEvent::CIMUEvent(const CIMUEvent& Event) :
-			m_Id(CreatId()), m_TimeStamp(Event.m_TimeStamp), m_EventType(Event.m_EventType), m_pIMUDevice(Event.m_pIMUDevice), m_IMUState(Event.m_IMUState)
-	{
-	}
-
-	CIMUEvent::CIMUEvent() :
-			m_Id(CreatId()), m_TimeStamp(CTimeStamp::s_Zero), m_EventType(EventType(0x0)), m_pIMUDevice(NULL), m_IMUState()
-	{
-	}
-
-	CIMUEvent::~CIMUEvent()
-	{
-	}
-
-	uint32_t CIMUEvent::CreatId()
-	{
-		pthread_mutex_lock(&s_IdCounterMutex);
-		uint32_t Id = CIMUEvent::s_IdCounter++;
-		pthread_mutex_unlock(&s_IdCounterMutex);
-		return Id;
-	}
+    uint32_t CIMUEvent::s_IdCounter = 0;
+    pthread_mutex_t CIMUEvent::s_IdCounterMutex = PTHREAD_MUTEX_INITIALIZER;
+
+    CIMUEvent::CIMUEvent(const timeval& TimeStamp, const EventType EventType, const CIMUDevice* pIMUDevice, const IMUState& EventState) :
+        m_Id(CreatId()) ,
+        m_TimeStamp(TimeStamp), m_EventType(EventType), m_pIMUDevice(pIMUDevice), m_IMUState(EventState)
+    {
+    }
+
+    CIMUEvent::CIMUEvent(const timeval& TimeStamp, const EventType EventType, const CIMUDevice* pIMUDevice) :
+        m_Id(CreatId()), m_TimeStamp(TimeStamp), m_EventType(EventType), m_pIMUDevice(pIMUDevice), m_IMUState(pIMUDevice->GetIMUState())
+    {
+    }
+
+    CIMUEvent::CIMUEvent(const EventType EventType, const CIMUDevice* pIMUDevice) :
+        m_Id(CreatId()), m_TimeStamp(CTimeStamp::GetCurrentTimeStamp()), m_EventType(EventType), m_pIMUDevice(pIMUDevice), m_IMUState(pIMUDevice->GetIMUState())
+    {
+    }
+
+    CIMUEvent::CIMUEvent(const CIMUEvent& Event) :
+        m_Id(CreatId()), m_TimeStamp(Event.m_TimeStamp), m_EventType(Event.m_EventType), m_pIMUDevice(Event.m_pIMUDevice), m_IMUState(Event.m_IMUState)
+    {
+    }
+
+    CIMUEvent::CIMUEvent() :
+        m_Id(CreatId()), m_TimeStamp(CTimeStamp::s_Zero), m_EventType(EventType(0x0)), m_pIMUDevice(NULL), m_IMUState()
+    {
+    }
+
+    CIMUEvent::~CIMUEvent()
+    {
+    }
+
+    uint32_t CIMUEvent::CreatId()
+    {
+        pthread_mutex_lock(&s_IdCounterMutex);
+        uint32_t Id = CIMUEvent::s_IdCounter++;
+        pthread_mutex_unlock(&s_IdCounterMutex);
+        return Id;
+    }
 }
diff --git a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUEvent.h b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUEvent.h
old mode 100755
new mode 100644
index f10f4755e27fd2a4c51ad2f38cf5241491877cd2..b342fb84fd69801ae8d3e477673a079185e42564
--- a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUEvent.h
+++ b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUEvent.h
@@ -3,7 +3,7 @@
  *
  *  Created on: Mar 16, 2014
  *      Author: Dr.-Ing. David Israel González Aguirre
- *      Mail:	david.gonzalez@kit.edu
+ *      Mail:   david.gonzalez@kit.edu
  */
 
 #ifndef IMUEVENT_H_
@@ -14,58 +14,58 @@
 
 namespace IMU
 {
-	class CIMUDevice;
-	class CIMUEvent
-	{
-		public:
+    class CIMUDevice;
+    class CIMUEvent
+    {
+    public:
 
-			enum EventType
-			{
-				eOnIMUStart = 0X0001, eOnIMUStop = 0X0002, eOnIMUCycle = 0X0004, eOnIMUFusedCycle = 0X0008, eOnIMUIntegratedState = 0X0010, eOnIMUCustomEvent = 0X8000
-			};
+        enum EventType
+        {
+            eOnIMUStart = 0X0001, eOnIMUStop = 0X0002, eOnIMUCycle = 0X0004, eOnIMUFusedCycle = 0X0008, eOnIMUIntegratedState = 0X0010, eOnIMUCustomEvent = 0X8000
+        };
 
-			CIMUEvent(const timeval& TimeStamp, const EventType EventType, const CIMUDevice* pIMUDevice, const IMUState& EventState);
-			CIMUEvent(const timeval& TimeStamp, const EventType EventType, const CIMUDevice* pIMUDevice);
-			CIMUEvent(const EventType EventType, const CIMUDevice* pIMUDevice);
-			CIMUEvent(const CIMUEvent& Event);
-			CIMUEvent();
+        CIMUEvent(const timeval& TimeStamp, const EventType EventType, const CIMUDevice* pIMUDevice, const IMUState& EventState);
+        CIMUEvent(const timeval& TimeStamp, const EventType EventType, const CIMUDevice* pIMUDevice);
+        CIMUEvent(const EventType EventType, const CIMUDevice* pIMUDevice);
+        CIMUEvent(const CIMUEvent& Event);
+        CIMUEvent();
 
-			virtual ~CIMUEvent();
+        virtual ~CIMUEvent();
 
-			inline uint32_t GetId() const
-			{
-				return m_Id;
-			}
+        inline uint32_t GetId() const
+        {
+            return m_Id;
+        }
 
-			inline EventType GetEventType() const
-			{
-				return m_EventType;
-			}
+        inline EventType GetEventType() const
+        {
+            return m_EventType;
+        }
 
-			inline const CIMUDevice* GetIMU() const
-			{
-				return m_pIMUDevice;
-			}
+        inline const CIMUDevice* GetIMU() const
+        {
+            return m_pIMUDevice;
+        }
 
-			inline const timeval& GetTimeStamp() const
-			{
-				return m_TimeStamp;
-			}
+        inline const timeval& GetTimeStamp() const
+        {
+            return m_TimeStamp;
+        }
 
-		protected:
+    protected:
 
-			uint32_t m_Id;
-			const timeval m_TimeStamp;
-			const EventType m_EventType;
-			const CIMUDevice* m_pIMUDevice;
-			const IMUState m_IMUState;
+        uint32_t m_Id;
+        const timeval m_TimeStamp;
+        const EventType m_EventType;
+        const CIMUDevice* m_pIMUDevice;
+        const IMUState m_IMUState;
 
-		private:
+    private:
 
-			static uint32_t CreatId();
-			static uint32_t s_IdCounter;
-			static pthread_mutex_t s_IdCounterMutex;
-	};
+        static uint32_t CreatId();
+        static uint32_t s_IdCounter;
+        static pthread_mutex_t s_IdCounterMutex;
+    };
 }
 
 #endif
diff --git a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUHelpers.cpp b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUHelpers.cpp
old mode 100755
new mode 100644
index 1ceeff59f0115005639a78973fd904217fe2fa6e..c787ddfaf1de4cb788cd85a20e73c297fd986032
--- a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUHelpers.cpp
+++ b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUHelpers.cpp
@@ -3,16 +3,16 @@
  *
  *  Created on: Mar 16, 2014
  *      Author: Dr.-Ing. David Israel González Aguirre
- *      Mail:	david.gonzalez@kit.edu
+ *      Mail:   david.gonzalez@kit.edu
  */
 
 #include "IMUHelpers.h"
 
 namespace IMU
 {
-	const timeval CTimeStamp::s_Zero = { 0 , 0 };
+    const timeval CTimeStamp::s_Zero = { 0 , 0 };
 
-	const float CGeolocationInformation::s_G_LPoles = 9.832f;
-	const float CGeolocationInformation::s_G_L45 = 9.806f;
-	const float CGeolocationInformation::s_G_LEquator = 9.780f;
+    const float CGeolocationInformation::s_G_LPoles = 9.832f;
+    const float CGeolocationInformation::s_G_L45 = 9.806f;
+    const float CGeolocationInformation::s_G_LEquator = 9.780f;
 }
diff --git a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUHelpers.h b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUHelpers.h
old mode 100755
new mode 100644
index 82632ec54165d23e5ba09d15a1a7afa718e0dcf6..8e5dd202c1836cef6068fd9be94e6faf27004e79
--- a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUHelpers.h
+++ b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUHelpers.h
@@ -3,7 +3,7 @@
  *
  *  Created on: Mar 17, 2014
  *      Author: Dr.-Ing. David Israel González Aguirre
- *      Mail:	david.gonzalez@kit.edu
+ *      Mail:   david.gonzalez@kit.edu
  */
 
 #ifndef IMUHELPERS_H_
@@ -16,59 +16,59 @@
 
 namespace IMU
 {
-	class CTimeStamp
-	{
-		public:
-
-			inline static timeval GetCurrentTimeStamp()
-			{
-				timeval TimeStamp;
-				gettimeofday(&TimeStamp,NULL);
-				return TimeStamp;
-			}
-
-			inline static float GetElapsedSeconds(const timeval& Post, const timeval& Pre)
-			{
-				return float(double(GetElapsedMicroseconds(Post,Pre)) / 1000000.0);
-			}
-
-			inline static float GetElapsedMilliseconds(const timeval& Post, const timeval& Pre)
-			{
-				return float(double(GetElapsedMicroseconds(Post,Pre)) / 1000.0);
-			}
-
-			inline static long GetElapsedMicroseconds(const timeval& Post, const timeval& Pre)
-			{
-				return ((Post.tv_sec - Pre.tv_sec) * 1000000) + (Post.tv_usec - Pre.tv_usec);
-			}
-
-			inline static long GetElapsedMicroseconds(const timeval& Pre)
-			{
-				timeval Post;
-				gettimeofday(&Post,NULL);
-				return ((Post.tv_sec - Pre.tv_sec) * 1000000) + (Post.tv_usec - Pre.tv_usec);
-			}
-
-			static const timeval s_Zero;
-	};
-
-	class CGeolocationInformation
-	{
-		public:
-
-			static const float s_G_LPoles;
-			static const float s_G_L45;
-			static const float s_G_LEquator;
-
-			//LatitudeInDegrees of your location:
-			//http://www.mapsofworld.com/lat_long/germany-lat-long.html
-			//49.0167 Karlsruhe, Germany
-
-			static float GetGravitationalAcceleration(const float LatitudeInDegrees = 49.0167f)
-			{
-				return s_G_L45 - (s_G_LPoles - s_G_LEquator) * std::cos((float(M_PI) / 90.0f) * LatitudeInDegrees);
-			}
-	};
+    class CTimeStamp
+    {
+    public:
+
+        inline static timeval GetCurrentTimeStamp()
+        {
+            timeval TimeStamp;
+            gettimeofday(&TimeStamp, NULL);
+            return TimeStamp;
+        }
+
+        inline static float GetElapsedSeconds(const timeval& Post, const timeval& Pre)
+        {
+            return float(double(GetElapsedMicroseconds(Post, Pre)) / 1000000.0);
+        }
+
+        inline static float GetElapsedMilliseconds(const timeval& Post, const timeval& Pre)
+        {
+            return float(double(GetElapsedMicroseconds(Post, Pre)) / 1000.0);
+        }
+
+        inline static long GetElapsedMicroseconds(const timeval& Post, const timeval& Pre)
+        {
+            return ((Post.tv_sec - Pre.tv_sec) * 1000000) + (Post.tv_usec - Pre.tv_usec);
+        }
+
+        inline static long GetElapsedMicroseconds(const timeval& Pre)
+        {
+            timeval Post;
+            gettimeofday(&Post, NULL);
+            return ((Post.tv_sec - Pre.tv_sec) * 1000000) + (Post.tv_usec - Pre.tv_usec);
+        }
+
+        static const timeval s_Zero;
+    };
+
+    class CGeolocationInformation
+    {
+    public:
+
+        static const float s_G_LPoles;
+        static const float s_G_L45;
+        static const float s_G_LEquator;
+
+        //LatitudeInDegrees of your location:
+        //http://www.mapsofworld.com/lat_long/germany-lat-long.html
+        //49.0167 Karlsruhe, Germany
+
+        static float GetGravitationalAcceleration(const float LatitudeInDegrees = 49.0167f)
+        {
+            return s_G_L45 - (s_G_LPoles - s_G_LEquator) * std::cos((float(M_PI) / 90.0f) * LatitudeInDegrees);
+        }
+    };
 
 
 
diff --git a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUState.cpp b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUState.cpp
old mode 100755
new mode 100644
index cde825c3c17e262d80f8721531370f053dde7756..b578fc2b661c2d7d05250c624628c29ccaf09676
--- a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUState.cpp
+++ b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUState.cpp
@@ -3,7 +3,7 @@
  *
  *  Created on: Mar 16, 2014
  *      Author: Dr.-Ing. David Israel González Aguirre
- *      Mail:	david.gonzalez@kit.edu
+ *      Mail:   david.gonzalez@kit.edu
  */
 
 #include "IMUState.h"
diff --git a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUState.h b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUState.h
old mode 100755
new mode 100644
index 7f8fe38c447973993230c921c48176059bc70fe0..f1f3df1c3d0100b2f190feb4a09fd5cc03187c94
--- a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUState.h
+++ b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/IMUState.h
@@ -3,7 +3,7 @@
  *
  *  Created on: Mar 16, 2014
  *      Author: Dr.-Ing. David Israel González Aguirre
- *      Mail:	david.gonzalez@kit.edu
+ *      Mail:   david.gonzalez@kit.edu
  */
 
 #ifndef IMUSTATE_H_
@@ -13,54 +13,54 @@
 
 namespace IMU
 {
-	struct IMUState
-	{
-			inline IMUState() :
-					m_ControlData(), m_PhysicalData()
-			{
-			}
+    struct IMUState
+    {
+        inline IMUState() :
+            m_ControlData(), m_PhysicalData()
+        {
+        }
 
-			struct ControlData
-			{
-					ControlData() :
-							m_PreviousSampleCount(-1), m_CurrentSampleCount(0), m_MessageCounter(0), m_IsConsecutive(false)
-					{
-						memset(&m_TimeStamp,0,sizeof(timeval));
-					}
+        struct ControlData
+        {
+            ControlData() :
+                m_PreviousSampleCount(-1), m_CurrentSampleCount(0), m_MessageCounter(0), m_IsConsecutive(false)
+            {
+                memset(&m_TimeStamp, 0, sizeof(timeval));
+            }
 
-					long m_PreviousSampleCount;
-					unsigned short m_CurrentSampleCount;
-					long m_MessageCounter;
-					bool m_IsConsecutive;
-					timeval m_TimeStamp;
-			};
+            long m_PreviousSampleCount;
+            unsigned short m_CurrentSampleCount;
+            long m_MessageCounter;
+            bool m_IsConsecutive;
+            timeval m_TimeStamp;
+        };
 
-			struct PhysicalData
-			{
-					PhysicalData() :
-							m_AccelerationMagnitud(0.0f)
-					{
-						memset(m_Acceleration,0,sizeof(float) * 3);
-						memset(m_GyroscopeRotation,0,sizeof(float) * 3);
-						memset(m_MagneticRotation,0,sizeof(float) * 3);
-						memset(m_QuaternionRotation,0,sizeof(float) * 4);
-					}
+        struct PhysicalData
+        {
+            PhysicalData() :
+                m_AccelerationMagnitud(0.0f)
+            {
+                memset(m_Acceleration, 0, sizeof(float) * 3);
+                memset(m_GyroscopeRotation, 0, sizeof(float) * 3);
+                memset(m_MagneticRotation, 0, sizeof(float) * 3);
+                memset(m_QuaternionRotation, 0, sizeof(float) * 4);
+            }
 
-					float m_Acceleration[3];
-					float m_AccelerationMagnitud;
-					float m_GyroscopeRotation[3];
-					float m_MagneticRotation[3];
-					float m_QuaternionRotation[4];
+            float m_Acceleration[3];
+            float m_AccelerationMagnitud;
+            float m_GyroscopeRotation[3];
+            float m_MagneticRotation[3];
+            float m_QuaternionRotation[4];
 
-					inline void UpdateAccelerationMagnitud()
-					{
-						m_AccelerationMagnitud = std::sqrt(m_Acceleration[0] * m_Acceleration[0] + m_Acceleration[1] * m_Acceleration[1] + m_Acceleration[2] * m_Acceleration[2]);
-					}
-			};
+            inline void UpdateAccelerationMagnitud()
+            {
+                m_AccelerationMagnitud = std::sqrt(m_Acceleration[0] * m_Acceleration[0] + m_Acceleration[1] * m_Acceleration[1] + m_Acceleration[2] * m_Acceleration[2]);
+            }
+        };
 
-			ControlData m_ControlData;
-			PhysicalData m_PhysicalData;
-	};
+        ControlData m_ControlData;
+        PhysicalData m_PhysicalData;
+    };
 }
 
 #endif
diff --git a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/Includes.h b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/Includes.h
old mode 100755
new mode 100644
index 958dea63913562559ba9b810d6febc65e88be338..364db5615867220318bb2195ed6df24e8ac86923
--- a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/Includes.h
+++ b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/Includes.h
@@ -2,8 +2,8 @@
  * Includes.h
  *
  *  Created on: Mar 17, 2014
- *		Author: Dr.-Ing. David Israel González Aguirre
- *		Mail:	david.gonzalez@kit.edu
+ *      Author: Dr.-Ing. David Israel González Aguirre
+ *      Mail:   david.gonzalez@kit.edu
  */
 
 #ifndef INCLUDES_H_
diff --git a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/Xsens/Xsens.h b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/Xsens/Xsens.h
old mode 100755
new mode 100644
index f52c895894940c56b40fdf50c5d4d70a34bbc9ca..3f7c4fe033b81dea8242dab459a91e0c59d5315a
--- a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/Xsens/Xsens.h
+++ b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/Xsens/Xsens.h
@@ -17,21 +17,21 @@
 
 namespace IMU
 {
-	namespace Xsens
-	{
-		struct XsensMTiFrame
-		{
-				XsensMTiFrame() :
-						m_DataLength(0)
-				{
-					memset(m_Data,0,sizeof(unsigned char) * MAXMSGLEN);
-				}
-
-				short m_DataLength;
-				unsigned char m_Data[MAXMSGLEN ];
-				IMUState m_IMUState;
-		};
-	}
+    namespace Xsens
+    {
+        struct XsensMTiFrame
+        {
+            XsensMTiFrame() :
+                m_DataLength(0)
+            {
+                memset(m_Data, 0, sizeof(unsigned char) * MAXMSGLEN);
+            }
+
+            short m_DataLength;
+            unsigned char m_Data[MAXMSGLEN ];
+            IMUState m_IMUState;
+        };
+    }
 }
 
 #endif
diff --git a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/Xsens/XsensMTiModule.cpp b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/Xsens/XsensMTiModule.cpp
old mode 100755
new mode 100644
index 389219d7aa4fd18cf340e366e42e32359b5a4275..cad622231046e90bb58b19abb4bbd23c712670f7
--- a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/Xsens/XsensMTiModule.cpp
+++ b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/Xsens/XsensMTiModule.cpp
@@ -29,14 +29,14 @@
 //
 // v1.2.0
 // 27-02-2006 - Renamed Xbus class to Motion Tracker C++ Communication class, short MTComm
-//			  - Defines XBRV_* accordingly renamed to MTRV_*
-//			  - Fixed device length not correct for bid 0 when using Xbus Master and setDeviceMode function
+//            - Defines XBRV_* accordingly renamed to MTRV_*
+//            - Fixed device length not correct for bid 0 when using Xbus Master and setDeviceMode function
 //
 // v1.1.7
 // 15-02-2006 - Added fixed point signed 12.20 dataformat support
-//				Added selective calibrated data output per sensor type support
-//				Added outputmode temperature support
-//				Fixed warning C4244: '=' : conversion from '' to '', possible loss of data
+//              Added selective calibrated data output per sensor type support
+//              Added outputmode temperature support
+//              Fixed warning C4244: '=' : conversion from '' to '', possible loss of data
 // v1.1.6
 // 25-01-2006 - Added escape function for CLRDTR, CLRRTS, SETDTR, SETRTS, SETXOFF, SETXON, SETBREAK, CLRBREAK
 //
@@ -45,46 +45,46 @@
 //
 // v1.1.4
 // 08-11-2005 - Changed practically all uses of m_timeOut into uses of the new m_clkEnd
-//			  - Changed COM timeout in win32 to return immediately if data is available,
-//				but wait 1ms otherwise
+//            - Changed COM timeout in win32 to return immediately if data is available,
+//              but wait 1ms otherwise
 //
 // v1.1.3
 // 18-10-2005 - Added MID_REQPRODUCTCODE, MID_REQ/SETTRANSMITDELAY
-//			  - Added MTRV_TIMEOUTNODATA indicating timeout occurred due to no data read
+//            - Added MTRV_TIMEOUTNODATA indicating timeout occurred due to no data read
 //
 // v1.1.2
 // 16-09-2005 - Added eMTS version 0.1->1.0 changes (EMTS_FACTORYMODE)
-//			  - Added factory output mode defines
+//            - Added factory output mode defines
 //
 // v1.1.1
 // 01-09-2005 - Added defines for Extended output mode
-//			  - Added reqSetting (byte array in + out & no param variant)
+//            - Added reqSetting (byte array in + out & no param variant)
 //
 // v1.1
 // 08-08-2005 - Added file read and write support
-//			  - Added functions for data retrieval (getValue etc)
-//				  for easy data retrieval of acc, gyr, mag etc
-//			  - ReadMessageRaw:
-//				- added a temporary buffer for unprocessed bytes
-//				- check for invalid length messages
-//			  - Changed BID_MT into 1 and added BID_MASTER (=0xFF)
-//			  - Changed various ....SerialPort functions to .....Port
-//			  - Changed mtSendMessage functions to mtWriteMessage
-//			  - Added numerous defines
-//			  - Deleted obsolete functions
-//			  - Changed function getLastErrorCode into getLastDeviceError
-//			  - Changed OpenPort function for compatiblity with Bluetooth ports
-//			  - Added workaround for lockup of USB driver (close function) 
-//			  - Added workaround for clock() problem with read function of USB driver
+//            - Added functions for data retrieval (getValue etc)
+//                for easy data retrieval of acc, gyr, mag etc
+//            - ReadMessageRaw:
+//              - added a temporary buffer for unprocessed bytes
+//              - check for invalid length messages
+//            - Changed BID_MT into 1 and added BID_MASTER (=0xFF)
+//            - Changed various ....SerialPort functions to .....Port
+//            - Changed mtSendMessage functions to mtWriteMessage
+//            - Added numerous defines
+//            - Deleted obsolete functions
+//            - Changed function getLastErrorCode into getLastDeviceError
+//            - Changed OpenPort function for compatiblity with Bluetooth ports
+//            - Added workaround for lockup of USB driver (close function)
+//            - Added workaround for clock() problem with read function of USB driver
 //
 // v1.0.2
 // 29-06-2005 - Inserted initSerialPort with devicename input
-//			  - Changed return value defines names from X_ to MTRV_
-//			  - Removed unneeded includes for linux
+//            - Changed return value defines names from X_ to MTRV_
+//            - Removed unneeded includes for linux
 //
 // v1.0.1
 // 22-06-2005 - Fixed ReqSetting functions (byte array & param variant)
-//				mtSendRawString had wrong length input
+//              mtSendRawString had wrong length input
 //
 // v1.0.0
 // 20-06-2005 - Initial release
@@ -92,11 +92,11 @@
 // ----------------------------------------------------------------------------
 //  This file is an Xsens Code Examples.
 //
-//  Copyright (C) Xsens Technologies B.V., 2005.  
+//  Copyright (C) Xsens Technologies B.V., 2005.
 //
 //  This source code is intended only as a example of the implementation
-//	of the Xsens MT Communication protocol.
-//	It was written for cross platform capabilities.
+//  of the Xsens MT Communication protocol.
+//  It was written for cross platform capabilities.
 //
 //  THIS CODE AND INFORMATION IS PROVIDED "AS IS" WITHOUT WARRANTY OF ANY
 //  KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE
@@ -109,7 +109,7 @@
 
 #ifdef _DEBUG
 #undef THIS_FILE
-static char THIS_FILE[]=__FILE__;
+static char THIS_FILE[] = __FILE__;
 #define new DEBUG_NEW
 #endif
 
@@ -123,2827 +123,3067 @@ static char THIS_FILE[]=__FILE__;
 
 namespace IMU
 {
-	namespace Xsens
-	{
-		//////////////////////////////////////////////////////////////////////
-		// Construction/Destruction
-		//////////////////////////////////////////////////////////////////////
-		//
-		CXsensMTiModule::CXsensMTiModule()
-		{
-			m_handle = -1;
-			m_portOpen = false;
-			m_fileOpen = false;
-			m_deviceError = 0;		// No error
-			m_retVal = MTRV_OK;
-			m_timeOut = TO_DEFAULT;
-			m_nTempBufferLen = 0;
-			m_clkEnd = 0;
-			for(int i = 0 ; i < MAXDEVICES + 1 ; i++)
-			{
-				m_storedOutputMode[i] = INVALIDSETTINGVALUE;
-				m_storedOutputSettings[i] = INVALIDSETTINGVALUE;
-				m_storedDataLength[i] = 0;
-			}
-		}
-
-		CXsensMTiModule::~CXsensMTiModule()
-		{
-			close();
-		}
-
-////////////////////////////////////////////////////////////////////
-// clockms
-//
-// Calculates the processor time used by the calling process.
-// For linux use gettimeofday instead of clock() function
-// When using read from FTDI serial port in a loop the 
-// clock() function very often keeps returning 0.
-//
-// Output
-//   returns processor time in milliseconds
-//
-		clock_t CXsensMTiModule::clockms()
-		{
-			clock_t clk;
+    namespace Xsens
+    {
+        //////////////////////////////////////////////////////////////////////
+        // Construction/Destruction
+        //////////////////////////////////////////////////////////////////////
+        //
+        CXsensMTiModule::CXsensMTiModule()
+        {
+            m_handle = -1;
+            m_portOpen = false;
+            m_fileOpen = false;
+            m_deviceError = 0;      // No error
+            m_retVal = MTRV_OK;
+            m_timeOut = TO_DEFAULT;
+            m_nTempBufferLen = 0;
+            m_clkEnd = 0;
+
+            for (int i = 0 ; i < MAXDEVICES + 1 ; i++)
+            {
+                m_storedOutputMode[i] = INVALIDSETTINGVALUE;
+                m_storedOutputSettings[i] = INVALIDSETTINGVALUE;
+                m_storedDataLength[i] = 0;
+            }
+        }
+
+        CXsensMTiModule::~CXsensMTiModule()
+        {
+            close();
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // clockms
+        //
+        // Calculates the processor time used by the calling process.
+        // For linux use gettimeofday instead of clock() function
+        // When using read from FTDI serial port in a loop the
+        // clock() function very often keeps returning 0.
+        //
+        // Output
+        //   returns processor time in milliseconds
+        //
+        clock_t CXsensMTiModule::clockms()
+        {
+            clock_t clk;
 #ifdef WIN32
-			clk = clock();		// Get current processor time
+            clk = clock();      // Get current processor time
 #if (CLOCKS_PER_SEC != 1000)
-			clk /= (CLOCKS_PER_SEC / 1000);
-			//	clk = (clk * 1000) / CLOCKS_PER_SEC;
+            clk /= (CLOCKS_PER_SEC / 1000);
+            //  clk = (clk * 1000) / CLOCKS_PER_SEC;
 #endif
 #else
-			struct timeval tv;
-			struct timezone tz;
-			gettimeofday(&tv,&tz);
-			clk = tv.tv_sec * 1000 + (tv.tv_usec / 1000);
+            struct timeval tv;
+            struct timezone tz;
+            gettimeofday(&tv, &tz);
+            clk = tv.tv_sec * 1000 + (tv.tv_usec / 1000);
 #endif
-			return clk;
-		}
+            return clk;
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // openPort (serial port number as input parameter)
+        //
+        // Opens a 'live' connection to a MT or XM
+        //
+        // Input
+        //   portNumber  : number of serial port to open (1-99)
+        //   baudrate    : baudrate value (One of the PBR_* defines), default = PBR_115K2
+        //   inqueueSize : size of input queue, default = 4096
+        //   outqueueSize: size of output queue, default = 1024
+        //
+        // Output
+        //   returns MTRV_OK if serial port is successfully opened, else MTRV_INPUTCANNOTBEOPENED
+        //
+        short CXsensMTiModule::openPort(const int portNumber, const unsigned long baudrate, const unsigned long /*inqueueSize*/, const unsigned long /*outqueueSize*/)
+        {
+            m_clkEnd = 0;
+
+            if (m_fileOpen || m_portOpen)
+            {
+                return (m_retVal = MTRV_ANINPUTALREADYOPEN);
+            }
 
-////////////////////////////////////////////////////////////////////
-// openPort (serial port number as input parameter)
-//
-// Opens a 'live' connection to a MT or XM
-//
-// Input
-//   portNumber	 : number of serial port to open (1-99)
-//   baudrate	 : baudrate value (One of the PBR_* defines), default = PBR_115K2
-//   inqueueSize : size of input queue, default = 4096
-//   outqueueSize: size of output queue, default = 1024
-//
-// Output
-//   returns MTRV_OK if serial port is successfully opened, else MTRV_INPUTCANNOTBEOPENED
-//
-		short CXsensMTiModule::openPort(const int portNumber, const unsigned long baudrate, const unsigned long /*inqueueSize*/, const unsigned long /*outqueueSize*/)
-		{
-			m_clkEnd = 0;
-
-			if (m_fileOpen || m_portOpen)
-			{
-				return (m_retVal = MTRV_ANINPUTALREADYOPEN);
-			}
-#ifdef WIN32	
-			char pchFileName[10];
-
-			sprintf(pchFileName,"\\\\.\\COM%d",portNumber);		// Create file name
-
-			m_handle = CreateFile(pchFileName, GENERIC_READ | GENERIC_WRITE, 0, NULL, OPEN_EXISTING, 0, NULL);
-			if (m_handle == INVALID_HANDLE_VALUE)
-			{
-				return (m_retVal = MTRV_INPUTCANNOTBEOPENED);
-			}
-
-			// Once here, port is open
-			m_portOpen = true;
-
-			//Get the current state & then change it
-			DCB dcb;
-
-			GetCommState(m_handle, &dcb);// Get current state
-
-			dcb.BaudRate = baudrate;// Setup the baud rate
-			dcb.Parity = NOPARITY;// Setup the Parity
-			dcb.ByteSize = 8;// Setup the data bits
-			dcb.StopBits = TWOSTOPBITS;// Setup the stop bits
-			dcb.fDsrSensitivity = FALSE;// Setup the flow control
-			dcb.fOutxCtsFlow = FALSE;// NoFlowControl:
-			dcb.fOutxDsrFlow = FALSE;
-			dcb.fOutX = FALSE;
-			dcb.fInX = FALSE;
-			if (!SetCommState(m_handle, (LPDCB)&dcb))
-			{			// Set new state
-				// Bluetooth ports cannot always be opened with 2 stopbits
-				// Now try to open port with 1 stopbit.
-				dcb.StopBits = ONESTOPBIT;
-				if (!SetCommState(m_handle, (LPDCB)&dcb))
-				{
-					CloseHandle(m_handle);
-					m_handle = INVALID_HANDLE_VALUE;
-					m_portOpen = false;
-					return (m_retVal = MTRV_INPUTCANNOTBEOPENED);
-				}
-			}
-
-			// Set COM timeouts
-			COMMTIMEOUTS CommTimeouts;
-
-			GetCommTimeouts(m_handle,&CommTimeouts);// Fill CommTimeouts structure
-
-			// immediate return if data is available, wait 1ms otherwise
-			CommTimeouts.ReadTotalTimeoutConstant = 1;
-			CommTimeouts.ReadIntervalTimeout = MAXDWORD;
-			CommTimeouts.ReadTotalTimeoutMultiplier = MAXDWORD;
-
-			// immediate return whether data is available or not
-//	CommTimeouts.ReadTotalTimeoutConstant = 0;
-//	CommTimeouts.ReadIntervalTimeout = MAXDWORD;
-//	CommTimeouts.ReadTotalTimeoutMultiplier = 0; 
-
-			SetCommTimeouts(m_handle, &CommTimeouts);// Set CommTimeouts structure
-
-			// Other initialization functions
-			EscapeCommFunction(m_handle, SETRTS);// Enable RTS (for Xbus Master use)
-			SetupComm(m_handle,inqueueSize,outqueueSize);// Set queue size
-
-			// Remove any 'old' data in buffer
-			PurgeComm(m_handle, PURGE_TXCLEAR | PURGE_RXCLEAR);
-
-			return (m_retVal = MTRV_OK);
-#else	
-			char chPort[15];
-			struct termios options;
-
-			/* Open port */
-			sprintf(chPort,"/dev/ttyS%d",(portNumber - 1));
-			m_handle = open(chPort,O_RDWR | O_NOCTTY);
-
-			// O_RDWR: Read+Write
-			// O_NOCTTY: Raw input, no "controlling terminal"
-			// O_NDELAY: Don't care about DCD signal
-
-			if (m_handle < 0)
-			{
-				// Port not open
-				return (m_retVal = MTRV_INPUTCANNOTBEOPENED);
-			}
-
-			// Once here, port is open
-			m_portOpen = true;
-
-			/* Start configuring of port for non-canonical transfer mode */
-			// Get current options for the port
-			tcgetattr(m_handle,&options);
-
-			// Set baudrate.
-			cfsetispeed(&options,baudrate);
-			cfsetospeed(&options,baudrate);
-
-			// Enable the receiver and set local mode
-			options.c_cflag |= (CLOCAL | CREAD);
-			// Set character size to data bits and set no parity Mask the characte size bits
-			options.c_cflag &= ~(CSIZE | PARENB);
-			options.c_cflag |= CS8;			// Select 8 data bits
-			options.c_cflag |= CSTOPB;			// send 2 stop bits
-			// Disable hardware flow control
-			options.c_cflag &= ~CRTSCTS;
-			options.c_lflag &= ~(ECHO | ECHONL | ICANON | ISIG | IEXTEN);
-			// Disable software flow control
-			options.c_iflag &= ~(IGNBRK | BRKINT | PARMRK | ISTRIP | INLCR | IGNCR | ICRNL | IXON);
-			// Set Raw output
-			options.c_oflag &= ~OPOST;
-			// Timeout 0.005 sec for first byte, read minimum of 0 bytes
-			options.c_cc[VMIN] = 0;
-			options.c_cc[VTIME] = 5;
-
-			// Set the new options for the port
-			tcsetattr(m_handle,TCSANOW,&options);
-
-			tcflush(m_handle,TCIOFLUSH);
-
-			return (m_retVal = MTRV_OK);
-#endif	
-		}
-
-////////////////////////////////////////////////////////////////////
-// openPort (string as input parameter)
-//
-// Opens a 'live' connection to a MT or XM
-//
-// Input
-//   portName	 : device name of serial port ("/dev/ttyUSB0" or "\\\\.\\COM1")
-//   baudrate	 : baudrate value (One of the PBR_* defines), default = PBR_115K2
-//   inqueueSize : size of input queue, default = 4096
-//   outqueueSize: size of output queue, default = 1024
-//
-// Output
-//   returns MTRV_OK if serial port is successfully opened, else MTRV_INPUTCANNOTBEOPENED
-//
-		short CXsensMTiModule::openPort(const char *portName, const unsigned long baudrate, const unsigned long /*inqueueSize*/, const unsigned long /*outqueueSize*/)
-		{
-			m_clkEnd = 0;
-
-			if (m_fileOpen || m_portOpen)
-			{
-				return (m_retVal = MTRV_ANINPUTALREADYOPEN);
-			}
-#ifdef WIN32	
-			m_handle = CreateFile(portName, GENERIC_READ | GENERIC_WRITE, 0, NULL, OPEN_EXISTING, 0, NULL);
-			if (m_handle == INVALID_HANDLE_VALUE)
-			{
-				return (m_retVal = MTRV_INPUTCANNOTBEOPENED);
-			}
-
-			// Once here, port is open
-			m_portOpen = true;
-
-			//Get the current state & then change it
-			DCB dcb;
-
-			GetCommState(m_handle, &dcb);// Get current state
-
-			dcb.BaudRate = baudrate;// Setup the baud rate
-			dcb.Parity = NOPARITY;// Setup the Parity
-			dcb.ByteSize = 8;// Setup the data bits
-			dcb.StopBits = TWOSTOPBITS;// Setup the stop bits
-			dcb.fDsrSensitivity = FALSE;// Setup the flow control
-			dcb.fOutxCtsFlow = FALSE;// NoFlowControl:
-			dcb.fOutxDsrFlow = FALSE;
-			dcb.fOutX = FALSE;
-			dcb.fInX = FALSE;
-			if (!SetCommState(m_handle, (LPDCB)&dcb))
-			{			// Set new state
-				// Bluetooth ports cannot always be opened with 2 stopbits
-				// Now try to open port with 1 stopbit.
-				dcb.StopBits = ONESTOPBIT;
-				if (!SetCommState(m_handle, (LPDCB)&dcb))
-				{
-					CloseHandle(m_handle);
-					m_handle = INVALID_HANDLE_VALUE;
-					m_portOpen = false;
-					return (m_retVal = MTRV_INPUTCANNOTBEOPENED);
-				}
-			}
-
-			// Set COM timeouts
-			COMMTIMEOUTS CommTimeouts;
-
-			GetCommTimeouts(m_handle,&CommTimeouts);// Fill CommTimeouts structure
-
-			// immediate return if data is available, wait 1ms otherwise
-			CommTimeouts.ReadTotalTimeoutConstant = 1;
-			CommTimeouts.ReadIntervalTimeout = MAXDWORD;
-			CommTimeouts.ReadTotalTimeoutMultiplier = MAXDWORD;
-
-			// immediate return whether data is available or not
-//	CommTimeouts.ReadTotalTimeoutConstant = 0;
-//	CommTimeouts.ReadIntervalTimeout = MAXDWORD;
-//	CommTimeouts.ReadTotalTimeoutMultiplier = 0; 
-			SetCommTimeouts(m_handle, &CommTimeouts);// Set CommTimeouts structure
-
-			// Other initialization functions
-			EscapeCommFunction(m_handle, SETRTS);// Enable RTS (for Xbus Master use)
-			SetupComm(m_handle,inqueueSize,outqueueSize);// Set queue size
-
-			// Remove any 'old' data in buffer
-			PurgeComm(m_handle, PURGE_TXCLEAR | PURGE_RXCLEAR);
-
-			return (m_retVal = MTRV_OK);
-#else	
-			struct termios options;
-
-			/* Open port */
-
-			m_handle = open(portName,O_RDWR | O_NOCTTY);
-
-			// O_RDWR: Read+Write
-			// O_NOCTTY: Raw input, no "controlling terminal"
-			// O_NDELAY: Don't care about DCD signal
-
-			if (m_handle < 0)
-			{
-				// Port not open
-				return (m_retVal = MTRV_INPUTCANNOTBEOPENED);
-			}
-
-			// Once here, port is open
-			m_portOpen = true;
-
-			/* Start configuring of port for non-canonical transfer mode */
-			// Get current options for the port
-			tcgetattr(m_handle,&options);
-
-			// Set baudrate.
-			cfsetispeed(&options,baudrate);
-			cfsetospeed(&options,baudrate);
-
-			// Enable the receiver and set local mode
-			options.c_cflag |= (CLOCAL | CREAD);
-			// Set character size to data bits and set no parity Mask the characte size bits
-			options.c_cflag &= ~(CSIZE | PARENB);
-			options.c_cflag |= CS8;			// Select 8 data bits
-			options.c_cflag |= CSTOPB;			// send 2 stop bits
-			// Disable hardware flow control
-			options.c_cflag &= ~CRTSCTS;
-			options.c_lflag &= ~(ECHO | ECHONL | ICANON | ISIG | IEXTEN);
-			// Disable software flow control
-			options.c_iflag &= ~(IGNBRK | BRKINT | PARMRK | ISTRIP | INLCR | IGNCR | ICRNL | IXON);
-			// Set Raw output
-			options.c_oflag &= ~OPOST;
-			// Timeout 0.005 sec for first byte, read minimum of 0 bytes
-			options.c_cc[VMIN] = 0;
-			options.c_cc[VTIME] = 5;
-
-			// Set the new options for the port
-			tcsetattr(m_handle,TCSANOW,&options);
-
-			tcflush(m_handle,TCIOFLUSH);
-
-			return (m_retVal = MTRV_OK);
-#endif	
-		}
-
-////////////////////////////////////////////////////////////////////
-// openFile
-//
-// Open file for reading and writing
-// Filepos is at start of file
-//
-// Input
-//   fileName	 : file name including path
-//	 createAlways: empties the log file, if existing
-//
-// Output
-//   returns MTRV_OK if the file is opened
-//   returns MTRV_INPUTCANNOTBEOPENED if the file can not be opened
-//   returns MTRV_ANINPUTALREADYOPEN if a serial port / file is already opened
-//
-		short CXsensMTiModule::openFile(const char *fileName, bool createAlways)
-		{
-			m_clkEnd = 0;
-
-			if (m_portOpen || m_portOpen)
-			{
-				return (m_retVal = MTRV_ANINPUTALREADYOPEN);
-			}
-#ifdef WIN32	
-			DWORD disposition = OPEN_ALWAYS;
-			if (createAlways == true)
-			{
-				disposition = CREATE_ALWAYS;
-			}
-			m_handle = CreateFile(fileName, GENERIC_READ | GENERIC_WRITE, FILE_SHARE_READ, NULL, disposition, 0, NULL);
-			if (m_handle == INVALID_HANDLE_VALUE)
-			{
-				return (m_retVal = MTRV_INPUTCANNOTBEOPENED);
-			}
-#else
-			int openMode = O_RDWR | O_CREAT;
-			if (createAlways == true)
-			{
-				openMode |= O_TRUNC;
-			}
-			m_handle = open(fileName,openMode,S_IRWXU);
-			if (m_handle < 0)
-			{
-				return (m_retVal = MTRV_INPUTCANNOTBEOPENED);
-			}
-#endif
-			m_timeOut = 0;   // No timeout when using file input
-			m_fileOpen = true;
-			return (m_retVal = MTRV_OK);
+#ifdef WIN32
+            char pchFileName[10];
 
-		}
+            sprintf(pchFileName, "\\\\.\\COM%d", portNumber);   // Create file name
 
-////////////////////////////////////////////////////////////////////
-// isPortOpen
-//
-// Return if serial port is open or not
-//
-		bool CXsensMTiModule::isPortOpen()
-		{
-			return m_portOpen;
-		}
+            m_handle = CreateFile(pchFileName, GENERIC_READ | GENERIC_WRITE, 0, NULL, OPEN_EXISTING, 0, NULL);
 
-////////////////////////////////////////////////////////////////////
-// isFileOpen
-//
-// Return if serial port is open or not
-//
-		bool CXsensMTiModule::isFileOpen()
-		{
-			return m_fileOpen;
-		}
+            if (m_handle == INVALID_HANDLE_VALUE)
+            {
+                return (m_retVal = MTRV_INPUTCANNOTBEOPENED);
+            }
 
-////////////////////////////////////////////////////////////////////
-// readData
-//
-// Reads bytes from serial port or file
-//
-// Input
-//   msgBuffer		: pointer to buffer in which next string will be stored
-//   nBytesToRead	: number of buffer bytes to read from serial port
-//   retval			: return value, either MTRV_OK, MTRV_ENDOFFILE or MTRV_NOINPUTINITIALIZED
-//
-// Output
-//   number of bytes actually read
-		int CXsensMTiModule::readData(unsigned char* msgBuffer, const int nBytesToRead)
-		{
-			//if(!m_fileOpen && !m_portOpen)
-			if (!(m_portOpen || m_fileOpen))
-			{
-				m_retVal = MTRV_NOINPUTINITIALIZED;
-				return 0;
-			}
-#ifdef WIN32
-			DWORD nBytesRead;
-			BOOL retval = ReadFile(m_handle, msgBuffer, nBytesToRead, &nBytesRead, NULL);
-			if (retval && nBytesRead == 0 && m_fileOpen)
-			{
-				m_retVal = MTRV_ENDOFFILE;
-			}
-			else
-			m_retVal = MTRV_OK;
-			return nBytesRead;
+            // Once here, port is open
+            m_portOpen = true;
+
+            //Get the current state & then change it
+            DCB dcb;
+
+            GetCommState(m_handle, &dcb);// Get current state
+
+            dcb.BaudRate = baudrate;// Setup the baud rate
+            dcb.Parity = NOPARITY;// Setup the Parity
+            dcb.ByteSize = 8;// Setup the data bits
+            dcb.StopBits = TWOSTOPBITS;// Setup the stop bits
+            dcb.fDsrSensitivity = FALSE;// Setup the flow control
+            dcb.fOutxCtsFlow = FALSE;// NoFlowControl:
+            dcb.fOutxDsrFlow = FALSE;
+            dcb.fOutX = FALSE;
+            dcb.fInX = FALSE;
+
+            if (!SetCommState(m_handle, (LPDCB)&dcb))
+            {
+                // Set new state
+                // Bluetooth ports cannot always be opened with 2 stopbits
+                // Now try to open port with 1 stopbit.
+                dcb.StopBits = ONESTOPBIT;
+
+                if (!SetCommState(m_handle, (LPDCB)&dcb))
+                {
+                    CloseHandle(m_handle);
+                    m_handle = INVALID_HANDLE_VALUE;
+                    m_portOpen = false;
+                    return (m_retVal = MTRV_INPUTCANNOTBEOPENED);
+                }
+            }
+
+            // Set COM timeouts
+            COMMTIMEOUTS CommTimeouts;
+
+            GetCommTimeouts(m_handle, &CommTimeouts); // Fill CommTimeouts structure
+
+            // immediate return if data is available, wait 1ms otherwise
+            CommTimeouts.ReadTotalTimeoutConstant = 1;
+            CommTimeouts.ReadIntervalTimeout = MAXDWORD;
+            CommTimeouts.ReadTotalTimeoutMultiplier = MAXDWORD;
+
+            // immediate return whether data is available or not
+            //  CommTimeouts.ReadTotalTimeoutConstant = 0;
+            //  CommTimeouts.ReadIntervalTimeout = MAXDWORD;
+            //  CommTimeouts.ReadTotalTimeoutMultiplier = 0;
+
+            SetCommTimeouts(m_handle, &CommTimeouts);// Set CommTimeouts structure
+
+            // Other initialization functions
+            EscapeCommFunction(m_handle, SETRTS);// Enable RTS (for Xbus Master use)
+            SetupComm(m_handle, inqueueSize, outqueueSize); // Set queue size
+
+            // Remove any 'old' data in buffer
+            PurgeComm(m_handle, PURGE_TXCLEAR | PURGE_RXCLEAR);
+
+            return (m_retVal = MTRV_OK);
 #else
-			const int nBytesRead = read(m_handle,msgBuffer,nBytesToRead);
-
-			m_retVal = MTRV_OK;
-			if (nBytesRead)
-				return nBytesRead;
-			else if (m_fileOpen)
-				m_retVal = MTRV_ENDOFFILE;
-			return nBytesRead;
-			/*
-			 if (nBytesRead == 0 && m_fileOpen)
-			 {
-			 nBytesRead = 0;
-			 m_retVal = MTRV_ENDOFFILE;
-			 }
-			 else
-			 m_retVal = MTRV_OK;
-			 return nBytesRead;*/
-
-			// In Linux it is sometimes better to read per byte instead of a block of bytes at once
-			// Use this block if experiencing problems with the above code
-			/*
-			 int j = 0;	// Index in buffer for read data
-			 int k = 0;	// Timeout factor
-			 int nRead = 0;	// Bytes read from port, return by read function
-
-			 do {
-			 nRead = read(m_handle, &msgBuffer[j], 1);
-			 if (nRead == 1) {	// Byte read
-			 k = 0;
-			 j++;
-			 }
-			 else {
-			 k++;
-			 }
-
-			 if (k == 3)	{ // Timeout, too long no data read from port
-			 return nRead;
-			 }
-			 }
-			 while (j < nBytesToRead);
-
-			 return j;
-			 */
+            char chPort[15];
+            struct termios options;
+
+            /* Open port */
+            sprintf(chPort, "/dev/ttyS%d", (portNumber - 1));
+            m_handle = open(chPort, O_RDWR | O_NOCTTY);
+
+            // O_RDWR: Read+Write
+            // O_NOCTTY: Raw input, no "controlling terminal"
+            // O_NDELAY: Don't care about DCD signal
+
+            if (m_handle < 0)
+            {
+                // Port not open
+                return (m_retVal = MTRV_INPUTCANNOTBEOPENED);
+            }
+
+            // Once here, port is open
+            m_portOpen = true;
+
+            /* Start configuring of port for non-canonical transfer mode */
+            // Get current options for the port
+            tcgetattr(m_handle, &options);
+
+            // Set baudrate.
+            cfsetispeed(&options, baudrate);
+            cfsetospeed(&options, baudrate);
+
+            // Enable the receiver and set local mode
+            options.c_cflag |= (CLOCAL | CREAD);
+            // Set character size to data bits and set no parity Mask the characte size bits
+            options.c_cflag &= ~(CSIZE | PARENB);
+            options.c_cflag |= CS8;         // Select 8 data bits
+            options.c_cflag |= CSTOPB;          // send 2 stop bits
+            // Disable hardware flow control
+            options.c_cflag &= ~CRTSCTS;
+            options.c_lflag &= ~(ECHO | ECHONL | ICANON | ISIG | IEXTEN);
+            // Disable software flow control
+            options.c_iflag &= ~(IGNBRK | BRKINT | PARMRK | ISTRIP | INLCR | IGNCR | ICRNL | IXON);
+            // Set Raw output
+            options.c_oflag &= ~OPOST;
+            // Timeout 0.005 sec for first byte, read minimum of 0 bytes
+            options.c_cc[VMIN] = 0;
+            options.c_cc[VTIME] = 5;
+
+            // Set the new options for the port
+            tcsetattr(m_handle, TCSANOW, &options);
+
+            tcflush(m_handle, TCIOFLUSH);
+
+            return (m_retVal = MTRV_OK);
 #endif
-		}
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // openPort (string as input parameter)
+        //
+        // Opens a 'live' connection to a MT or XM
+        //
+        // Input
+        //   portName    : device name of serial port ("/dev/ttyUSB0" or "\\\\.\\COM1")
+        //   baudrate    : baudrate value (One of the PBR_* defines), default = PBR_115K2
+        //   inqueueSize : size of input queue, default = 4096
+        //   outqueueSize: size of output queue, default = 1024
+        //
+        // Output
+        //   returns MTRV_OK if serial port is successfully opened, else MTRV_INPUTCANNOTBEOPENED
+        //
+        short CXsensMTiModule::openPort(const char* portName, const unsigned long baudrate, const unsigned long /*inqueueSize*/, const unsigned long /*outqueueSize*/)
+        {
+            m_clkEnd = 0;
+
+            if (m_fileOpen || m_portOpen)
+            {
+                return (m_retVal = MTRV_ANINPUTALREADYOPEN);
+            }
 
-////////////////////////////////////////////////////////////////////
-// writeData
-//
-// Writes bytes to serial port (to do: file)
-//
-// Input
-//   msgBuffer		: a pointer to a char buffer containing
-//					  the characters to be written to serial port
-//   nBytesToWrite	: number of buffer bytes to write to serial port
-//
-// Output
-//   number of bytes actually written
-// 
-// The MTComm return value is != MTRV_OK if serial port is closed
-		int CXsensMTiModule::writeData(const unsigned char* msgBuffer, const int nBytesToWrite)
-		{
-			if (!m_fileOpen && !m_portOpen)
-			{
-				m_retVal = MTRV_NOINPUTINITIALIZED;
-				return 0;
-			}
-
-			m_retVal = MTRV_OK;
 #ifdef WIN32
-			DWORD nBytesWritten;
-			WriteFile(m_handle, msgBuffer, nBytesToWrite, &nBytesWritten, NULL);
-			return nBytesWritten;
+            m_handle = CreateFile(portName, GENERIC_READ | GENERIC_WRITE, 0, NULL, OPEN_EXISTING, 0, NULL);
+
+            if (m_handle == INVALID_HANDLE_VALUE)
+            {
+                return (m_retVal = MTRV_INPUTCANNOTBEOPENED);
+            }
+
+            // Once here, port is open
+            m_portOpen = true;
+
+            //Get the current state & then change it
+            DCB dcb;
+
+            GetCommState(m_handle, &dcb);// Get current state
+
+            dcb.BaudRate = baudrate;// Setup the baud rate
+            dcb.Parity = NOPARITY;// Setup the Parity
+            dcb.ByteSize = 8;// Setup the data bits
+            dcb.StopBits = TWOSTOPBITS;// Setup the stop bits
+            dcb.fDsrSensitivity = FALSE;// Setup the flow control
+            dcb.fOutxCtsFlow = FALSE;// NoFlowControl:
+            dcb.fOutxDsrFlow = FALSE;
+            dcb.fOutX = FALSE;
+            dcb.fInX = FALSE;
+
+            if (!SetCommState(m_handle, (LPDCB)&dcb))
+            {
+                // Set new state
+                // Bluetooth ports cannot always be opened with 2 stopbits
+                // Now try to open port with 1 stopbit.
+                dcb.StopBits = ONESTOPBIT;
+
+                if (!SetCommState(m_handle, (LPDCB)&dcb))
+                {
+                    CloseHandle(m_handle);
+                    m_handle = INVALID_HANDLE_VALUE;
+                    m_portOpen = false;
+                    return (m_retVal = MTRV_INPUTCANNOTBEOPENED);
+                }
+            }
+
+            // Set COM timeouts
+            COMMTIMEOUTS CommTimeouts;
+
+            GetCommTimeouts(m_handle, &CommTimeouts); // Fill CommTimeouts structure
+
+            // immediate return if data is available, wait 1ms otherwise
+            CommTimeouts.ReadTotalTimeoutConstant = 1;
+            CommTimeouts.ReadIntervalTimeout = MAXDWORD;
+            CommTimeouts.ReadTotalTimeoutMultiplier = MAXDWORD;
+
+            // immediate return whether data is available or not
+            //  CommTimeouts.ReadTotalTimeoutConstant = 0;
+            //  CommTimeouts.ReadIntervalTimeout = MAXDWORD;
+            //  CommTimeouts.ReadTotalTimeoutMultiplier = 0;
+            SetCommTimeouts(m_handle, &CommTimeouts);// Set CommTimeouts structure
+
+            // Other initialization functions
+            EscapeCommFunction(m_handle, SETRTS);// Enable RTS (for Xbus Master use)
+            SetupComm(m_handle, inqueueSize, outqueueSize); // Set queue size
+
+            // Remove any 'old' data in buffer
+            PurgeComm(m_handle, PURGE_TXCLEAR | PURGE_RXCLEAR);
+
+            return (m_retVal = MTRV_OK);
 #else
-			return write(m_handle,msgBuffer,nBytesToWrite);
+            struct termios options;
+
+            /* Open port */
+
+            m_handle = open(portName, O_RDWR | O_NOCTTY);
+
+            // O_RDWR: Read+Write
+            // O_NOCTTY: Raw input, no "controlling terminal"
+            // O_NDELAY: Don't care about DCD signal
+
+            if (m_handle < 0)
+            {
+                // Port not open
+                return (m_retVal = MTRV_INPUTCANNOTBEOPENED);
+            }
+
+            // Once here, port is open
+            m_portOpen = true;
+
+            /* Start configuring of port for non-canonical transfer mode */
+            // Get current options for the port
+            tcgetattr(m_handle, &options);
+
+            // Set baudrate.
+            cfsetispeed(&options, baudrate);
+            cfsetospeed(&options, baudrate);
+
+            // Enable the receiver and set local mode
+            options.c_cflag |= (CLOCAL | CREAD);
+            // Set character size to data bits and set no parity Mask the characte size bits
+            options.c_cflag &= ~(CSIZE | PARENB);
+            options.c_cflag |= CS8;         // Select 8 data bits
+            options.c_cflag |= CSTOPB;          // send 2 stop bits
+            // Disable hardware flow control
+            options.c_cflag &= ~CRTSCTS;
+            options.c_lflag &= ~(ECHO | ECHONL | ICANON | ISIG | IEXTEN);
+            // Disable software flow control
+            options.c_iflag &= ~(IGNBRK | BRKINT | PARMRK | ISTRIP | INLCR | IGNCR | ICRNL | IXON);
+            // Set Raw output
+            options.c_oflag &= ~OPOST;
+            // Timeout 0.005 sec for first byte, read minimum of 0 bytes
+            options.c_cc[VMIN] = 0;
+            options.c_cc[VTIME] = 5;
+
+            // Set the new options for the port
+            tcsetattr(m_handle, TCSANOW, &options);
+
+            tcflush(m_handle, TCIOFLUSH);
+
+            return (m_retVal = MTRV_OK);
 #endif
-		}
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // openFile
+        //
+        // Open file for reading and writing
+        // Filepos is at start of file
+        //
+        // Input
+        //   fileName    : file name including path
+        //   createAlways: empties the log file, if existing
+        //
+        // Output
+        //   returns MTRV_OK if the file is opened
+        //   returns MTRV_INPUTCANNOTBEOPENED if the file can not be opened
+        //   returns MTRV_ANINPUTALREADYOPEN if a serial port / file is already opened
+        //
+        short CXsensMTiModule::openFile(const char* fileName, bool createAlways)
+        {
+            m_clkEnd = 0;
+
+            if (m_portOpen || m_portOpen)
+            {
+                return (m_retVal = MTRV_ANINPUTALREADYOPEN);
+            }
 
-////////////////////////////////////////////////////////////////////
-// flush
-//
-// Remove any 'old' data in COM port buffer and flushes internal 
-//   temporary buffer
-//
-		void CXsensMTiModule::flush()
-		{
-			if (m_portOpen)
-			{
 #ifdef WIN32
-				// Remove any 'old' data in buffer
-				PurgeComm(m_handle, PURGE_TXCLEAR | PURGE_RXCLEAR);
+            DWORD disposition = OPEN_ALWAYS;
+
+            if (createAlways == true)
+            {
+                disposition = CREATE_ALWAYS;
+            }
+
+            m_handle = CreateFile(fileName, GENERIC_READ | GENERIC_WRITE, FILE_SHARE_READ, NULL, disposition, 0, NULL);
+
+            if (m_handle == INVALID_HANDLE_VALUE)
+            {
+                return (m_retVal = MTRV_INPUTCANNOTBEOPENED);
+            }
+
 #else
-				tcflush(m_handle,TCIOFLUSH);
+            int openMode = O_RDWR | O_CREAT;
+
+            if (createAlways == true)
+            {
+                openMode |= O_TRUNC;
+            }
+
+            m_handle = open(fileName, openMode, S_IRWXU);
+
+            if (m_handle < 0)
+            {
+                return (m_retVal = MTRV_INPUTCANNOTBEOPENED);
+            }
+
 #endif
-			}
-			m_nTempBufferLen = 0;
-			m_retVal = MTRV_OK;
-		}
+            m_timeOut = 0;   // No timeout when using file input
+            m_fileOpen = true;
+            return (m_retVal = MTRV_OK);
+
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // isPortOpen
+        //
+        // Return if serial port is open or not
+        //
+        bool CXsensMTiModule::isPortOpen()
+        {
+            return m_portOpen;
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // isFileOpen
+        //
+        // Return if serial port is open or not
+        //
+        bool CXsensMTiModule::isFileOpen()
+        {
+            return m_fileOpen;
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // readData
+        //
+        // Reads bytes from serial port or file
+        //
+        // Input
+        //   msgBuffer      : pointer to buffer in which next string will be stored
+        //   nBytesToRead   : number of buffer bytes to read from serial port
+        //   retval         : return value, either MTRV_OK, MTRV_ENDOFFILE or MTRV_NOINPUTINITIALIZED
+        //
+        // Output
+        //   number of bytes actually read
+        int CXsensMTiModule::readData(unsigned char* msgBuffer, const int nBytesToRead)
+        {
+            //if(!m_fileOpen && !m_portOpen)
+            if (!(m_portOpen || m_fileOpen))
+            {
+                m_retVal = MTRV_NOINPUTINITIALIZED;
+                return 0;
+            }
 
-////////////////////////////////////////////////////////////////////
-// escape
-//
-// Directs a COM port to perform an extended function
-//
-// Input
-//	function	: Windows define. Can be one of following:
-//				  CLRDTR, CLRRTS, SETDTR, SETRTS, SETXOFF, SETXON, SETBREAK, CLRBREAK
-		void CXsensMTiModule::escape(unsigned long /*function*/)
-		{
 #ifdef WIN32
-			EscapeCommFunction(m_handle, function);
+            DWORD nBytesRead;
+            BOOL retval = ReadFile(m_handle, msgBuffer, nBytesToRead, &nBytesRead, NULL);
+
+            if (retval && nBytesRead == 0 && m_fileOpen)
+            {
+                m_retVal = MTRV_ENDOFFILE;
+            }
+            else
+            {
+                m_retVal = MTRV_OK;
+            }
+
+            return nBytesRead;
 #else
+            const int nBytesRead = read(m_handle, msgBuffer, nBytesToRead);
+
+            m_retVal = MTRV_OK;
+
+            if (nBytesRead)
+            {
+                return nBytesRead;
+            }
+            else if (m_fileOpen)
+            {
+                m_retVal = MTRV_ENDOFFILE;
+            }
+
+            return nBytesRead;
+            /*
+             if (nBytesRead == 0 && m_fileOpen)
+             {
+             nBytesRead = 0;
+             m_retVal = MTRV_ENDOFFILE;
+             }
+             else
+             m_retVal = MTRV_OK;
+             return nBytesRead;*/
+
+            // In Linux it is sometimes better to read per byte instead of a block of bytes at once
+            // Use this block if experiencing problems with the above code
+            /*
+             int j = 0; // Index in buffer for read data
+             int k = 0; // Timeout factor
+             int nRead = 0; // Bytes read from port, return by read function
+
+             do {
+             nRead = read(m_handle, &msgBuffer[j], 1);
+             if (nRead == 1) {  // Byte read
+             k = 0;
+             j++;
+             }
+             else {
+             k++;
+             }
+
+             if (k == 3)    { // Timeout, too long no data read from port
+             return nRead;
+             }
+             }
+             while (j < nBytesToRead);
+
+             return j;
+             */
 #endif
-		}
-
-////////////////////////////////////////////////////////////////////
-// setPortQueueSize
-//
-// Set input and output buffer size of serial port
-//
-		void CXsensMTiModule::setPortQueueSize(const unsigned long /*inqueueSize  = 4096 */, const unsigned long /*outqueueSize  = 1024 */)
-		{
-			if (m_portOpen)
-			{
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // writeData
+        //
+        // Writes bytes to serial port (to do: file)
+        //
+        // Input
+        //   msgBuffer      : a pointer to a char buffer containing
+        //                    the characters to be written to serial port
+        //   nBytesToWrite  : number of buffer bytes to write to serial port
+        //
+        // Output
+        //   number of bytes actually written
+        //
+        // The MTComm return value is != MTRV_OK if serial port is closed
+        int CXsensMTiModule::writeData(const unsigned char* msgBuffer, const int nBytesToWrite)
+        {
+            if (!m_fileOpen && !m_portOpen)
+            {
+                m_retVal = MTRV_NOINPUTINITIALIZED;
+                return 0;
+            }
+
+            m_retVal = MTRV_OK;
 #ifdef WIN32
-				SetupComm(m_handle,inqueueSize,outqueueSize);	// Set queue size
+            DWORD nBytesWritten;
+            WriteFile(m_handle, msgBuffer, nBytesToWrite, &nBytesWritten, NULL);
+            return nBytesWritten;
 #else
-				// Not yet implemented
+            return write(m_handle, msgBuffer, nBytesToWrite);
 #endif
-			}
-			m_retVal = MTRV_OK;
-		}
-
-////////////////////////////////////////////////////////////////////
-// setFilePos
-//
-// Sets the current position of the file pointer for file input
-//
-// Input
-//	 relPos		: 32-bit value specifying the relative move in bytes
-//				    origin is specified in moveMethod
-//	 moveMethod	: FILEPOS_BEGIN, FILEPOS_CURRENT or FILEPOS_END
-// Output
-//	
-//   returns MTRV_OK if file pointer is successfully set
-//
-		short CXsensMTiModule::setFilePos(long relPos, unsigned long moveMethod)
-		{
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // flush
+        //
+        // Remove any 'old' data in COM port buffer and flushes internal
+        //   temporary buffer
+        //
+        void CXsensMTiModule::flush()
+        {
+            if (m_portOpen)
+            {
 #ifdef WIN32
-			if (m_fileOpen)
-			{
-				if(SetFilePointer(m_handle, relPos, NULL, moveMethod) != INVALID_SET_FILE_POINTER)
-				{
-					return (m_retVal = MTRV_OK);
-				}
-			}
+                // Remove any 'old' data in buffer
+                PurgeComm(m_handle, PURGE_TXCLEAR | PURGE_RXCLEAR);
 #else
-			if (m_fileOpen)
-			{
-				if (lseek(m_handle,relPos,moveMethod) != -1)
-				{
-					return (m_retVal = MTRV_OK);
-				}
-			}
+                tcflush(m_handle, TCIOFLUSH);
 #endif
-			return (m_retVal = MTRV_NOTSUCCESSFUL);
-		}
-
-////////////////////////////////////////////////////////////////////
-// getFileSize
-//
-// Retrieves the file size of the opened file
-//
-// Input
-// Output
-//	 fileSize  : Number of bytes of the current file
-//	
-//   returns MTRV_OK if successful
-//
-		short CXsensMTiModule::getFileSize(unsigned long &fileSize)
-		{
+            }
+
+            m_nTempBufferLen = 0;
+            m_retVal = MTRV_OK;
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // escape
+        //
+        // Directs a COM port to perform an extended function
+        //
+        // Input
+        //  function    : Windows define. Can be one of following:
+        //                CLRDTR, CLRRTS, SETDTR, SETRTS, SETXOFF, SETXON, SETBREAK, CLRBREAK
+        void CXsensMTiModule::escape(unsigned long /*function*/)
+        {
 #ifdef WIN32
-			if (m_fileOpen)
-			{
-				if ((fileSize = GetFileSize(m_handle, NULL)) != INVALID_FILE_SIZE)
-				{
-					return (m_retVal = MTRV_OK);
-				}
-			}
+            EscapeCommFunction(m_handle, function);
 #else
-			if (m_fileOpen)
-			{
-				struct stat buf;
-				if (fstat(m_handle,&buf) == 0)
-				{
-					fileSize = buf.st_size;
-					return (m_retVal = MTRV_OK);
-				}
-			}
 #endif
-			return (m_retVal = MTRV_NOTSUCCESSFUL);
-		}
-
-////////////////////////////////////////////////////////////////////
-// close
-//
-// Closes handle of file or serial port
-//
-		short CXsensMTiModule::close()
-		{
-			if (m_portOpen || m_fileOpen)
-			{
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // setPortQueueSize
+        //
+        // Set input and output buffer size of serial port
+        //
+        void CXsensMTiModule::setPortQueueSize(const unsigned long /*inqueueSize  = 4096 */, const unsigned long /*outqueueSize  = 1024 */)
+        {
+            if (m_portOpen)
+            {
 #ifdef WIN32
-				if (m_portOpen)
-				{		// Because of USB-serial driver bug
-					flush();
-				}
-				CloseHandle(m_handle);
+                SetupComm(m_handle, inqueueSize, outqueueSize); // Set queue size
 #else
-				::close(m_handle);
+                // Not yet implemented
 #endif
-			}
-			m_fileOpen = m_portOpen = false;
-			m_timeOut = TO_DEFAULT;   // Restore timeout value (file input)
-			m_clkEnd = 0;
-			m_nTempBufferLen = 0;
-			m_deviceError = 0;   // No error
-			for(int i = 0 ; i < MAXDEVICES + 1 ; i++)
-			{
-				m_storedOutputMode[i] = INVALIDSETTINGVALUE;
-				m_storedOutputSettings[i] = INVALIDSETTINGVALUE;
-				m_storedDataLength[i] = 0;
-			}
-			return (m_retVal = MTRV_OK);
-		}
-
-////////////////////////////////////////////////////////////////////
-// readMessage
-//
-// Reads the next message from serial port buffer or file. 
-// To be read within current time out period
-//
-// Input
-// Output
-//	 mid		: MessageID of message received
-//	 data	    : array pointer to data bytes (no header)
-//	 dataLen    : number of data bytes read
-//   bid		: BID or address of message read (optional)
-//	
-//   returns MTRV_OK if a message has been read else <>MTRV_OK
-//
-// Remarks
-//   allocate enough memory for message buffer
-//   use setTimeOut for different timeout value
-		short CXsensMTiModule::readMessage(unsigned char &mid, unsigned char data[], short &dataLen, unsigned char *bid)
-		{
-			unsigned char buffer[MAXMSGLEN ];
-			short msgLen;
-
-			if (!(m_fileOpen || m_portOpen))
-			{
-				return (m_retVal = MTRV_NOINPUTINITIALIZED);
-			}
-
-			if (readMessageRaw(buffer,&msgLen) == MTRV_OK)
-			{
-				// Message read
-				mid = buffer[IND_MID];
-				if (bid != NULL)
-				{
-					*bid = buffer[IND_BID];
-				}
-				if (buffer[IND_LEN] != EXTLENCODE)
-				{
-					dataLen = buffer[IND_LEN];
-					memcpy(data,&buffer[IND_DATA0],dataLen);
-				}
-				else
-				{
-					dataLen = buffer[IND_LENEXTH] * 256 + buffer[IND_LENEXTL];
-					memcpy(data,&buffer[IND_DATAEXT0],dataLen);
-				}
-			}
-			return m_retVal;
-		}
-
-////////////////////////////////////////////////////////////////////
-// readDataMessage
-//
-// Read a MTData or XMData message from serial port (using TimeOut val)
-//
-// Input
-//   data		: pointer to buffer in which the DATA field of MTData/XMData is stored
-//   dataLen	: number of bytes in buffer (= number bytes in DATA field)
-// Output
-//   returns MTRV_OK if MTData / XMData message has been read else <>MTRV_OK
-//
-// Remarks
-//   allocate enough memory for data buffer
-//   use setTimeOut for different timeout value
-		short CXsensMTiModule::readDataMessage(unsigned char data[], short &dataLen)
-		{
-			if (!(m_portOpen || m_fileOpen))
-				return (m_retVal = MTRV_NOINPUTINITIALIZED);
-
-			unsigned char buffer[MAXMSGLEN ];
-			short buflen;
-
-			if (readMessageRaw(buffer,&buflen) == MTRV_OK)
-			{
-				if (buffer[IND_MID] == MID_MTDATA)
-				{	// MID_XMDATA is same
-					if (buffer[IND_LEN] != EXTLENCODE)
-					{
-						dataLen = buffer[IND_LEN];
-						memcpy(data,&buffer[IND_DATA0],dataLen);
-					}
-					else
-					{
-						dataLen = buffer[IND_LENEXTH] * 256 + buffer[IND_LENEXTL];
-						memcpy(data,&buffer[IND_DATAEXT0],dataLen);
-					}
-					return (m_retVal = MTRV_OK);
-				}
-				else if (buffer[IND_MID] == MID_ERROR)
-				{
-					m_deviceError = buffer[IND_DATA0];
-					return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
-				}
-			}
-			return m_retVal;
-		}
-
-////////////////////////////////////////////////////////////////////
-// readMessageRaw
-//
-// Read a message from serial port for a certain period
-//
-// Input
-//   msgBuffer		: pointer to buffer in which next msg will be stored
-//   msgBufferLength: integer to number of bytes written in buffer (header + data + chksum)
-// Output
-//   returns MTRV_OK if a message has been read else <>MTRV_OK
-//
-// Remarks
-//   allocate enough memory for message buffer
-//   use setTimeOut for different timeout value
-		short CXsensMTiModule::readMessageRaw(unsigned char *msgBuffer, short *msgBufferLength)
-		{
-			int state = 0;
-			int nBytesToRead = 1;
-			int nBytesRead = 0;
-			int nOffset = 0;
-			int nMsgDataLen = 0;
-			int nMsgLen;
-			unsigned char chCheckSum;
-			bool Synced = false;
-
-			if (!(m_portOpen || m_fileOpen))
-				return (m_retVal = MTRV_NOINPUTINITIALIZED);
-
-			// Copy previous read bytes if available
-			if (m_nTempBufferLen > 0)
-			{
-				memcpy(msgBuffer,m_tempBuffer,m_nTempBufferLen);
-				nBytesRead = m_nTempBufferLen;
-				m_nTempBufferLen = 0;
-			}
-			clock_t clkStart = clockms();		// Get current processor time
-			clock_t clkEnd = m_clkEnd;		// check if the end timer is already set
-			if (clkEnd == 0)
-				clkEnd = clkStart + m_timeOut;
-
-			while(true)
-			{
-				do
-				{
-					// First check if we already have some bytes read
-					if (nBytesRead > 0 && nBytesToRead > 0)
-					{
-						if (nBytesToRead > nBytesRead)
-						{
-							nOffset += nBytesRead;
-							nBytesToRead -= nBytesRead;
-							nBytesRead = 0;
-						}
-						else
-						{
-							nOffset += nBytesToRead;
-							nBytesRead -= nBytesToRead;
-							nBytesToRead = 0;
-						}
-					}
-
-					// Check if serial port buffer must be read
-					if (nBytesToRead > 0)
-					{
-						nBytesRead = readData(msgBuffer + nOffset,nBytesToRead);
-						if (m_retVal == MTRV_ENDOFFILE)
-							return (m_retVal = MTRV_ENDOFFILE);
-						nOffset += nBytesRead;
-						nBytesToRead -= nBytesRead;
-						nBytesRead = 0;
-					}
-
-					if (!nBytesToRead)
-					{
-						switch(state)
-						{
-							case 0:					// Check preamble
-								if (msgBuffer[IND_PREAMBLE] == PREAMBLE)
-								{
-									state++;
-									nBytesToRead = 3;
-								}
-								else
-								{
-									nOffset = 0;
-									nBytesToRead = 1;
-								}
-							break;
-							case 1:					// Check ADDR, MID, LEN
-								if (msgBuffer[IND_LEN] != 0xFF)
-								{
-									state = 3;
-									nBytesToRead = (nMsgDataLen = msgBuffer[IND_LEN]) + 1;   // Read LEN + 1 (chksum)
-								}
-								else
-								{
-									state = 2;
-									nBytesToRead = 2;	// Read extended length
-								}
-							break;
-							case 2:
-								state = 3;
-								nBytesToRead = (nMsgDataLen = msgBuffer[IND_LENEXTH] * 256 + msgBuffer[IND_LENEXTL]) + 1;	// Read LENEXT + CS
-								if (nMsgDataLen > MAXMSGLEN - LEN_MSGEXTHEADERCS)
-								{
-									// Not synced - check for preamble in the bytes read
-									for(int i = 1 ; i < LEN_MSGEXTHEADER ; i++)
-										if (msgBuffer[i] == PREAMBLE)
-										{
-											// Found a maybe preamble - 'fill buffer'
-											nBytesRead = LEN_MSGEXTHEADER - i;
-											memmove(msgBuffer,msgBuffer + i,nBytesRead);
-											break;
-										}
-									Synced = false;
-									nOffset = 0;
-									state = 0;
-									nBytesToRead = 1;			// Start looking for preamble
-								}
-							break;
-							case 3:					// Check msg
-								chCheckSum = 0;
-								nMsgLen = nMsgDataLen + 5 + (msgBuffer[IND_LEN] == 0xFF ? 2 : 0);
-
-								for(int i = 1 ; i < nMsgLen ; i++)
-									chCheckSum += msgBuffer[i];
-
-								if (chCheckSum == 0)
-								{				// Checksum ok?
-									if (nBytesRead > 0)
-									{			// Store bytes if read too much
-										memcpy(m_tempBuffer,msgBuffer + nMsgLen,nBytesRead);
-										m_nTempBufferLen = nBytesRead;
-									}
-									*msgBufferLength = nMsgLen;
-									Synced = true;
-									return (m_retVal = MTRV_OK);
-								}
-								else
-								{
-									if (!Synced)
-										for(int i = 1 ; i < nMsgLen ; i++)			// Not synced - maybe recheck for preamble in this incorrect message
-											if (msgBuffer[i] == PREAMBLE)
-											{
-												// Found a maybe preamble - 'fill buffer'
-												nBytesRead = nMsgLen - i;
-												memmove(msgBuffer,msgBuffer + i,nBytesRead);
-												break;
-											}
-									Synced = false;
-									nOffset = 0;
-									state = 0;
-									nBytesToRead = 1;			// Start looking for preamble
-								}
-							break;
-						}
-					}
-				}
-				while((clkEnd >= clockms()) || m_timeOut == 0 || nBytesRead != 0);
-
-				// Check if pending message has a valid message
-				if (state > 0)
-				{
-					int i;
-					// Search for preamble
-					for(i = 1; i < nOffset ; i++)
-						if (msgBuffer[i] == PREAMBLE)
-						{
-							// Found a maybe preamble - 'fill buffer'
-							nBytesRead = nOffset - i - 1;			// no preamble
-							memmove(msgBuffer + 1,msgBuffer + i + 1,nBytesRead);
-							break;
-						}
-					if (i < nOffset)
-					{
-						// Found preamble in message - recheck
-						nOffset = 1;
-						state = 1;
-						nBytesToRead = 3;			// Start looking for preamble
-						continue;
-					}
-				}
-				break;
-			}
-
-			return (m_retVal = MTRV_TIMEOUT);
-		}
-
-////////////////////////////////////////////////////////////////////
-// writeMessage (optional: integer value)
-//
-// Sends a message and in case of an serial port interface it checks
-//   if the return message (ack, error or timeout). See return value
-//   In case an file is opened the functions returns directly after
-//   'sending' the message
-//
-//   Use this function for GotoConfig, Reset, ResetOrientation etc
-//
-// Input
-//	 mid		  : MessageID of message to send
-//	 dataValue	  : A integer value that will be included into the data message field
-//				    can be a 1,2 or 4 bytes values
-//	 dataValueLen : Size of dataValue in bytes
-//   bid		  : BID or address to use in message to send (default = 0xFF)
-//
-// Return value
-//   = MTRV_OK if an Ack message received / or data successfully written to file
-//	 = MTRV_RECVERRORMSG if an error message received
-//	 = MTRV_TIMEOUT if timeout occurred
-//   = MTRV_NOINPUTINITIALIZED
-//
-		short CXsensMTiModule::writeMessage(const unsigned char mid, const unsigned long dataValue, const unsigned char dataValueLen, const unsigned char bid)
-		{
-			unsigned char buffer[MAXMSGLEN ];
-			short msgLen;
-
-			if (!(m_fileOpen || m_portOpen))
-			{
-				return (m_retVal = MTRV_NOINPUTINITIALIZED);
-			}
-
-			buffer[IND_PREAMBLE] = PREAMBLE;
-			buffer[IND_BID] = bid;
-			buffer[IND_MID] = mid;
-			buffer[IND_LEN] = dataValueLen;
-			if (dataValueLen)
-				swapEndian((const unsigned char *) &dataValue,&buffer[IND_DATA0],dataValueLen);
-			calcChecksum(buffer,LEN_MSGHEADER + dataValueLen);
-
-			// Send message
-			writeData(buffer,LEN_MSGHEADERCS + dataValueLen);
-
-			// Return if file opened
-			if (m_fileOpen)
-			{
-				return (m_retVal = MTRV_OK);
-			}
-
-			// Keep reading until an Ack or Error message is received (or timeout)
-			clock_t clkStart , clkOld;
-			bool msgRead = false;
-
-			clkStart = clockms();			// Get current processor time
-			clkOld = m_clkEnd;
-			if (clkOld == 0)
-				m_clkEnd = m_timeOut + clkStart;
-
-			while(m_clkEnd >= clockms() || (m_timeOut == 0))
-			{
-				if (readMessageRaw(buffer,&msgLen) == MTRV_OK)
-				{
-					// Message received
-					msgRead = true;
-					if (buffer[IND_MID] == (mid + 1))
-					{
-						m_clkEnd = clkOld;
-						return (m_retVal = MTRV_OK);				// Acknowledge received
-					}
-					else if (buffer[IND_MID] == MID_ERROR)
-					{
-						m_deviceError = buffer[IND_DATA0];
-						m_clkEnd = clkOld;
-						return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
-					}
-				}
-			}
-
-			m_clkEnd = clkOld;
-			if (msgRead)
-				return (m_retVal = MTRV_TIMEOUT);
-			else
-				return (m_retVal = MTRV_TIMEOUTNODATA);
-		}
-
-////////////////////////////////////////////////////////////////////
-// writeMessage (data array)
-//
-// Sends a message and in case of an serial port interface it checks
-//   if the return message (ack, error or timeout). See return value
-//   In case an file is opened the functions returns directly after
-//   'sending' the message
-//
-// Input
-//	 mid		: MessageID of message to send
-//	 data	    : array pointer to data bytes
-//	 dataLen    : number of bytes to include in message
-//   bid		: BID or address to use in message to send (default = 0xFF)
-//
-// Output
-//   = MTRV_OK if an Ack message received
-//	 = MTRV_RECVERRORMSG if an error message received
-//	 = MTRV_TIMEOUT if timeout occurred
-//   = MTRV_NOINPUTINITIALIZED
-//
-		short CXsensMTiModule::writeMessage(const unsigned char mid, const unsigned char data[], const unsigned short &dataLen, const unsigned char bid)
-		{
-			unsigned char buffer[MAXMSGLEN ];
-			short msgLen;
-			short headerLength;
-
-			if (!(m_fileOpen || m_portOpen))
-			{
-				return (m_retVal = MTRV_NOINPUTINITIALIZED);
-			}
-
-			// Build message to send
-			buffer[IND_PREAMBLE] = PREAMBLE;
-			buffer[IND_BID] = bid;
-			buffer[IND_MID] = mid;
-
-			if (dataLen < EXTLENCODE)
-			{
-				buffer[IND_LEN] = (unsigned char) dataLen;
-				headerLength = LEN_MSGHEADER;
-			}
-			else
-			{
-				buffer[IND_LEN] = EXTLENCODE;
-				buffer[IND_LENEXTH] = (unsigned char) (dataLen >> 8);
-				buffer[IND_LENEXTL] = (unsigned char) (dataLen & 0x00FF);
-				headerLength = LEN_MSGEXTHEADER;
-			}
-			memcpy(&buffer[headerLength],data,dataLen);
-			calcChecksum(buffer,headerLength + dataLen);
-
-			// Send message
-			writeData(buffer,headerLength + dataLen + LEN_CHECKSUM);
-
-			// Return if file opened
-			if (m_fileOpen)
-			{
-				return (m_retVal = MTRV_OK);
-			}
-
-			// Keep reading until an Ack or Error message is received (or timeout)
-			bool msgRead = false;
-			clock_t clkStart , clkOld;
-
-			clkStart = clockms();   // Get current processor time
-			clkOld = m_clkEnd;
-			if (clkOld == 0)
-				m_clkEnd = m_timeOut + clkStart;
-
-			while(m_clkEnd >= clockms() || (m_timeOut == 0))
-			{
-				if (readMessageRaw(buffer,&msgLen) == MTRV_OK)
-				{
-					// Message received
-					msgRead = true;
-					if (buffer[IND_MID] == (mid + 1))
-					{
-						m_clkEnd = clkOld;
-						return (m_retVal = MTRV_OK);				// Acknowledge received
-					}
-					else if (buffer[IND_MID] == MID_ERROR)
-					{
-						m_deviceError = buffer[IND_DATA0];
-						m_clkEnd = clkOld;
-						return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
-					}
-				}
-			}
-
-			m_clkEnd = clkOld;
-			if (msgRead)
-				return (m_retVal = MTRV_TIMEOUT);
-			else
-				return (m_retVal = MTRV_TIMEOUTNODATA);
-		}
-
-////////////////////////////////////////////////////////////////////
-// waitForMessage
-//
-// Read messages from serial port or file using the current timeout period
-//  until the received message is equal to a specific message identifier 
-// By default the timeout period by file input is set to infinity (= until
-//  end of file is reached)
-//
-// Input/Output
-//   mid			: message identifier of message that should be returned
-//   data			: pointer to buffer in which the data of the requested msg will be stored
-//   dataLen		: integer to number of data bytes
-//	 bid			: optional, pointer which holds the bid of the returned message
-// Output
-//   returns MTRV_OK if the message has been read else != MTRV_OK
-//
-// Remarks
-//   allocate enough memory for data message buffer
-//   use setTimeOut for different timeout value
-		short CXsensMTiModule::waitForMessage(const unsigned char mid, unsigned char data[], short *dataLen, unsigned char *bid)
-		{
-			unsigned char buffer[MAXMSGLEN ];
-			short buflen;
-
-			clock_t clkStart , clkOld;
-
-			if (!(m_fileOpen || m_portOpen))
-			{
-				return (m_retVal = MTRV_NOINPUTINITIALIZED);
-			}
-
-			clkStart = clockms();		// Get current processor time
-			clkOld = m_clkEnd;
-			if (clkOld == 0)
-				m_clkEnd = m_timeOut + clkStart;
-
-			while(m_clkEnd >= clockms() || (m_timeOut == 0))
-			{
-				if (readMessageRaw(buffer,&buflen) == MTRV_OK)
-				{
-					if (buffer[IND_MID] == mid)
-					{
-						if (bid != NULL)
-						{
-							*bid = buffer[IND_BID];
-						}
-						if (data != NULL && dataLen != NULL)
-						{
-							if (buffer[IND_LEN] != EXTLENCODE)
-							{
-								*dataLen = buffer[IND_LEN];
-								memcpy(data,&buffer[IND_DATA0],*dataLen);
-							}
-							else
-							{
-								*dataLen = buffer[IND_LENEXTH] * 256 + buffer[IND_LENEXTL];
-								memcpy(data,&buffer[IND_DATAEXT0],*dataLen);
-							}
-						}
-						else if (dataLen != NULL)
-							dataLen = 0;
-						m_clkEnd = clkOld;
-						return (m_retVal = MTRV_OK);
-					}
-				}
-				else if (m_retVal == MTRV_ENDOFFILE)
-				{
-					m_clkEnd = clkOld;
-					return (m_retVal = MTRV_ENDOFFILE);
-				}
-			}
-
-			m_clkEnd = clkOld;
-			return (m_retVal = MTRV_TIMEOUT);
-		}
-
-////////////////////////////////////////////////////////////////////
-// reqSetting (integer & no param variant)
-//
-// Request a integer setting from the device. This setting
-// can be an unsigned 1,2 or 4 bytes setting. Only valid
-// for serial port connections
-//
-// Input
-//	 mid		: Message ID of message to send
-//   bid		: Bus ID of message to send (def 0xFF)
-//
-// Output
-//   = MTRV_OK if an Ack message is received
-//	 = MTRV_RECVERRORMSG if an error message is received
-//	 = MTRV_TIMEOUT if timeout occurred
-//
-//	 value contains the integer value of the data field of the ack message
-//
-		short CXsensMTiModule::reqSetting(const unsigned char mid, unsigned long &value, const unsigned char bid)
-		{
-			unsigned char buffer[MAXMSGLEN ];
-			short msgLen;
-
-			if (m_fileOpen)
-			{
-				return (m_retVal = MTRV_INVALIDFORFILEINPUT);
-			}
-			if (!m_portOpen)
-			{
-				return (m_retVal = MTRV_NOINPUTINITIALIZED);
-			}
-			buffer[IND_PREAMBLE] = PREAMBLE;
-			buffer[IND_BID] = bid;
-			buffer[IND_MID] = mid;
-			buffer[IND_LEN] = 0;
-			calcChecksum(buffer,LEN_MSGHEADER + buffer[IND_LEN]);
-
-			// Send message
-			writeData(buffer,LEN_MSGHEADERCS + buffer[IND_LEN]);
-
-			// Read next message or else timeout
-			if (readMessageRaw(buffer,&msgLen) == MTRV_OK)
-			{
-				// Message received
-				if (buffer[IND_MID] == (mid + 1))
-				{
-					// Acknowledge received
-					value = 0;
-					swapEndian(&buffer[IND_DATA0],(unsigned char *) &value,buffer[IND_LEN]);
-					return (m_retVal = MTRV_OK);
-				}
-				else if (buffer[IND_MID] == MID_ERROR)
-				{
-					m_deviceError = buffer[IND_DATA0];
-					return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
-				}
-				else
-				{
-					return (m_retVal = MTRV_UNEXPECTEDMSG);   // Unexpected message
-				}
-			}
-			return m_retVal;
-		}
-
-////////////////////////////////////////////////////////////////////
-// reqSetting (integer & param variant)
-//
-// Request a integer setting from the device. This setting
-// can be an unsigned 1,2 or 4 bytes setting. Only valid
-// for serial port connections.
-//
-// Input
-//	 mid		: Message ID of message to send
-//	 param		: For messages that need a parameter
-//   bid		: Bus ID of message to send (def 0xFF)
-//
-// Output
-//   = MTRV_OK if an Ack message is received
-//	 = MTRV_RECVERRORMSG if an error message is received
-//	 = MTRV_TIMEOUT if timeout occurred
-//
-//	 value contains the integer value of the data field of the ack message
-//
-		short CXsensMTiModule::reqSetting(const unsigned char mid, const unsigned char param, unsigned long &value, const unsigned char bid)
-		{
-			unsigned char buffer[MAXMSGLEN ];
-			short msgLen;
-
-			if (m_fileOpen)
-			{
-				return (m_retVal = MTRV_INVALIDFORFILEINPUT);
-			}
-			if (!m_portOpen)
-			{
-				return (m_retVal = MTRV_NOINPUTINITIALIZED);
-			}
-			buffer[IND_PREAMBLE] = PREAMBLE;
-			buffer[IND_BID] = bid;
-			buffer[IND_MID] = mid;
-			if (param != 0xFF)
-			{
-				buffer[IND_LEN] = 1;
-				buffer[IND_DATA0] = param;
-			}
-			else
-			{
-				buffer[IND_LEN] = 0;
-			}
-			calcChecksum(buffer,LEN_MSGHEADER + buffer[IND_LEN]);
-
-			// Send message
-			writeData(buffer,LEN_MSGHEADERCS + buffer[IND_LEN]);
-
-			// Read next message or else timeout
-			if (readMessageRaw(buffer,&msgLen) == MTRV_OK)
-			{
-				// Message received
-				if (buffer[IND_MID] == (mid + 1))
-				{
-					// Acknowledge received
-					value = 0;
-					if (param == 0xFF)
-					{
-						swapEndian(&buffer[IND_DATA0],(unsigned char *) &value,buffer[IND_LEN]);
-					}
-					else
-					{
-						swapEndian(&buffer[IND_DATA0] + 1,(unsigned char *) &value,buffer[IND_LEN] - 1);
-					}
-					return (m_retVal = MTRV_OK);
-				}
-				else if (buffer[IND_MID] == MID_ERROR)
-				{
-					m_deviceError = buffer[IND_DATA0];
-					return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
-				}
-				else
-				{
-					return (m_retVal = MTRV_UNEXPECTEDMSG);   // Unexpected message
-				}
-			}
-			return m_retVal;
-		}
-
-////////////////////////////////////////////////////////////////////
-// reqSetting (float & no param variant)
-//
-// Request a float setting from the device. Only valid
-// for serial port connections.
-//
-// Input
-//	 mid		: Message ID of message to send
-//   bid		: Bus ID of message to send (def 0xFF)
-//
-// Output
-//   = MTRV_OK if an Ack message is received
-//	 = MTRV_RECVERRORMSG if an error message is received
-//	 = MTRV_TIMEOUT if timeout occurred
-//
-//	 value contains the float value of the acknowledge data field
-//
-		short CXsensMTiModule::reqSetting(const unsigned char mid, float &value, const unsigned char bid)
-		{
-			unsigned char buffer[MAXMSGLEN ];
-			short msgLen;
-
-			if (m_fileOpen)
-			{
-				return (m_retVal = MTRV_INVALIDFORFILEINPUT);
-			}
-			if (!m_portOpen)
-			{
-				return (m_retVal = MTRV_NOINPUTINITIALIZED);
-			}
-			buffer[IND_PREAMBLE] = PREAMBLE;
-			buffer[IND_BID] = bid;
-			buffer[IND_MID] = mid;
-			buffer[IND_LEN] = 0;
-			calcChecksum(buffer,LEN_MSGHEADER + buffer[IND_LEN]);
-
-			// Send message
-			writeData(buffer,LEN_MSGHEADERCS + buffer[IND_LEN]);
-
-			// Read next message or else timeout
-			if (readMessageRaw(buffer,&msgLen) == MTRV_OK)
-			{
-				// Message received
-				if (buffer[IND_MID] == (mid + 1))
-				{
-					// Acknowledge received
-					value = 0;
-					swapEndian(&buffer[IND_DATA0],(unsigned char *) &value,buffer[IND_LEN]);
-					return (m_retVal = MTRV_OK);
-				}
-				else if (buffer[IND_MID] == MID_ERROR)
-				{
-					m_deviceError = buffer[IND_DATA0];
-					return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
-				}
-				else
-				{
-					return (m_retVal = MTRV_UNEXPECTEDMSG);   // Unexpected message
-				}
-			}
-			return m_retVal;
-		}
-
-////////////////////////////////////////////////////////////////////
-// reqSetting (float & param variant)
-//
-// Request a float setting from the device. Only valid
-// for serial port connections.
-//
-// Input
-//	 mid		: Message ID of message to send
-//	 param		: For messages that need a parameter (optional)
-//   bid		: Bus ID of message to send (def 0xFF)
-//
-// Output
-//   = MTRV_OK if an Ack message is received
-//	 = MTRV_RECVERRORMSG if an error message is received
-//	 = MTRV_TIMEOUT if timeout occurred
-//
-//	 value contains the float value of the acknowledge data field
-//
-		short CXsensMTiModule::reqSetting(const unsigned char mid, const unsigned char param, float &value, const unsigned char bid)
-		{
-			unsigned char buffer[MAXMSGLEN ];
-			short msgLen;
-
-			if (m_fileOpen)
-			{
-				return (m_retVal = MTRV_INVALIDFORFILEINPUT);
-			}
-			if (!m_portOpen)
-			{
-				return (m_retVal = MTRV_NOINPUTINITIALIZED);
-			}
-			buffer[IND_PREAMBLE] = PREAMBLE;
-			buffer[IND_BID] = bid;
-			buffer[IND_MID] = mid;
-			if (param != 0xFF)
-			{
-				buffer[IND_LEN] = 1;
-				buffer[IND_DATA0] = param;
-			}
-			else
-			{
-				buffer[IND_LEN] = 0;
-			}
-			calcChecksum(buffer,LEN_MSGHEADER + buffer[IND_LEN]);
-
-			// Send message
-			writeData(buffer,LEN_MSGHEADERCS + buffer[IND_LEN]);
-
-			// Read next message or else timeout
-			if (readMessageRaw(buffer,&msgLen) == MTRV_OK)
-			{
-				// Message received
-				if (buffer[IND_MID] == (mid + 1))
-				{
-					// Acknowledge received
-					value = 0;
-					if (param == 0xFF)
-					{
-						swapEndian(&buffer[IND_DATA0],(unsigned char *) &value,buffer[IND_LEN]);
-					}
-					else
-					{
-						swapEndian(&buffer[IND_DATA0] + 1,(unsigned char *) &value,buffer[IND_LEN] - 1);
-					}
-					return (m_retVal = MTRV_OK);
-				}
-				else if (buffer[IND_MID] == MID_ERROR)
-				{
-					m_deviceError = buffer[IND_DATA0];
-					return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
-				}
-				else
-				{
-					return (m_retVal = MTRV_UNEXPECTEDMSG);   // Unexpected message
-				}
-			}
-			return m_retVal;
-		}
-
-////////////////////////////////////////////////////////////////////
-// reqSetting (byte array & no param variant)
-//
-// Send a message to the device and the data of acknowledge message
-// will be returned. Only valid for serial port connections
-//
-// Input
-//	 mid		: Message ID of message to send
-//   bid		: Bus ID of message to send (def 0xFF)
-//	 
-// Output
-//   = MTRV_OK if an Ack message is received
-//	 = MTRV_RECVERRORMSG if an error message is received
-//	 = MTRV_TIMEOUT if timeout occurred
-//
-//	 data[] contains the data of the acknowledge message
-//	 dataLen contains the number bytes returned
-//
-		short CXsensMTiModule::reqSetting(const unsigned char mid, unsigned char data[], short &dataLen, const unsigned char bid)
-		{
-			unsigned char buffer[MAXMSGLEN ];
-			short msgLen;
-
-			if (m_fileOpen)
-			{
-				return (m_retVal = MTRV_INVALIDFORFILEINPUT);
-			}
-			if (!m_portOpen)
-			{
-				return (m_retVal = MTRV_NOINPUTINITIALIZED);
-			}
-			buffer[IND_PREAMBLE] = PREAMBLE;
-			buffer[IND_BID] = bid;
-			buffer[IND_MID] = mid;
-			buffer[IND_LEN] = 0;
-			calcChecksum(buffer,LEN_MSGHEADER + buffer[IND_LEN]);
-
-			// Send message
-			writeData(buffer,LEN_MSGHEADERCS + buffer[IND_LEN]);
-
-			dataLen = 0;
-			// Read next message or else timeout
-			if (readMessageRaw(buffer,&msgLen) == MTRV_OK)
-			{
-				// Message received
-				if (buffer[IND_MID] == (mid + 1))
-				{
-					// Acknowledge received
-					if (buffer[IND_LEN] != EXTLENCODE)
-					{
-						dataLen = buffer[IND_LEN];
-						memcpy(data,&buffer[IND_DATA0],dataLen);
-					}
-					else
-					{
-						dataLen = buffer[IND_LENEXTH] * 256 + buffer[IND_LENEXTL];
-						memcpy(data,&buffer[IND_DATAEXT0],dataLen);
-					}
-					return (m_retVal = MTRV_OK);
-				}
-				else if (buffer[IND_MID] == MID_ERROR)
-				{
-					m_deviceError = buffer[IND_DATA0];
-					return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
-				}
-				else
-				{
-					return (m_retVal = MTRV_UNEXPECTEDMSG);   // Unexpected message
-				}
-			}
-			return m_retVal;
-		}
-
-////////////////////////////////////////////////////////////////////
-// reqSetting (byte array in + out & no param variant)
-//
-// Send a message to the device and the data of acknowledge message
-// will be returned. Only valid for serial port connections
-//
-// Input
-//	 mid		: Message ID of message to send
-//   bid		: Bus ID of message to send (def 0xFF)
-//	 dataIn		: Data to be included in request
-//	 dataInLen	: Number of bytes in dataIn
-//	 
-// Output
-//   = MTRV_OK if an Ack message is received
-//	 = MTRV_RECVERRORMSG if an error message is received
-//	 = MTRV_TIMEOUT if timeout occurred
-//
-//	 dataOut[] contains the data of the acknowledge message
-//	 dataOutLen contains the number bytes returned
-//
-		short CXsensMTiModule::reqSetting(const unsigned char mid, unsigned char dataIn[], short dataInLen, unsigned char dataOut[], short &dataOutLen, const unsigned char bid)
-		{
-			unsigned char buffer[MAXMSGLEN ];
-			short headerLength;
-			short msgLen;
-
-			if (m_fileOpen)
-			{
-				return (m_retVal = MTRV_INVALIDFORFILEINPUT);
-			}
-			if (!m_portOpen)
-			{
-				return (m_retVal = MTRV_NOINPUTINITIALIZED);
-			}
-			buffer[IND_PREAMBLE] = PREAMBLE;
-			buffer[IND_BID] = bid;
-			buffer[IND_MID] = mid;
-			if (dataInLen < EXTLENCODE)
-			{
-				buffer[IND_LEN] = (unsigned char) dataInLen;
-				headerLength = LEN_MSGHEADER;
-			}
-			else
-			{
-				buffer[IND_LEN] = EXTLENCODE;
-				buffer[IND_LENEXTH] = (unsigned char) (dataInLen >> 8);
-				buffer[IND_LENEXTL] = (unsigned char) (dataInLen & 0x00FF);
-				headerLength = LEN_MSGEXTHEADER;
-			}
-			memcpy(&buffer[headerLength],dataIn,dataInLen);
-			calcChecksum(buffer,headerLength + dataInLen);
-
-			// Send message
-			writeData(buffer,headerLength + dataInLen + LEN_CHECKSUM);
-
-			dataOutLen = 0;
-			// Read next message or else timeout
-			if (readMessageRaw(buffer,&msgLen) == MTRV_OK)
-			{
-				// Message received
-				if (buffer[IND_MID] == (mid + 1))
-				{
-					// Acknowledge received
-					if (buffer[IND_LEN] != EXTLENCODE)
-					{
-						dataOutLen = buffer[IND_LEN];
-						memcpy(dataOut,&buffer[IND_DATA0],dataOutLen);
-					}
-					else
-					{
-						dataOutLen = buffer[IND_LENEXTH] * 256 + buffer[IND_LENEXTL];
-						memcpy(dataOut,&buffer[IND_DATAEXT0],dataOutLen);
-					}
-					return (m_retVal = MTRV_OK);
-				}
-				else if (buffer[IND_MID] == MID_ERROR)
-				{
-					m_deviceError = buffer[IND_DATA0];
-					return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
-				}
-				else
-				{
-					return (m_retVal = MTRV_UNEXPECTEDMSG);   // Unexpected message
-				}
-			}
-			return m_retVal;
-		}
-
-////////////////////////////////////////////////////////////////////
-// reqSetting (byte array & param variant)
-//
-// Send a message to the device and the data of acknowledge message
-// will be returned. Only valid for serial port connections
-//
-// Input
-//	 mid		: Message ID of message to send
-//	 param		: For messages that need a parameter (optional)
-//   bid		: Bus ID of message to send (def 0xFF)
-//	 
-// Output
-//   = MTRV_OK if an Ack message is received
-//	 = MTRV_RECVERRORMSG if an error message is received
-//	 = MTRV_TIMEOUT if timeout occurred
-//
-//	 data[] contains the data of the acknowledge message (including param!!)
-//	 dataLen contains the number bytes returned
-//
-		short CXsensMTiModule::reqSetting(const unsigned char mid, const unsigned char param, unsigned char data[], short &dataLen, const unsigned char bid)
-		{
-			unsigned char buffer[MAXMSGLEN ];
-			short msgLen;
-
-			if (m_fileOpen)
-			{
-				return (m_retVal = MTRV_INVALIDFORFILEINPUT);
-			}
-			if (!m_portOpen)
-			{
-				return (m_retVal = MTRV_NOINPUTINITIALIZED);
-			}
-			buffer[IND_PREAMBLE] = PREAMBLE;
-			buffer[IND_BID] = bid;
-			buffer[IND_MID] = mid;
-			if (param != 0xFF)
-			{
-				buffer[IND_LEN] = 1;
-				buffer[IND_DATA0] = param;
-			}
-			else
-			{
-				buffer[IND_LEN] = 0;
-			}
-			calcChecksum(buffer,LEN_MSGHEADER + buffer[IND_LEN]);
-
-			// Send message
-			writeData(buffer,LEN_MSGHEADERCS + buffer[IND_LEN]);
-
-			dataLen = 0;
-			// Read next message or else timeout
-			if (readMessageRaw(buffer,&msgLen) == MTRV_OK)
-			{
-				// Message received
-				if (buffer[IND_MID] == (mid + 1))
-				{
-					// Acknowledge received
-					if (buffer[IND_LEN] != EXTLENCODE)
-					{
-						dataLen = buffer[IND_LEN];
-						memcpy(data,&buffer[IND_DATA0],dataLen);
-					}
-					else
-					{
-						dataLen = buffer[IND_LENEXTH] * 256 + buffer[IND_LENEXTL];
-						memcpy(data,&buffer[IND_DATAEXT0],dataLen);
-					}
-					return (m_retVal = MTRV_OK);
-				}
-				else if (buffer[IND_MID] == MID_ERROR)
-				{
-					m_deviceError = buffer[IND_DATA0];
-					return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
-				}
-				else
-				{
-					return (m_retVal = MTRV_UNEXPECTEDMSG);   // Unexpected message
-				}
-			}
-			return m_retVal;
-		}
-
-////////////////////////////////////////////////////////////////////
-// setSetting (integer & no param variant)
-//
-// Sets a integer setting of the device. This setting
-// can be an unsigned 1,2 or 4 bytes setting. Only valid
-// for serial port connections.
-//
-// Input
-//	 mid		: Message ID of message to send
-//   bid		: Bus ID of message to send (def 0xFF)
-//	 value		: Contains the integer value to be used
-//	 valuelen	: Length in bytes of the value
-//
-// Output
-//   = MTRV_OK if an Ack message is received
-//	 = MTRV_RECVERRORMSG if an error message is received
-//	 = MTRV_TIMEOUT if timeout occurred
-//
-//
-		short CXsensMTiModule::setSetting(const unsigned char mid, const unsigned long value, const unsigned short valuelen, const unsigned char bid)
-		{
-			unsigned char buffer[MAXMSGLEN ];
-			short msgLen;
-
-			if (m_fileOpen)
-			{
-				return (m_retVal = MTRV_INVALIDFORFILEINPUT);
-			}
-			if (!m_portOpen)
-			{
-				return (m_retVal = MTRV_NOINPUTINITIALIZED);
-			}
-			msgLen = LEN_MSGHEADER;
-			buffer[IND_PREAMBLE] = PREAMBLE;
-			buffer[IND_BID] = bid;
-			buffer[IND_MID] = mid;
-			buffer[IND_LEN] = (unsigned char) valuelen;
-			swapEndian((unsigned char *) &value,&buffer[msgLen],valuelen);
-			calcChecksum(buffer,LEN_MSGHEADER + buffer[IND_LEN]);
-
-			// Send message
-			writeData(buffer,LEN_MSGHEADERCS + buffer[IND_LEN]);
-
-			// Read next received message
-			if (readMessageRaw(buffer,&msgLen) == MTRV_OK)
-			{
-				// Message received
-				if (buffer[IND_MID] == (mid + 1))
-				{
-					return (m_retVal = MTRV_OK);				// Acknowledge received
-				}
-				else if (buffer[IND_MID] == MID_ERROR)
-				{
-					m_deviceError = buffer[IND_DATA0];
-					return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
-				}
-			}
-			return m_retVal;
-		}
-
-////////////////////////////////////////////////////////////////////
-// setSetting (integer & param variant)
-//
-// Sets a integer setting of the device. This setting
-// can be an unsigned 1,2 or 4 bytes setting. Only valid
-// for serial port connections.
-//
-// Input
-//	 mid		: Message ID of message to send
-//	 param		: For messages that need a parameter (optional)
-//   bid		: Bus ID of message to send (def 0xFF)
-//	 value		: Contains the integer value to be used
-//	 valuelen	: Length in bytes of the value
-//
-// Output
-//   = MTRV_OK if an Ack message is received
-//	 = MTRV_RECVERRORMSG if an error message is received
-//	 = MTRV_TIMEOUT if timeout occurred
-//
-//
-		short CXsensMTiModule::setSetting(const unsigned char mid, const unsigned char param, const unsigned long value, const unsigned short valuelen, const unsigned char bid)
-		{
-			unsigned char buffer[MAXMSGLEN ];
-			short msgLen;
-
-			if (m_fileOpen)
-			{
-				return (m_retVal = MTRV_INVALIDFORFILEINPUT);
-			}
-			if (!m_portOpen)
-			{
-				return (m_retVal = MTRV_NOINPUTINITIALIZED);
-			}
-			msgLen = LEN_MSGHEADER;
-			buffer[IND_PREAMBLE] = PREAMBLE;
-			buffer[IND_BID] = bid;
-			buffer[IND_MID] = mid;
-			if (param != 0xFF)
-			{
-				msgLen++;
-				buffer[IND_LEN] = valuelen + 1;
-				buffer[IND_DATA0] = param;
-			}
-			else
-			{
-				buffer[IND_LEN] = (unsigned char) valuelen;
-			}
-			swapEndian((unsigned char *) &value,&buffer[msgLen],valuelen);
-			calcChecksum(buffer,LEN_MSGHEADER + buffer[IND_LEN]);
-
-			// Send message
-			writeData(buffer,LEN_MSGHEADERCS + buffer[IND_LEN]);
-
-			// Read next received message
-			if (readMessageRaw(buffer,&msgLen) == MTRV_OK)
-			{
-				// Message received
-				if (buffer[IND_MID] == (mid + 1))
-				{
-					return (m_retVal = MTRV_OK);				// Acknowledge received
-				}
-				else if (buffer[IND_MID] == MID_ERROR)
-				{
-					m_deviceError = buffer[IND_DATA0];
-					return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
-				}
-			}
-			return m_retVal;
-		}
-
-////////////////////////////////////////////////////////////////////
-// setSetting (float & no param variant)
-//
-// Sets a float setting of the device. Only valid
-// for serial port connections.
-//
-// Input
-//	 mid		: Message ID of message to send
-//   bid		: Bus ID of message to send (def 0xFF)
-//	 value		: Contains the float value to be used
-//
-// Output
-//   = MTRV_OK if an Ack message is received
-//	 = MTRV_RECVERRORMSG if an error message is received
-//	 = MTRV_TIMEOUT if timeout occurred
-//
-		short CXsensMTiModule::setSetting(const unsigned char mid, const float value, const unsigned char bid)
-		{
-			unsigned char buffer[MAXMSGLEN ];
-			short msgLen;
-
-			if (m_fileOpen)
-			{
-				return (m_retVal = MTRV_INVALIDFORFILEINPUT);
-			}
-			if (!m_portOpen)
-			{
-				return (m_retVal = MTRV_NOINPUTINITIALIZED);
-			}
-			msgLen = LEN_MSGHEADER;
-			buffer[IND_PREAMBLE] = PREAMBLE;
-			buffer[IND_BID] = bid;
-			buffer[IND_MID] = mid;
-			buffer[IND_LEN] = LEN_FLOAT;
-			swapEndian((unsigned char *) &value,&buffer[msgLen],LEN_FLOAT);
-			calcChecksum(buffer,LEN_MSGHEADER + LEN_FLOAT);
-
-			// Send message
-			writeData(buffer,LEN_MSGHEADERCS + LEN_FLOAT);
-
-			// Read next received message
-			if (readMessageRaw(buffer,&msgLen) == MTRV_OK)
-			{
-				// Message received
-				if (buffer[IND_MID] == (mid + 1))
-				{
-					return (m_retVal = MTRV_OK);				// Acknowledge received
-				}
-				else if (buffer[IND_MID] == MID_ERROR)
-				{
-					m_deviceError = buffer[IND_DATA0];
-					return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
-				}
-			}
-			return m_retVal;
-		}
-
-////////////////////////////////////////////////////////////////////
-// setSetting (float & param variant)
-//
-// Sets a float setting of the device. Only valid
-// for serial port connections.
-//
-// Input
-//	 mid		: Message ID of message to send
-//	 param		: For messages that need a parameter (optional)
-//   bid		: Bus ID of message to send (def 0xFF)
-//	 value		: Contains the float value to be used
-//
-// Output
-//   = MTRV_OK if an Ack message is received
-//	 = MTRV_RECVERRORMSG if an error message is received
-//	 = MTRV_TIMEOUT if timeout occurred
-//
-//
-		short CXsensMTiModule::setSetting(const unsigned char mid, const unsigned char param, const float value, const unsigned char bid)
-		{
-			unsigned char buffer[MAXMSGLEN ];
-			short msgLen;
-
-			if (m_fileOpen)
-			{
-				return (m_retVal = MTRV_INVALIDFORFILEINPUT);
-			}
-			if (!m_portOpen)
-			{
-				return (m_retVal = MTRV_NOINPUTINITIALIZED);
-			}
-			msgLen = LEN_MSGHEADER;
-			buffer[IND_PREAMBLE] = PREAMBLE;
-			buffer[IND_BID] = bid;
-			buffer[IND_MID] = mid;
-			if (param != 0xFF)
-			{
-				msgLen++;
-				buffer[IND_LEN] = LEN_FLOAT + 1;
-				buffer[IND_DATA0] = param;
-			}
-			else
-			{
-				buffer[IND_LEN] = LEN_FLOAT;
-			}
-			swapEndian((unsigned char *) &value,&buffer[msgLen],LEN_FLOAT);
-			calcChecksum(buffer,LEN_MSGHEADER + buffer[IND_LEN]);
-
-			// Send message
-			writeData(buffer,LEN_MSGHEADERCS + buffer[IND_LEN]);
-
-			// Read next received message
-			if (readMessageRaw(buffer,&msgLen) == MTRV_OK)
-			{
-				// Message received
-				if (buffer[IND_MID] == (mid + 1))
-				{
-					return (m_retVal = MTRV_OK);				// Acknowledge received
-				}
-				else if (buffer[IND_MID] == MID_ERROR)
-				{
-					m_deviceError = buffer[IND_DATA0];
-					return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
-				}
-			}
-			return m_retVal;
-		}
-
-////////////////////////////////////////////////////////////////////
-// setSetting (float & param & store variant)
-//
-// Sets a float setting of the device and with the Store field.
-// Only valid for serial port connections
-//
-// Input
-//	 mid		: Message ID of message to send
-//	 param		: For messages that need a parameter (optional)
-//	 value		: Contains the float value to be used
-//	 store		; Store in non-volatile memory (1) or not (0)
-//   bid		: Bus ID of message to send (def 0xFF)
-//
-// Output
-//   = MTRV_OK if an Ack message is received
-//	 = MTRV_RECVERRORMSG if an error message is received
-//	 = MTRV_TIMEOUT if timeout occurred
-//
-//
-		short CXsensMTiModule::setSetting(const unsigned char mid, const unsigned char param, const float value, const bool store, const unsigned char bid)
-		{
-			unsigned char buffer[MAXMSGLEN ];
-			short msgLen;
-
-			if (m_fileOpen)
-			{
-				return (m_retVal = MTRV_INVALIDFORFILEINPUT);
-			}
-			if (!m_portOpen)
-			{
-				return (m_retVal = MTRV_NOINPUTINITIALIZED);
-			}
-			msgLen = LEN_MSGHEADER;
-			buffer[IND_PREAMBLE] = PREAMBLE;
-			buffer[IND_BID] = bid;
-			buffer[IND_MID] = mid;
-			if (param != 0xFF)
-			{
-				msgLen++;
-				buffer[IND_LEN] = LEN_FLOAT + 2;
-				buffer[IND_DATA0] = param;
-			}
-			else
-			{
-				buffer[IND_LEN] = LEN_FLOAT + 1;
-			}
-			swapEndian((unsigned char *) &value,&buffer[msgLen],LEN_FLOAT);
-			buffer[msgLen + LEN_FLOAT ] = store;
-			calcChecksum(buffer,LEN_MSGHEADER + buffer[IND_LEN]);
-
-			// Send message
-			writeData(buffer,LEN_MSGHEADERCS + buffer[IND_LEN]);
-
-			// Read next received message
-			if (readMessageRaw(buffer,&msgLen) == MTRV_OK)
-			{
-				// Message received
-				if (buffer[IND_MID] == (mid + 1))
-				{
-					return (m_retVal = MTRV_OK);			// Acknowledge received
-				}
-				else if (buffer[IND_MID] == MID_ERROR)
-				{
-					m_deviceError = buffer[IND_DATA0];
-					return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
-				}
-			}
-			return m_retVal;
-		}
-
-////////////////////////////////////////////////////////////////////
-// getDeviceMode
-//
-// Requests the current output mode/setting of input (file or serialport)
-//  the Outputmode, Outputsettings, DataLength & number of devices
-//  are stored in member variables of the MTComm class. These values 
-//  are needed for the GetValue functions.
-//  The function optionally returns the number of devices
-//
-// File: expects the Configuration message at the start of the file
-//       which holds the OutputMode & OutputSettings. File position 
-//       is after the first message
-//
-// Input
-// Output
-//	 numDevices : [optional] number of devices connected to port or
-//                found in configuration file
-//	
-//   returns MTRV_OK if the mode & settings are read
-//
-		short CXsensMTiModule::getDeviceMode(unsigned short *numDevices)
-		{
-			unsigned char mid = 0 , data[MAXMSGLEN ];
-			short datalen;
-
-			if (numDevices != NULL)
-			{
-				*numDevices = 0;
-			}
-
-			// In case serial port is used (live device / XM or MT)
-			if (m_portOpen)
-			{
-				if (reqSetting(MID_INITBUS,data,datalen) != MTRV_OK)
-				{
-					return m_retVal;
-				}
-
-				// Retrieve outputmode + outputsettings
-				for(int i = 0 ; i < datalen / LEN_DEVICEID ; i++)
-				{
-					if (reqSetting(MID_REQOUTPUTMODE,m_storedOutputMode[BID_MT + i],BID_MT + i) != MTRV_OK)
-					{
-						return m_retVal;
-					}
-
-					if (reqSetting(MID_REQOUTPUTSETTINGS,m_storedOutputSettings[BID_MT + i],BID_MT + i) != MTRV_OK)
-					{
-						return m_retVal;
-					}
-
-					if (reqSetting(MID_REQDATALENGTH,m_storedDataLength[BID_MT + i],BID_MT + i) != MTRV_OK)
-					{
-						return m_retVal;
-					}
-				}
-
-				if (numDevices != NULL)
-				{
-					*numDevices = datalen / LEN_DEVICEID;
-				}
-
-				unsigned char masterDID[4];
-				short DIDlen;
-
-				if (reqSetting(MID_REQDID,masterDID,DIDlen) != MTRV_OK)
-				{
-					return m_retVal;
-				}
-
-				if (memcmp(masterDID,data,LEN_DEVICEID) != 0)
-				{
-					// Using an XbusMaster
-					m_storedOutputMode[0] = OUTPUTMODE_XM;
-					m_storedOutputSettings[0] = OUTPUTSETTINGS_XM;
-					m_storedDataLength[0] = LEN_SAMPLECNT;
-				}
-				else
-				{
-					m_storedOutputMode[0] = m_storedOutputMode[BID_MT ];
-					m_storedOutputSettings[0] = m_storedOutputSettings[BID_MT ];
-					m_storedDataLength[0] = m_storedDataLength[BID_MT ];
-				}
-				return (m_retVal = MTRV_OK);
-			}
-			else if (m_fileOpen)
-			{
-				// Configuration message should be the first message in the file
-				setFilePos(0);
-				if (readMessage(mid,data,datalen) == MTRV_OK)
-				{
-					if (mid == MID_CONFIGURATION)
-					{
-						unsigned short _numDevices = 0;
-						swapEndian(data + CONF_NUMDEVICES,(unsigned char *) &_numDevices,CONF_NUMDEVICESLEN);
-						for(unsigned int i = 0 ; i < _numDevices ; i++)
-						{
-							m_storedOutputMode[BID_MT + i] = 0;
-							swapEndian(data + CONF_OUTPUTMODE + i * CONF_BLOCKLEN,(unsigned char *) (m_storedOutputMode + BID_MT + i),
-							CONF_OUTPUTMODELEN);
-							m_storedOutputSettings[BID_MT + i] = 0;
-							swapEndian(data + CONF_OUTPUTSETTINGS + i * CONF_BLOCKLEN,(unsigned char *) (m_storedOutputSettings + BID_MT + i),
-							CONF_OUTPUTSETTINGSLEN);
-							m_storedDataLength[BID_MT + i] = 0;
-							swapEndian(data + CONF_DATALENGTH + i * CONF_BLOCKLEN,(unsigned char *) (m_storedDataLength + BID_MT + i),
-							CONF_DATALENGTHLEN);
-						}
-						if (numDevices != NULL)
-						{
-							*numDevices = _numDevices;
-						}
-						if (memcmp(data + CONF_MASTERDID,data + CONF_DID,LEN_DEVICEID) != 0)
-						{
-							// Using an XbusMaster
-							m_storedOutputMode[0] = OUTPUTMODE_XM;
-							m_storedOutputSettings[0] = OUTPUTSETTINGS_XM;
-							m_storedDataLength[0] = LEN_SAMPLECNT;
-						}
-						else
-						{
-							m_storedOutputMode[0] = m_storedOutputMode[BID_MT ];
-							m_storedOutputSettings[0] = m_storedOutputSettings[BID_MT ];
-							m_storedDataLength[0] = m_storedDataLength[BID_MT ];
-						}
-						return (m_retVal = MTRV_OK);
-					}
-				}
-				return (m_retVal = MTRV_NOTSUCCESSFUL);
-			}
-			return (m_retVal = MTRV_NOINPUTINITIALIZED);
-		}
-
-////////////////////////////////////////////////////////////////////
-// setDeviceMode
-//
-// Sets the current output mode/setting of input (not for file-based 
-//   inputs)
-//
-// Input
-//	 OutputMode		: OutputMode to be set in device & stored in MTComm 
-//						class member variable
-//	 OutputSettings : OutputSettings to be set in device & stored in 
-//						MTComm class member variable
-// Output
-//	
-//   returns MTRV_OK if the mode & settings are read
-//
-		short CXsensMTiModule::setDeviceMode(unsigned long OutputMode, unsigned long OutputSettings, const unsigned char bid)
-		{
-			// In case serial port is used (live XM / MT)
-			if (m_portOpen)
-			{
-				// Set OutputMode
-				if (setSetting(MID_SETOUTPUTMODE,OutputMode,LEN_OUTPUTMODE,bid) != MTRV_OK)
-				{
-					return m_retVal;
-				}
-				if (bid == BID_MASTER || (bid == BID_MT && m_storedOutputMode[0] != OUTPUTMODE_XM))
-				{
-					m_storedOutputMode[0] = m_storedOutputMode[BID_MT ] = OutputMode;
-				}
-				else
-				{
-					m_storedOutputMode[bid] = OutputMode;
-				}
-				// Set OutputSettings
-				if (setSetting(MID_SETOUTPUTSETTINGS,OutputSettings,LEN_OUTPUTSETTINGS,bid) != MTRV_OK)
-				{
-					return m_retVal;
-				}
-				if (bid == BID_MASTER || (bid == BID_MT && m_storedOutputMode[0] != OUTPUTMODE_XM))
-				{
-					m_storedOutputSettings[0] = m_storedOutputSettings[BID_MT ] = OutputSettings;
-				}
-				else
-				{
-					m_storedOutputSettings[bid] = OutputSettings;
-				}
-				// Get DataLength from device
-				if (OutputMode != OUTPUTMODE_XM)
-				{
-					unsigned long value;
-					if (reqSetting(MID_REQDATALENGTH,value,bid) == MTRV_OK)
-					{
-						if ((bid == BID_MASTER ) || ((bid == BID_MT ) && (m_storedOutputMode[0] != OUTPUTMODE_XM)))
-						{
-							m_storedDataLength[0] = m_storedDataLength[BID_MT ] = value;
-						}
-						else
-						{
-							m_storedDataLength[bid] = value;
-						}
-					}
-				}
-				else
-				{
-					m_storedDataLength[0] = LEN_SAMPLECNT;
-				}
-				return (m_retVal = MTRV_OK);
-			}
-			return (m_retVal = MTRV_INVALIDFORFILEINPUT);
-		}
-
-////////////////////////////////////////////////////////////////////
-// getMode
-//
-// Gets the output mode/setting used in MTComm class and the corresponding
-//  datalength. These variables are set by the functions GetDeviceMode, 
-//  SetDeviceMode or SetMode
-//
-// Input
-// Output
-//	 OutputMode		: OutputMode stored in MTComm class member variable
-//	 OutputSettings : OutputSettings stored in MTComm class member variable
-//	
-//   returns always MTRV_OK
-//
-		short CXsensMTiModule::getMode(unsigned long &OutputMode, unsigned long &OutputSettings, unsigned short &dataLength, const unsigned char bid)
-		{
-			unsigned char nbid = (bid == BID_MASTER ) ? 0 : bid;
-			OutputMode = m_storedOutputMode[nbid];
-			OutputSettings = m_storedOutputSettings[nbid];
-			dataLength = (unsigned short) m_storedDataLength[nbid];
-			return (m_retVal = MTRV_OK);
-		}
-
-////////////////////////////////////////////////////////////////////
-// setMode
-//
-// Sets the output mode/setting used in MTComm class. Use the function
-//  GetDeviceMode to retrieve the current values of file/device.
-// This function will also calculate the data length field
-//
-// Input
-//	 OutputMode		: OutputMode to be stored in MTComm class member variable
-//	 OutputSettings : OutputSettings to be stored in MTComm class member variable
-// Output
-//	
-//   returns always MTRV_OK
-//
-		short CXsensMTiModule::setMode(unsigned long OutputMode, unsigned long OutputSettings, const unsigned char bid)
-		{
-			unsigned char nbid = bid;
-
-			if (nbid == BID_MASTER)
-			{
-				nbid = 0;
-			}
-			m_storedOutputMode[nbid] = OutputMode;
-			m_storedOutputSettings[nbid] = OutputSettings;
-			if (OutputMode == INVALIDSETTINGVALUE || OutputSettings == INVALIDSETTINGVALUE)
-			{
-				m_storedDataLength[nbid] = 0;
-			}
-			else
-			{
-				unsigned short dataLength = 0;
-				if (OutputMode & OUTPUTMODE_MT9)
-				{
-					dataLength = ((OutputSettings & OUTPUTSETTINGS_TIMESTAMP_MASK) == OUTPUTSETTINGS_TIMESTAMP_SAMPLECNT) ? LEN_SAMPLECNT : 0 + LEN_RAWDATA;
-				}
-				else if (OutputMode == OUTPUTMODE_XM)
-				{
-					// XbusMaster concatenates sample counter
-					dataLength = LEN_SAMPLECNT;
-				}
-				else
-				{
-					if (OutputMode & OUTPUTMODE_RAW)
-					{
-						dataLength = LEN_RAWDATA;
-					}
-					else
-					{
-						if (OutputMode & OUTPUTMODE_CALIB)
-						{
-							dataLength = LEN_CALIBDATA;
-						}
-						if (OutputMode & OUTPUTMODE_ORIENT)
-						{
-							switch(OutputSettings & OUTPUTSETTINGS_ORIENTMODE_MASK)
-							{
-								case OUTPUTSETTINGS_ORIENTMODE_QUATERNION:
-									dataLength += LEN_ORIENT_QUATDATA;
-								break;
-								case OUTPUTSETTINGS_ORIENTMODE_EULER:
-									dataLength += LEN_ORIENT_EULERDATA;
-								break;
-								case OUTPUTSETTINGS_ORIENTMODE_MATRIX:
-									dataLength += LEN_ORIENT_MATRIXDATA;
-								break;
-								default:
-								break;
-							}
-						}
-					}
-					switch(OutputSettings & OUTPUTSETTINGS_TIMESTAMP_MASK)
-					{
-						case OUTPUTSETTINGS_TIMESTAMP_SAMPLECNT:
-							dataLength += LEN_SAMPLECNT;
-						break;
-						default:
-						break;
-					}
-				}
-				m_storedDataLength[nbid] = dataLength;
-			}
-			// If not XbusMaster store also in BID_MT
-			if (bid == BID_MASTER && OutputMode != OUTPUTMODE_XM)
-			{
-				m_storedOutputMode[BID_MT ] = m_storedOutputMode[0];
-				m_storedOutputSettings[BID_MT ] = m_storedOutputSettings[0];
-				m_storedDataLength[BID_MT ] = m_storedDataLength[0];
-			}
-			return (m_retVal = MTRV_OK);
-		}
-
-////////////////////////////////////////////////////////////////////
-// getValue (unsigned short variant)
-//
-// Retrieves a unsigned short value from the data input parameter
-// This function is valid for the following value specifiers:
-//		VALUE_RAW_TEMP
-//		VALUE_SAMPLECNT		
-//
-// Use getDeviceMode or setMode to initialize the Outputmode
-// and Outputsettings member variables used to retrieve the correct
-// value
-//
-// Input
-//	 valueSpec		: Specifier of the value to be retrieved
-//	 data[]			: Data field of a MTData / BusData message
-//	 bid			: bus identifier of the device of which the
-//						value should be returned (default = BID_MT)
-// Output
-//	 value			: reference to unsigned short in which the retrieved
-//						value will be returned
-//	
-//	Return value
-//    MTRV_OK		: value is successfully retrieved
-//	  != MTRV_OK	: not successful
-//
-		short CXsensMTiModule::getValue(const unsigned long valueSpec, unsigned short &value, const unsigned char data[], const unsigned char bid)
-		{
-			short offset = 0;
-			unsigned char nbid = bid;
-
-			if (nbid == BID_MASTER)
-			{
-				nbid = 0;
-			}
-
-			// Check for invalid mode/settings
-			if (m_storedOutputMode[nbid] == INVALIDSETTINGVALUE || m_storedOutputSettings[nbid] == INVALIDSETTINGVALUE)
-			{
-				return (m_retVal = MTRV_NOVALIDMODESPECIFIED);
-			}
-
-			// Calculate offset for XM input
-			if (m_storedOutputMode[0] == OUTPUTMODE_XM)
-			{
-				int i = 0;
-				while(i < nbid)
-				{
-					offset += (short) m_storedDataLength[i++];
-				}
-			}
-
-			// Check if data is unsigned short & available in data
-			m_retVal = MTRV_INVALIDVALUESPEC;
-			if (valueSpec == VALUE_RAW_TEMP)
-			{
-				if (m_storedOutputMode[nbid] & (OUTPUTMODE_RAW | OUTPUTMODE_MT9))
-				{
-					offset += (m_storedOutputMode[nbid] == OUTPUTMODE_MT9 && m_storedOutputSettings[nbid] == OUTPUTSETTINGS_TIMESTAMP_SAMPLECNT) ? LEN_SAMPLECNT : 0;
-					swapEndian(data + offset + valueSpec * LEN_UNSIGSHORT * 3,(unsigned char *) &value,LEN_RAW_TEMP);
-					m_retVal = MTRV_OK;
-				}
-			}
-			else if (valueSpec == VALUE_SAMPLECNT)
-			{
-				if ((m_storedOutputSettings[nbid] & OUTPUTSETTINGS_TIMESTAMP_MASK) == OUTPUTSETTINGS_TIMESTAMP_SAMPLECNT)
-				{
-					if (!(m_storedOutputMode[nbid] == OUTPUTMODE_MT9))
-					{
-						offset += (short) m_storedDataLength[nbid] - LEN_SAMPLECNT;
-					}
-					swapEndian(data + offset,(unsigned char *) &value,LEN_SAMPLECNT);
-					m_retVal = MTRV_OK;
-				}
-			}
-			return m_retVal;
-		}
-
-////////////////////////////////////////////////////////////////////
-// getValue (array of unsigned short variant)
-//
-// Retrieves an array of unsigned short values from the data input 
-// parameter. This function is valid for the following value specifiers:
-//		VALUE_RAW_ACC
-//		VALUE_RAW_GYR
-//		VALUE_RAW_MAG
-//
-// Use getDeviceMode or setMode to initialize the Outputmode
-// and Outputsettings member variables used to retrieve the correct
-// value
-//
-// Input
-//	 valueSpec		: Specifier of the value to be retrieved
-//	 data[]			: Data field of a MTData / BusData message
-//	 bid			: bus identifier of the device of which the
-//						value should be returned (default = BID_MT)
-// Output
-//	 value[]		: pointer to array of unsigned shorts in which the 
-//						retrieved values will be returned
-//	
-//	Return value
-//    MTRV_OK		: value is successfully retrieved
-//	  != MTRV_OK	: not successful
-//
-		short CXsensMTiModule::getValue(const unsigned long valueSpec, unsigned short value[], const unsigned char data[], const unsigned char bid)
-		{
-			short offset = 0;
-			unsigned char nbid = bid;
-
-			if (nbid == BID_MASTER)
-			{
-				nbid = 0;
-			}
-			// Check for invalid mode/settings
-			if (m_storedOutputMode[nbid] == INVALIDSETTINGVALUE || m_storedOutputSettings[nbid] == INVALIDSETTINGVALUE)
-			{
-				return (m_retVal = MTRV_NOVALIDMODESPECIFIED);
-			}
-
-			// Calculate offset for XM input
-			if (m_storedOutputMode[0] == OUTPUTMODE_XM)
-			{
-				int i = 0;
-				while(i < nbid)
-				{
-					offset += (short) m_storedDataLength[i++];
-				}
-			}
-
-			// Check if data is unsigned short, available in data & retrieve data
-			m_retVal = MTRV_INVALIDVALUESPEC;
-			//if (valueSpec >= VALUE_RAW_ACC && valueSpec <= VALUE_RAW_MAG)
-			if (valueSpec <= VALUE_RAW_MAG)
-			{
-				if (m_storedOutputMode[nbid] & (OUTPUTMODE_RAW | OUTPUTMODE_MT9))
-				{
-					offset += (short) (valueSpec * LEN_UNSIGSHORT * 3);
-					offset += (m_storedOutputMode[nbid] == OUTPUTMODE_MT9 && m_storedOutputSettings[nbid] == OUTPUTSETTINGS_TIMESTAMP_SAMPLECNT) ? LEN_SAMPLECNT : 0;
-					for(int i = 0 ; i < 3 ; i++)
-					{
-						swapEndian(data + offset + i * LEN_UNSIGSHORT,(unsigned char *) value + i * LEN_UNSIGSHORT,LEN_UNSIGSHORT);
-					}
-					m_retVal = MTRV_OK;
-				}
-			}
-			return m_retVal;
-		}
-
-////////////////////////////////////////////////////////////////////
-// getValue (array of floats variant)
-//
-// Retrieves an array of float values from the data input parameter. 
-// This function is valid for the following value specifiers:
-//		VALUE_TEMP
-//		VALUE_CALIB_ACC
-//		VALUE_CALIB_GYR
-//		VALUE_CALIB_MAG
-//		VALUE_ORIENT_QUAT
-//		VALUE_ORIENT_EULER
-//		VALUE_ORIENT_MATRIX
-//
-// Use getDeviceMode or setMode to initialize the Outputmode
-// and Outputsettings member variables used to retrieve the correct
-// value
-//
-// Input
-//	 valueSpec		: Specifier of the value to be retrieved
-//	 data[]			: Data field of a MTData / BusData message
-//	 bid			: bus identifier of the device of which the
-//						value should be returned (default = BID_MT)
-// Output
-//	 value[]		: pointer to array of floats in which the 
-//						retrieved values will be returned
-//	
-//	Return value
-//    MTRV_OK		: value is successfully retrieved
-//	  != MTRV_OK	: not successful
-//
-		short CXsensMTiModule::getValue(const unsigned long valueSpec, float value[], const unsigned char data[], const unsigned char bid)
-		{
-			short offset = 0;
-			int nElements = 0;
-			unsigned char nbid = bid;
-
-			if (nbid == BID_MASTER)
-			{
-				nbid = 0;
-			}
-
-			// Check for invalid mode/settings
-			if (m_storedOutputMode[nbid] == INVALIDSETTINGVALUE || m_storedOutputSettings[nbid] == INVALIDSETTINGVALUE)
-			{
-				return (m_retVal = MTRV_NOVALIDMODESPECIFIED);
-			}
-
-			// Calculate offset for XM input
-			if (m_storedOutputMode[0] == OUTPUTMODE_XM)
-			{
-				int i = 0;
-				while(i < nbid)
-				{
-					offset += (short) m_storedDataLength[i++];
-				}
-			}
-
-			// Check if data is float & available in data
-			m_retVal = MTRV_INVALIDVALUESPEC;
-			if (valueSpec == VALUE_TEMP)
-			{
-				if (m_storedOutputMode[nbid] & OUTPUTMODE_TEMP)
-				{
-					nElements = LEN_TEMPDATA / LEN_FLOAT;
-					m_retVal = MTRV_OK;
-				}
-			}
-			else if (valueSpec == VALUE_CALIB_ACC)
-			{
-				offset += ((m_storedOutputMode[nbid] & OUTPUTMODE_TEMP) != 0) ? LEN_TEMPDATA : 0;
-				if ((m_storedOutputMode[nbid] & OUTPUTMODE_CALIB) && (m_storedOutputSettings[nbid] & OUTPUTSETTINGS_CALIBMODE_ACC_MASK) == 0)
-				{
-					nElements = LEN_CALIB_ACCDATA / LEN_FLOAT;
-					m_retVal = MTRV_OK;
-				}
-			}
-			else if (valueSpec == VALUE_CALIB_GYR)
-			{
-				offset += ((m_storedOutputMode[nbid] & OUTPUTMODE_TEMP) != 0) ? LEN_TEMPDATA : 0;
-				if ((m_storedOutputMode[nbid] & OUTPUTMODE_CALIB) && (m_storedOutputSettings[nbid] & OUTPUTSETTINGS_CALIBMODE_GYR_MASK) == 0)
-				{
-					offset += ((m_storedOutputSettings[nbid] & OUTPUTSETTINGS_CALIBMODE_ACC_MASK) == 0) ? LEN_CALIB_ACCX * 3 : 0;
-					nElements = LEN_CALIB_GYRDATA / LEN_FLOAT;
-					m_retVal = MTRV_OK;
-				}
-			}
-			else if (valueSpec == VALUE_CALIB_MAG)
-			{
-				offset += ((m_storedOutputMode[nbid] & OUTPUTMODE_TEMP) != 0) ? LEN_TEMPDATA : 0;
-				if ((m_storedOutputMode[nbid] & OUTPUTMODE_CALIB) && (m_storedOutputSettings[nbid] & OUTPUTSETTINGS_CALIBMODE_MAG_MASK) == 0)
-				{
-					offset += ((m_storedOutputSettings[nbid] & OUTPUTSETTINGS_CALIBMODE_ACC_MASK) == 0) ? LEN_CALIB_ACCX * 3 : 0;
-					offset += ((m_storedOutputSettings[nbid] & OUTPUTSETTINGS_CALIBMODE_GYR_MASK) == 0) ? LEN_CALIB_GYRX * 3 : 0;
-					nElements = LEN_CALIB_MAGDATA / LEN_FLOAT;
-					m_retVal = MTRV_OK;
-				}
-			}
-			else if (valueSpec >= VALUE_ORIENT_QUAT && valueSpec <= VALUE_ORIENT_MATRIX)
-			{
-				offset += ((m_storedOutputMode[nbid] & OUTPUTMODE_TEMP) != 0) ? LEN_TEMPDATA : 0;
-				if ((m_storedOutputMode[nbid] & OUTPUTMODE_CALIB))
-				{
-					offset += ((m_storedOutputSettings[nbid] & OUTPUTSETTINGS_CALIBMODE_ACC_MASK) == 0) ? LEN_CALIB_ACCX * 3 : 0;
-					offset += ((m_storedOutputSettings[nbid] & OUTPUTSETTINGS_CALIBMODE_GYR_MASK) == 0) ? LEN_CALIB_GYRX * 3 : 0;
-					offset += ((m_storedOutputSettings[nbid] & OUTPUTSETTINGS_CALIBMODE_MAG_MASK) == 0) ? LEN_CALIB_MAGX * 3 : 0;
-				}
-				if (m_storedOutputMode[nbid] & OUTPUTMODE_ORIENT)
-				{
-					unsigned long orientmode = m_storedOutputSettings[nbid] & OUTPUTSETTINGS_ORIENTMODE_MASK;
-					switch(valueSpec)
-					{
-						case VALUE_ORIENT_QUAT:
-							if (orientmode == OUTPUTSETTINGS_ORIENTMODE_QUATERNION)
-							{
-								nElements = LEN_ORIENT_QUATDATA / LEN_FLOAT;
-								m_retVal = MTRV_OK;
-							}
-						break;
-						case VALUE_ORIENT_EULER:
-							if (orientmode == OUTPUTSETTINGS_ORIENTMODE_EULER)
-							{
-								nElements = LEN_ORIENT_EULERDATA / LEN_FLOAT;
-								m_retVal = MTRV_OK;
-							}
-						break;
-						case VALUE_ORIENT_MATRIX:
-							if (orientmode == OUTPUTSETTINGS_ORIENTMODE_MATRIX)
-							{
-								nElements = LEN_ORIENT_MATRIXDATA / LEN_FLOAT;
-								m_retVal = MTRV_OK;
-							}
-						break;
-						default:
-						break;
-					}
-				}
-			}
-			if (m_retVal == MTRV_OK)
-			{
-				if ((m_storedOutputSettings[nbid] & OUTPUTSETTINGS_DATAFORMAT_F1220) == 0)
-				{
-					for(int i = 0 ; i < nElements ; i++)
-					{
-						swapEndian(data + offset + i * LEN_FLOAT,(unsigned char *) value + i * LEN_FLOAT,LEN_FLOAT);
-					}
-				}
-				else
-				{
-					int temp;
-					for(int i = 0 ; i < nElements ; i++)
-					{
-						swapEndian(data + offset + i * LEN_FLOAT,(unsigned char*) &temp,4);
-						value[i] = (float) temp / 1048576;
-					}
-				}
-			}
-			return m_retVal;
-		}
+            }
+
+            m_retVal = MTRV_OK;
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // setFilePos
+        //
+        // Sets the current position of the file pointer for file input
+        //
+        // Input
+        //   relPos     : 32-bit value specifying the relative move in bytes
+        //                  origin is specified in moveMethod
+        //   moveMethod : FILEPOS_BEGIN, FILEPOS_CURRENT or FILEPOS_END
+        // Output
+        //
+        //   returns MTRV_OK if file pointer is successfully set
+        //
+        short CXsensMTiModule::setFilePos(long relPos, unsigned long moveMethod)
+        {
+#ifdef WIN32
 
-//////////////////////////////////////////////////////////////////////
-// getLastDeviceError
-//
-// Returns the last reported device error of the latest received Error 
-//	message
-//
-// Output
-//   Error code
-		short CXsensMTiModule::getLastDeviceError()
-		{
-			return m_deviceError;
-		}
+            if (m_fileOpen)
+            {
+                if (SetFilePointer(m_handle, relPos, NULL, moveMethod) != INVALID_SET_FILE_POINTER)
+                {
+                    return (m_retVal = MTRV_OK);
+                }
+            }
 
-//////////////////////////////////////////////////////////////////////
-// getLastRetVal
-//
-// Returns the returned value of the last called function
-//
-// Output
-//   Return value
-		short CXsensMTiModule::getLastRetVal()
-		{
-			return m_retVal;
-		}
+#else
 
-//////////////////////////////////////////////////////////////////////
-// setTimeOut
-//
-// Sets the time out value in milliseconds used by the functions
-// Use 0 for infinite timeout
-//
-// Output
-//   MTRV_OK is set, MTRV_INVALIDTIMEOUT if time value < 0
-		short CXsensMTiModule::setTimeOut(short timeOutMs)
-		{
-			if (timeOutMs >= 0)
-			{
-				m_timeOut = timeOutMs;
-				return (m_retVal = MTRV_OK);
-			}
-			else
-				return (m_retVal = MTRV_INVALIDTIMEOUT);
-		}
+            if (m_fileOpen)
+            {
+                if (lseek(m_handle, relPos, moveMethod) != -1)
+                {
+                    return (m_retVal = MTRV_OK);
+                }
+            }
 
-//////////////////////////////////////////////////////////////////////
-// swapEndian
-//
-// Convert 2 or 4 bytes data from little to big endian or back
-//
-// Input
-//	 input	: Pointer to data to be converted
-//   output	: Pointer where converted data is stored
-//   length	: Length of setting (0,2 & 4)
-//
-// Remarks:
-//	 Allocate enough bytes for output buffer
-
-		void CXsensMTiModule::swapEndian(const unsigned char input[], unsigned char output[], const int length)
-		{
-			switch(length)
-			{
-				case 4:
-					output[0] = input[3];
-					output[1] = input[2];
-					output[2] = input[1];
-					output[3] = input[0];
-				break;
-				case 2:
-					output[0] = input[1];
-					output[1] = input[0];
-				break;
-				case 1:
-					output[0] = input[0];
-				break;
-				default:
-					for(int i = 0 , j = length - 1 ; i < length ; i++ , j--)
-						output[j] = input[i];
-				break;
-			}
-		}
+#endif
+            return (m_retVal = MTRV_NOTSUCCESSFUL);
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // getFileSize
+        //
+        // Retrieves the file size of the opened file
+        //
+        // Input
+        // Output
+        //   fileSize  : Number of bytes of the current file
+        //
+        //   returns MTRV_OK if successful
+        //
+        short CXsensMTiModule::getFileSize(unsigned long& fileSize)
+        {
+#ifdef WIN32
 
-//////////////////////////////////////////////////////////////////////
-// calcChecksum
-//
-// Calculate and append checksum to msgBuffer
-//
-		void CXsensMTiModule::calcChecksum(unsigned char *msgBuffer, const int msgBufferLength)
-		{
-			unsigned char checkSum = 0;
-			int i;
+            if (m_fileOpen)
+            {
+                if ((fileSize = GetFileSize(m_handle, NULL)) != INVALID_FILE_SIZE)
+                {
+                    return (m_retVal = MTRV_OK);
+                }
+            }
 
-			for(i = 1; i < msgBufferLength ; i++)
-				checkSum += msgBuffer[i];
+#else
 
-			msgBuffer[msgBufferLength] = -checkSum;   // Store chksum
-		}
+            if (m_fileOpen)
+            {
+                struct stat buf;
 
-//////////////////////////////////////////////////////////////////////
-// checkChecksum
-//
-// Checks if message checksum is valid
-//
-// Output
-//   returns true checksum is OK
-		bool CXsensMTiModule::checkChecksum(const unsigned char *msgBuffer, const int msgBufferLength)
-		{
-			unsigned char checkSum = 0;
-			int i;
-
-			for(i = 1; i < msgBufferLength ; i++)
-				checkSum += msgBuffer[i];
-
-			if (checkSum == 0)
-			{
-				return true;
-			}
-			else
-			{
-				return false;
-			}
-		}
-	}
+                if (fstat(m_handle, &buf) == 0)
+                {
+                    fileSize = buf.st_size;
+                    return (m_retVal = MTRV_OK);
+                }
+            }
+
+#endif
+            return (m_retVal = MTRV_NOTSUCCESSFUL);
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // close
+        //
+        // Closes handle of file or serial port
+        //
+        short CXsensMTiModule::close()
+        {
+            if (m_portOpen || m_fileOpen)
+            {
+#ifdef WIN32
+
+                if (m_portOpen)
+                {
+                    // Because of USB-serial driver bug
+                    flush();
+                }
+
+                CloseHandle(m_handle);
+#else
+                ::close(m_handle);
+#endif
+            }
+
+            m_fileOpen = m_portOpen = false;
+            m_timeOut = TO_DEFAULT;   // Restore timeout value (file input)
+            m_clkEnd = 0;
+            m_nTempBufferLen = 0;
+            m_deviceError = 0;   // No error
+
+            for (int i = 0 ; i < MAXDEVICES + 1 ; i++)
+            {
+                m_storedOutputMode[i] = INVALIDSETTINGVALUE;
+                m_storedOutputSettings[i] = INVALIDSETTINGVALUE;
+                m_storedDataLength[i] = 0;
+            }
+
+            return (m_retVal = MTRV_OK);
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // readMessage
+        //
+        // Reads the next message from serial port buffer or file.
+        // To be read within current time out period
+        //
+        // Input
+        // Output
+        //   mid        : MessageID of message received
+        //   data       : array pointer to data bytes (no header)
+        //   dataLen    : number of data bytes read
+        //   bid        : BID or address of message read (optional)
+        //
+        //   returns MTRV_OK if a message has been read else <>MTRV_OK
+        //
+        // Remarks
+        //   allocate enough memory for message buffer
+        //   use setTimeOut for different timeout value
+        short CXsensMTiModule::readMessage(unsigned char& mid, unsigned char data[], short& dataLen, unsigned char* bid)
+        {
+            unsigned char buffer[MAXMSGLEN ];
+            short msgLen;
+
+            if (!(m_fileOpen || m_portOpen))
+            {
+                return (m_retVal = MTRV_NOINPUTINITIALIZED);
+            }
+
+            if (readMessageRaw(buffer, &msgLen) == MTRV_OK)
+            {
+                // Message read
+                mid = buffer[IND_MID];
+
+                if (bid != NULL)
+                {
+                    *bid = buffer[IND_BID];
+                }
+
+                if (buffer[IND_LEN] != EXTLENCODE)
+                {
+                    dataLen = buffer[IND_LEN];
+                    memcpy(data, &buffer[IND_DATA0], dataLen);
+                }
+                else
+                {
+                    dataLen = buffer[IND_LENEXTH] * 256 + buffer[IND_LENEXTL];
+                    memcpy(data, &buffer[IND_DATAEXT0], dataLen);
+                }
+            }
+
+            return m_retVal;
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // readDataMessage
+        //
+        // Read a MTData or XMData message from serial port (using TimeOut val)
+        //
+        // Input
+        //   data       : pointer to buffer in which the DATA field of MTData/XMData is stored
+        //   dataLen    : number of bytes in buffer (= number bytes in DATA field)
+        // Output
+        //   returns MTRV_OK if MTData / XMData message has been read else <>MTRV_OK
+        //
+        // Remarks
+        //   allocate enough memory for data buffer
+        //   use setTimeOut for different timeout value
+        short CXsensMTiModule::readDataMessage(unsigned char data[], short& dataLen)
+        {
+            if (!(m_portOpen || m_fileOpen))
+            {
+                return (m_retVal = MTRV_NOINPUTINITIALIZED);
+            }
+
+            unsigned char buffer[MAXMSGLEN ];
+            short buflen;
+
+            if (readMessageRaw(buffer, &buflen) == MTRV_OK)
+            {
+                if (buffer[IND_MID] == MID_MTDATA)
+                {
+                    // MID_XMDATA is same
+                    if (buffer[IND_LEN] != EXTLENCODE)
+                    {
+                        dataLen = buffer[IND_LEN];
+                        memcpy(data, &buffer[IND_DATA0], dataLen);
+                    }
+                    else
+                    {
+                        dataLen = buffer[IND_LENEXTH] * 256 + buffer[IND_LENEXTL];
+                        memcpy(data, &buffer[IND_DATAEXT0], dataLen);
+                    }
+
+                    return (m_retVal = MTRV_OK);
+                }
+                else if (buffer[IND_MID] == MID_ERROR)
+                {
+                    m_deviceError = buffer[IND_DATA0];
+                    return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
+                }
+            }
+
+            return m_retVal;
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // readMessageRaw
+        //
+        // Read a message from serial port for a certain period
+        //
+        // Input
+        //   msgBuffer      : pointer to buffer in which next msg will be stored
+        //   msgBufferLength: integer to number of bytes written in buffer (header + data + chksum)
+        // Output
+        //   returns MTRV_OK if a message has been read else <>MTRV_OK
+        //
+        // Remarks
+        //   allocate enough memory for message buffer
+        //   use setTimeOut for different timeout value
+        short CXsensMTiModule::readMessageRaw(unsigned char* msgBuffer, short* msgBufferLength)
+        {
+            int state = 0;
+            int nBytesToRead = 1;
+            int nBytesRead = 0;
+            int nOffset = 0;
+            int nMsgDataLen = 0;
+            int nMsgLen;
+            unsigned char chCheckSum;
+            bool Synced = false;
+
+            if (!(m_portOpen || m_fileOpen))
+            {
+                return (m_retVal = MTRV_NOINPUTINITIALIZED);
+            }
+
+            // Copy previous read bytes if available
+            if (m_nTempBufferLen > 0)
+            {
+                memcpy(msgBuffer, m_tempBuffer, m_nTempBufferLen);
+                nBytesRead = m_nTempBufferLen;
+                m_nTempBufferLen = 0;
+            }
+
+            clock_t clkStart = clockms();       // Get current processor time
+            clock_t clkEnd = m_clkEnd;      // check if the end timer is already set
+
+            if (clkEnd == 0)
+            {
+                clkEnd = clkStart + m_timeOut;
+            }
+
+            while (true)
+            {
+                do
+                {
+                    // First check if we already have some bytes read
+                    if (nBytesRead > 0 && nBytesToRead > 0)
+                    {
+                        if (nBytesToRead > nBytesRead)
+                        {
+                            nOffset += nBytesRead;
+                            nBytesToRead -= nBytesRead;
+                            nBytesRead = 0;
+                        }
+                        else
+                        {
+                            nOffset += nBytesToRead;
+                            nBytesRead -= nBytesToRead;
+                            nBytesToRead = 0;
+                        }
+                    }
+
+                    // Check if serial port buffer must be read
+                    if (nBytesToRead > 0)
+                    {
+                        nBytesRead = readData(msgBuffer + nOffset, nBytesToRead);
+
+                        if (m_retVal == MTRV_ENDOFFILE)
+                        {
+                            return (m_retVal = MTRV_ENDOFFILE);
+                        }
+
+                        nOffset += nBytesRead;
+                        nBytesToRead -= nBytesRead;
+                        nBytesRead = 0;
+                    }
+
+                    if (!nBytesToRead)
+                    {
+                        switch (state)
+                        {
+                            case 0:                 // Check preamble
+                                if (msgBuffer[IND_PREAMBLE] == PREAMBLE)
+                                {
+                                    state++;
+                                    nBytesToRead = 3;
+                                }
+                                else
+                                {
+                                    nOffset = 0;
+                                    nBytesToRead = 1;
+                                }
+
+                                break;
+
+                            case 1:                 // Check ADDR, MID, LEN
+                                if (msgBuffer[IND_LEN] != 0xFF)
+                                {
+                                    state = 3;
+                                    nBytesToRead = (nMsgDataLen = msgBuffer[IND_LEN]) + 1;   // Read LEN + 1 (chksum)
+                                }
+                                else
+                                {
+                                    state = 2;
+                                    nBytesToRead = 2;   // Read extended length
+                                }
+
+                                break;
+
+                            case 2:
+                                state = 3;
+                                nBytesToRead = (nMsgDataLen = msgBuffer[IND_LENEXTH] * 256 + msgBuffer[IND_LENEXTL]) + 1;   // Read LENEXT + CS
+
+                                if (nMsgDataLen > MAXMSGLEN - LEN_MSGEXTHEADERCS)
+                                {
+                                    // Not synced - check for preamble in the bytes read
+                                    for (int i = 1 ; i < LEN_MSGEXTHEADER ; i++)
+                                        if (msgBuffer[i] == PREAMBLE)
+                                        {
+                                            // Found a maybe preamble - 'fill buffer'
+                                            nBytesRead = LEN_MSGEXTHEADER - i;
+                                            memmove(msgBuffer, msgBuffer + i, nBytesRead);
+                                            break;
+                                        }
+
+                                    Synced = false;
+                                    nOffset = 0;
+                                    state = 0;
+                                    nBytesToRead = 1;           // Start looking for preamble
+                                }
+
+                                break;
+
+                            case 3:                 // Check msg
+                                chCheckSum = 0;
+                                nMsgLen = nMsgDataLen + 5 + (msgBuffer[IND_LEN] == 0xFF ? 2 : 0);
+
+                                for (int i = 1 ; i < nMsgLen ; i++)
+                                {
+                                    chCheckSum += msgBuffer[i];
+                                }
+
+                                if (chCheckSum == 0)
+                                {
+                                    // Checksum ok?
+                                    if (nBytesRead > 0)
+                                    {
+                                        // Store bytes if read too much
+                                        memcpy(m_tempBuffer, msgBuffer + nMsgLen, nBytesRead);
+                                        m_nTempBufferLen = nBytesRead;
+                                    }
+
+                                    *msgBufferLength = nMsgLen;
+                                    Synced = true;
+                                    return (m_retVal = MTRV_OK);
+                                }
+                                else
+                                {
+                                    if (!Synced)
+                                        for (int i = 1 ; i < nMsgLen ; i++)         // Not synced - maybe recheck for preamble in this incorrect message
+                                            if (msgBuffer[i] == PREAMBLE)
+                                            {
+                                                // Found a maybe preamble - 'fill buffer'
+                                                nBytesRead = nMsgLen - i;
+                                                memmove(msgBuffer, msgBuffer + i, nBytesRead);
+                                                break;
+                                            }
+
+                                    Synced = false;
+                                    nOffset = 0;
+                                    state = 0;
+                                    nBytesToRead = 1;           // Start looking for preamble
+                                }
+
+                                break;
+                        }
+                    }
+                }
+                while ((clkEnd >= clockms()) || m_timeOut == 0 || nBytesRead != 0);
+
+                // Check if pending message has a valid message
+                if (state > 0)
+                {
+                    int i;
+
+                    // Search for preamble
+                    for (i = 1; i < nOffset ; i++)
+                        if (msgBuffer[i] == PREAMBLE)
+                        {
+                            // Found a maybe preamble - 'fill buffer'
+                            nBytesRead = nOffset - i - 1;           // no preamble
+                            memmove(msgBuffer + 1, msgBuffer + i + 1, nBytesRead);
+                            break;
+                        }
+
+                    if (i < nOffset)
+                    {
+                        // Found preamble in message - recheck
+                        nOffset = 1;
+                        state = 1;
+                        nBytesToRead = 3;           // Start looking for preamble
+                        continue;
+                    }
+                }
+
+                break;
+            }
+
+            return (m_retVal = MTRV_TIMEOUT);
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // writeMessage (optional: integer value)
+        //
+        // Sends a message and in case of an serial port interface it checks
+        //   if the return message (ack, error or timeout). See return value
+        //   In case an file is opened the functions returns directly after
+        //   'sending' the message
+        //
+        //   Use this function for GotoConfig, Reset, ResetOrientation etc
+        //
+        // Input
+        //   mid          : MessageID of message to send
+        //   dataValue    : A integer value that will be included into the data message field
+        //                  can be a 1,2 or 4 bytes values
+        //   dataValueLen : Size of dataValue in bytes
+        //   bid          : BID or address to use in message to send (default = 0xFF)
+        //
+        // Return value
+        //   = MTRV_OK if an Ack message received / or data successfully written to file
+        //   = MTRV_RECVERRORMSG if an error message received
+        //   = MTRV_TIMEOUT if timeout occurred
+        //   = MTRV_NOINPUTINITIALIZED
+        //
+        short CXsensMTiModule::writeMessage(const unsigned char mid, const unsigned long dataValue, const unsigned char dataValueLen, const unsigned char bid)
+        {
+            unsigned char buffer[MAXMSGLEN ];
+            short msgLen;
+
+            if (!(m_fileOpen || m_portOpen))
+            {
+                return (m_retVal = MTRV_NOINPUTINITIALIZED);
+            }
+
+            buffer[IND_PREAMBLE] = PREAMBLE;
+            buffer[IND_BID] = bid;
+            buffer[IND_MID] = mid;
+            buffer[IND_LEN] = dataValueLen;
+
+            if (dataValueLen)
+            {
+                swapEndian((const unsigned char*) &dataValue, &buffer[IND_DATA0], dataValueLen);
+            }
+
+            calcChecksum(buffer, LEN_MSGHEADER + dataValueLen);
+
+            // Send message
+            writeData(buffer, LEN_MSGHEADERCS + dataValueLen);
+
+            // Return if file opened
+            if (m_fileOpen)
+            {
+                return (m_retVal = MTRV_OK);
+            }
+
+            // Keep reading until an Ack or Error message is received (or timeout)
+            clock_t clkStart , clkOld;
+            bool msgRead = false;
+
+            clkStart = clockms();           // Get current processor time
+            clkOld = m_clkEnd;
+
+            if (clkOld == 0)
+            {
+                m_clkEnd = m_timeOut + clkStart;
+            }
+
+            while (m_clkEnd >= clockms() || (m_timeOut == 0))
+            {
+                if (readMessageRaw(buffer, &msgLen) == MTRV_OK)
+                {
+                    // Message received
+                    msgRead = true;
+
+                    if (buffer[IND_MID] == (mid + 1))
+                    {
+                        m_clkEnd = clkOld;
+                        return (m_retVal = MTRV_OK);                // Acknowledge received
+                    }
+                    else if (buffer[IND_MID] == MID_ERROR)
+                    {
+                        m_deviceError = buffer[IND_DATA0];
+                        m_clkEnd = clkOld;
+                        return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
+                    }
+                }
+            }
+
+            m_clkEnd = clkOld;
+
+            if (msgRead)
+            {
+                return (m_retVal = MTRV_TIMEOUT);
+            }
+            else
+            {
+                return (m_retVal = MTRV_TIMEOUTNODATA);
+            }
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // writeMessage (data array)
+        //
+        // Sends a message and in case of an serial port interface it checks
+        //   if the return message (ack, error or timeout). See return value
+        //   In case an file is opened the functions returns directly after
+        //   'sending' the message
+        //
+        // Input
+        //   mid        : MessageID of message to send
+        //   data       : array pointer to data bytes
+        //   dataLen    : number of bytes to include in message
+        //   bid        : BID or address to use in message to send (default = 0xFF)
+        //
+        // Output
+        //   = MTRV_OK if an Ack message received
+        //   = MTRV_RECVERRORMSG if an error message received
+        //   = MTRV_TIMEOUT if timeout occurred
+        //   = MTRV_NOINPUTINITIALIZED
+        //
+        short CXsensMTiModule::writeMessage(const unsigned char mid, const unsigned char data[], const unsigned short& dataLen, const unsigned char bid)
+        {
+            unsigned char buffer[MAXMSGLEN ];
+            short msgLen;
+            short headerLength;
+
+            if (!(m_fileOpen || m_portOpen))
+            {
+                return (m_retVal = MTRV_NOINPUTINITIALIZED);
+            }
+
+            // Build message to send
+            buffer[IND_PREAMBLE] = PREAMBLE;
+            buffer[IND_BID] = bid;
+            buffer[IND_MID] = mid;
+
+            if (dataLen < EXTLENCODE)
+            {
+                buffer[IND_LEN] = (unsigned char) dataLen;
+                headerLength = LEN_MSGHEADER;
+            }
+            else
+            {
+                buffer[IND_LEN] = EXTLENCODE;
+                buffer[IND_LENEXTH] = (unsigned char)(dataLen >> 8);
+                buffer[IND_LENEXTL] = (unsigned char)(dataLen & 0x00FF);
+                headerLength = LEN_MSGEXTHEADER;
+            }
+
+            memcpy(&buffer[headerLength], data, dataLen);
+            calcChecksum(buffer, headerLength + dataLen);
+
+            // Send message
+            writeData(buffer, headerLength + dataLen + LEN_CHECKSUM);
+
+            // Return if file opened
+            if (m_fileOpen)
+            {
+                return (m_retVal = MTRV_OK);
+            }
+
+            // Keep reading until an Ack or Error message is received (or timeout)
+            bool msgRead = false;
+            clock_t clkStart , clkOld;
+
+            clkStart = clockms();   // Get current processor time
+            clkOld = m_clkEnd;
+
+            if (clkOld == 0)
+            {
+                m_clkEnd = m_timeOut + clkStart;
+            }
+
+            while (m_clkEnd >= clockms() || (m_timeOut == 0))
+            {
+                if (readMessageRaw(buffer, &msgLen) == MTRV_OK)
+                {
+                    // Message received
+                    msgRead = true;
+
+                    if (buffer[IND_MID] == (mid + 1))
+                    {
+                        m_clkEnd = clkOld;
+                        return (m_retVal = MTRV_OK);                // Acknowledge received
+                    }
+                    else if (buffer[IND_MID] == MID_ERROR)
+                    {
+                        m_deviceError = buffer[IND_DATA0];
+                        m_clkEnd = clkOld;
+                        return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
+                    }
+                }
+            }
+
+            m_clkEnd = clkOld;
+
+            if (msgRead)
+            {
+                return (m_retVal = MTRV_TIMEOUT);
+            }
+            else
+            {
+                return (m_retVal = MTRV_TIMEOUTNODATA);
+            }
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // waitForMessage
+        //
+        // Read messages from serial port or file using the current timeout period
+        //  until the received message is equal to a specific message identifier
+        // By default the timeout period by file input is set to infinity (= until
+        //  end of file is reached)
+        //
+        // Input/Output
+        //   mid            : message identifier of message that should be returned
+        //   data           : pointer to buffer in which the data of the requested msg will be stored
+        //   dataLen        : integer to number of data bytes
+        //   bid            : optional, pointer which holds the bid of the returned message
+        // Output
+        //   returns MTRV_OK if the message has been read else != MTRV_OK
+        //
+        // Remarks
+        //   allocate enough memory for data message buffer
+        //   use setTimeOut for different timeout value
+        short CXsensMTiModule::waitForMessage(const unsigned char mid, unsigned char data[], short* dataLen, unsigned char* bid)
+        {
+            unsigned char buffer[MAXMSGLEN ];
+            short buflen;
+
+            clock_t clkStart , clkOld;
+
+            if (!(m_fileOpen || m_portOpen))
+            {
+                return (m_retVal = MTRV_NOINPUTINITIALIZED);
+            }
+
+            clkStart = clockms();       // Get current processor time
+            clkOld = m_clkEnd;
+
+            if (clkOld == 0)
+            {
+                m_clkEnd = m_timeOut + clkStart;
+            }
+
+            while (m_clkEnd >= clockms() || (m_timeOut == 0))
+            {
+                if (readMessageRaw(buffer, &buflen) == MTRV_OK)
+                {
+                    if (buffer[IND_MID] == mid)
+                    {
+                        if (bid != NULL)
+                        {
+                            *bid = buffer[IND_BID];
+                        }
+
+                        if (data != NULL && dataLen != NULL)
+                        {
+                            if (buffer[IND_LEN] != EXTLENCODE)
+                            {
+                                *dataLen = buffer[IND_LEN];
+                                memcpy(data, &buffer[IND_DATA0], *dataLen);
+                            }
+                            else
+                            {
+                                *dataLen = buffer[IND_LENEXTH] * 256 + buffer[IND_LENEXTL];
+                                memcpy(data, &buffer[IND_DATAEXT0], *dataLen);
+                            }
+                        }
+                        else if (dataLen != NULL)
+                        {
+                            dataLen = 0;
+                        }
+
+                        m_clkEnd = clkOld;
+                        return (m_retVal = MTRV_OK);
+                    }
+                }
+                else if (m_retVal == MTRV_ENDOFFILE)
+                {
+                    m_clkEnd = clkOld;
+                    return (m_retVal = MTRV_ENDOFFILE);
+                }
+            }
+
+            m_clkEnd = clkOld;
+            return (m_retVal = MTRV_TIMEOUT);
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // reqSetting (integer & no param variant)
+        //
+        // Request a integer setting from the device. This setting
+        // can be an unsigned 1,2 or 4 bytes setting. Only valid
+        // for serial port connections
+        //
+        // Input
+        //   mid        : Message ID of message to send
+        //   bid        : Bus ID of message to send (def 0xFF)
+        //
+        // Output
+        //   = MTRV_OK if an Ack message is received
+        //   = MTRV_RECVERRORMSG if an error message is received
+        //   = MTRV_TIMEOUT if timeout occurred
+        //
+        //   value contains the integer value of the data field of the ack message
+        //
+        short CXsensMTiModule::reqSetting(const unsigned char mid, unsigned long& value, const unsigned char bid)
+        {
+            unsigned char buffer[MAXMSGLEN ];
+            short msgLen;
+
+            if (m_fileOpen)
+            {
+                return (m_retVal = MTRV_INVALIDFORFILEINPUT);
+            }
+
+            if (!m_portOpen)
+            {
+                return (m_retVal = MTRV_NOINPUTINITIALIZED);
+            }
+
+            buffer[IND_PREAMBLE] = PREAMBLE;
+            buffer[IND_BID] = bid;
+            buffer[IND_MID] = mid;
+            buffer[IND_LEN] = 0;
+            calcChecksum(buffer, LEN_MSGHEADER + buffer[IND_LEN]);
+
+            // Send message
+            writeData(buffer, LEN_MSGHEADERCS + buffer[IND_LEN]);
+
+            // Read next message or else timeout
+            if (readMessageRaw(buffer, &msgLen) == MTRV_OK)
+            {
+                // Message received
+                if (buffer[IND_MID] == (mid + 1))
+                {
+                    // Acknowledge received
+                    value = 0;
+                    swapEndian(&buffer[IND_DATA0], (unsigned char*) &value, buffer[IND_LEN]);
+                    return (m_retVal = MTRV_OK);
+                }
+                else if (buffer[IND_MID] == MID_ERROR)
+                {
+                    m_deviceError = buffer[IND_DATA0];
+                    return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
+                }
+                else
+                {
+                    return (m_retVal = MTRV_UNEXPECTEDMSG);   // Unexpected message
+                }
+            }
+
+            return m_retVal;
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // reqSetting (integer & param variant)
+        //
+        // Request a integer setting from the device. This setting
+        // can be an unsigned 1,2 or 4 bytes setting. Only valid
+        // for serial port connections.
+        //
+        // Input
+        //   mid        : Message ID of message to send
+        //   param      : For messages that need a parameter
+        //   bid        : Bus ID of message to send (def 0xFF)
+        //
+        // Output
+        //   = MTRV_OK if an Ack message is received
+        //   = MTRV_RECVERRORMSG if an error message is received
+        //   = MTRV_TIMEOUT if timeout occurred
+        //
+        //   value contains the integer value of the data field of the ack message
+        //
+        short CXsensMTiModule::reqSetting(const unsigned char mid, const unsigned char param, unsigned long& value, const unsigned char bid)
+        {
+            unsigned char buffer[MAXMSGLEN ];
+            short msgLen;
+
+            if (m_fileOpen)
+            {
+                return (m_retVal = MTRV_INVALIDFORFILEINPUT);
+            }
+
+            if (!m_portOpen)
+            {
+                return (m_retVal = MTRV_NOINPUTINITIALIZED);
+            }
+
+            buffer[IND_PREAMBLE] = PREAMBLE;
+            buffer[IND_BID] = bid;
+            buffer[IND_MID] = mid;
+
+            if (param != 0xFF)
+            {
+                buffer[IND_LEN] = 1;
+                buffer[IND_DATA0] = param;
+            }
+            else
+            {
+                buffer[IND_LEN] = 0;
+            }
+
+            calcChecksum(buffer, LEN_MSGHEADER + buffer[IND_LEN]);
+
+            // Send message
+            writeData(buffer, LEN_MSGHEADERCS + buffer[IND_LEN]);
+
+            // Read next message or else timeout
+            if (readMessageRaw(buffer, &msgLen) == MTRV_OK)
+            {
+                // Message received
+                if (buffer[IND_MID] == (mid + 1))
+                {
+                    // Acknowledge received
+                    value = 0;
+
+                    if (param == 0xFF)
+                    {
+                        swapEndian(&buffer[IND_DATA0], (unsigned char*) &value, buffer[IND_LEN]);
+                    }
+                    else
+                    {
+                        swapEndian(&buffer[IND_DATA0] + 1, (unsigned char*) &value, buffer[IND_LEN] - 1);
+                    }
+
+                    return (m_retVal = MTRV_OK);
+                }
+                else if (buffer[IND_MID] == MID_ERROR)
+                {
+                    m_deviceError = buffer[IND_DATA0];
+                    return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
+                }
+                else
+                {
+                    return (m_retVal = MTRV_UNEXPECTEDMSG);   // Unexpected message
+                }
+            }
+
+            return m_retVal;
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // reqSetting (float & no param variant)
+        //
+        // Request a float setting from the device. Only valid
+        // for serial port connections.
+        //
+        // Input
+        //   mid        : Message ID of message to send
+        //   bid        : Bus ID of message to send (def 0xFF)
+        //
+        // Output
+        //   = MTRV_OK if an Ack message is received
+        //   = MTRV_RECVERRORMSG if an error message is received
+        //   = MTRV_TIMEOUT if timeout occurred
+        //
+        //   value contains the float value of the acknowledge data field
+        //
+        short CXsensMTiModule::reqSetting(const unsigned char mid, float& value, const unsigned char bid)
+        {
+            unsigned char buffer[MAXMSGLEN ];
+            short msgLen;
+
+            if (m_fileOpen)
+            {
+                return (m_retVal = MTRV_INVALIDFORFILEINPUT);
+            }
+
+            if (!m_portOpen)
+            {
+                return (m_retVal = MTRV_NOINPUTINITIALIZED);
+            }
+
+            buffer[IND_PREAMBLE] = PREAMBLE;
+            buffer[IND_BID] = bid;
+            buffer[IND_MID] = mid;
+            buffer[IND_LEN] = 0;
+            calcChecksum(buffer, LEN_MSGHEADER + buffer[IND_LEN]);
+
+            // Send message
+            writeData(buffer, LEN_MSGHEADERCS + buffer[IND_LEN]);
+
+            // Read next message or else timeout
+            if (readMessageRaw(buffer, &msgLen) == MTRV_OK)
+            {
+                // Message received
+                if (buffer[IND_MID] == (mid + 1))
+                {
+                    // Acknowledge received
+                    value = 0;
+                    swapEndian(&buffer[IND_DATA0], (unsigned char*) &value, buffer[IND_LEN]);
+                    return (m_retVal = MTRV_OK);
+                }
+                else if (buffer[IND_MID] == MID_ERROR)
+                {
+                    m_deviceError = buffer[IND_DATA0];
+                    return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
+                }
+                else
+                {
+                    return (m_retVal = MTRV_UNEXPECTEDMSG);   // Unexpected message
+                }
+            }
+
+            return m_retVal;
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // reqSetting (float & param variant)
+        //
+        // Request a float setting from the device. Only valid
+        // for serial port connections.
+        //
+        // Input
+        //   mid        : Message ID of message to send
+        //   param      : For messages that need a parameter (optional)
+        //   bid        : Bus ID of message to send (def 0xFF)
+        //
+        // Output
+        //   = MTRV_OK if an Ack message is received
+        //   = MTRV_RECVERRORMSG if an error message is received
+        //   = MTRV_TIMEOUT if timeout occurred
+        //
+        //   value contains the float value of the acknowledge data field
+        //
+        short CXsensMTiModule::reqSetting(const unsigned char mid, const unsigned char param, float& value, const unsigned char bid)
+        {
+            unsigned char buffer[MAXMSGLEN ];
+            short msgLen;
+
+            if (m_fileOpen)
+            {
+                return (m_retVal = MTRV_INVALIDFORFILEINPUT);
+            }
+
+            if (!m_portOpen)
+            {
+                return (m_retVal = MTRV_NOINPUTINITIALIZED);
+            }
+
+            buffer[IND_PREAMBLE] = PREAMBLE;
+            buffer[IND_BID] = bid;
+            buffer[IND_MID] = mid;
+
+            if (param != 0xFF)
+            {
+                buffer[IND_LEN] = 1;
+                buffer[IND_DATA0] = param;
+            }
+            else
+            {
+                buffer[IND_LEN] = 0;
+            }
+
+            calcChecksum(buffer, LEN_MSGHEADER + buffer[IND_LEN]);
+
+            // Send message
+            writeData(buffer, LEN_MSGHEADERCS + buffer[IND_LEN]);
+
+            // Read next message or else timeout
+            if (readMessageRaw(buffer, &msgLen) == MTRV_OK)
+            {
+                // Message received
+                if (buffer[IND_MID] == (mid + 1))
+                {
+                    // Acknowledge received
+                    value = 0;
+
+                    if (param == 0xFF)
+                    {
+                        swapEndian(&buffer[IND_DATA0], (unsigned char*) &value, buffer[IND_LEN]);
+                    }
+                    else
+                    {
+                        swapEndian(&buffer[IND_DATA0] + 1, (unsigned char*) &value, buffer[IND_LEN] - 1);
+                    }
+
+                    return (m_retVal = MTRV_OK);
+                }
+                else if (buffer[IND_MID] == MID_ERROR)
+                {
+                    m_deviceError = buffer[IND_DATA0];
+                    return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
+                }
+                else
+                {
+                    return (m_retVal = MTRV_UNEXPECTEDMSG);   // Unexpected message
+                }
+            }
+
+            return m_retVal;
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // reqSetting (byte array & no param variant)
+        //
+        // Send a message to the device and the data of acknowledge message
+        // will be returned. Only valid for serial port connections
+        //
+        // Input
+        //   mid        : Message ID of message to send
+        //   bid        : Bus ID of message to send (def 0xFF)
+        //
+        // Output
+        //   = MTRV_OK if an Ack message is received
+        //   = MTRV_RECVERRORMSG if an error message is received
+        //   = MTRV_TIMEOUT if timeout occurred
+        //
+        //   data[] contains the data of the acknowledge message
+        //   dataLen contains the number bytes returned
+        //
+        short CXsensMTiModule::reqSetting(const unsigned char mid, unsigned char data[], short& dataLen, const unsigned char bid)
+        {
+            unsigned char buffer[MAXMSGLEN ];
+            short msgLen;
+
+            if (m_fileOpen)
+            {
+                return (m_retVal = MTRV_INVALIDFORFILEINPUT);
+            }
+
+            if (!m_portOpen)
+            {
+                return (m_retVal = MTRV_NOINPUTINITIALIZED);
+            }
+
+            buffer[IND_PREAMBLE] = PREAMBLE;
+            buffer[IND_BID] = bid;
+            buffer[IND_MID] = mid;
+            buffer[IND_LEN] = 0;
+            calcChecksum(buffer, LEN_MSGHEADER + buffer[IND_LEN]);
+
+            // Send message
+            writeData(buffer, LEN_MSGHEADERCS + buffer[IND_LEN]);
+
+            dataLen = 0;
+
+            // Read next message or else timeout
+            if (readMessageRaw(buffer, &msgLen) == MTRV_OK)
+            {
+                // Message received
+                if (buffer[IND_MID] == (mid + 1))
+                {
+                    // Acknowledge received
+                    if (buffer[IND_LEN] != EXTLENCODE)
+                    {
+                        dataLen = buffer[IND_LEN];
+                        memcpy(data, &buffer[IND_DATA0], dataLen);
+                    }
+                    else
+                    {
+                        dataLen = buffer[IND_LENEXTH] * 256 + buffer[IND_LENEXTL];
+                        memcpy(data, &buffer[IND_DATAEXT0], dataLen);
+                    }
+
+                    return (m_retVal = MTRV_OK);
+                }
+                else if (buffer[IND_MID] == MID_ERROR)
+                {
+                    m_deviceError = buffer[IND_DATA0];
+                    return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
+                }
+                else
+                {
+                    return (m_retVal = MTRV_UNEXPECTEDMSG);   // Unexpected message
+                }
+            }
+
+            return m_retVal;
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // reqSetting (byte array in + out & no param variant)
+        //
+        // Send a message to the device and the data of acknowledge message
+        // will be returned. Only valid for serial port connections
+        //
+        // Input
+        //   mid        : Message ID of message to send
+        //   bid        : Bus ID of message to send (def 0xFF)
+        //   dataIn     : Data to be included in request
+        //   dataInLen  : Number of bytes in dataIn
+        //
+        // Output
+        //   = MTRV_OK if an Ack message is received
+        //   = MTRV_RECVERRORMSG if an error message is received
+        //   = MTRV_TIMEOUT if timeout occurred
+        //
+        //   dataOut[] contains the data of the acknowledge message
+        //   dataOutLen contains the number bytes returned
+        //
+        short CXsensMTiModule::reqSetting(const unsigned char mid, unsigned char dataIn[], short dataInLen, unsigned char dataOut[], short& dataOutLen, const unsigned char bid)
+        {
+            unsigned char buffer[MAXMSGLEN ];
+            short headerLength;
+            short msgLen;
+
+            if (m_fileOpen)
+            {
+                return (m_retVal = MTRV_INVALIDFORFILEINPUT);
+            }
+
+            if (!m_portOpen)
+            {
+                return (m_retVal = MTRV_NOINPUTINITIALIZED);
+            }
+
+            buffer[IND_PREAMBLE] = PREAMBLE;
+            buffer[IND_BID] = bid;
+            buffer[IND_MID] = mid;
+
+            if (dataInLen < EXTLENCODE)
+            {
+                buffer[IND_LEN] = (unsigned char) dataInLen;
+                headerLength = LEN_MSGHEADER;
+            }
+            else
+            {
+                buffer[IND_LEN] = EXTLENCODE;
+                buffer[IND_LENEXTH] = (unsigned char)(dataInLen >> 8);
+                buffer[IND_LENEXTL] = (unsigned char)(dataInLen & 0x00FF);
+                headerLength = LEN_MSGEXTHEADER;
+            }
+
+            memcpy(&buffer[headerLength], dataIn, dataInLen);
+            calcChecksum(buffer, headerLength + dataInLen);
+
+            // Send message
+            writeData(buffer, headerLength + dataInLen + LEN_CHECKSUM);
+
+            dataOutLen = 0;
+
+            // Read next message or else timeout
+            if (readMessageRaw(buffer, &msgLen) == MTRV_OK)
+            {
+                // Message received
+                if (buffer[IND_MID] == (mid + 1))
+                {
+                    // Acknowledge received
+                    if (buffer[IND_LEN] != EXTLENCODE)
+                    {
+                        dataOutLen = buffer[IND_LEN];
+                        memcpy(dataOut, &buffer[IND_DATA0], dataOutLen);
+                    }
+                    else
+                    {
+                        dataOutLen = buffer[IND_LENEXTH] * 256 + buffer[IND_LENEXTL];
+                        memcpy(dataOut, &buffer[IND_DATAEXT0], dataOutLen);
+                    }
+
+                    return (m_retVal = MTRV_OK);
+                }
+                else if (buffer[IND_MID] == MID_ERROR)
+                {
+                    m_deviceError = buffer[IND_DATA0];
+                    return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
+                }
+                else
+                {
+                    return (m_retVal = MTRV_UNEXPECTEDMSG);   // Unexpected message
+                }
+            }
+
+            return m_retVal;
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // reqSetting (byte array & param variant)
+        //
+        // Send a message to the device and the data of acknowledge message
+        // will be returned. Only valid for serial port connections
+        //
+        // Input
+        //   mid        : Message ID of message to send
+        //   param      : For messages that need a parameter (optional)
+        //   bid        : Bus ID of message to send (def 0xFF)
+        //
+        // Output
+        //   = MTRV_OK if an Ack message is received
+        //   = MTRV_RECVERRORMSG if an error message is received
+        //   = MTRV_TIMEOUT if timeout occurred
+        //
+        //   data[] contains the data of the acknowledge message (including param!!)
+        //   dataLen contains the number bytes returned
+        //
+        short CXsensMTiModule::reqSetting(const unsigned char mid, const unsigned char param, unsigned char data[], short& dataLen, const unsigned char bid)
+        {
+            unsigned char buffer[MAXMSGLEN ];
+            short msgLen;
+
+            if (m_fileOpen)
+            {
+                return (m_retVal = MTRV_INVALIDFORFILEINPUT);
+            }
+
+            if (!m_portOpen)
+            {
+                return (m_retVal = MTRV_NOINPUTINITIALIZED);
+            }
+
+            buffer[IND_PREAMBLE] = PREAMBLE;
+            buffer[IND_BID] = bid;
+            buffer[IND_MID] = mid;
+
+            if (param != 0xFF)
+            {
+                buffer[IND_LEN] = 1;
+                buffer[IND_DATA0] = param;
+            }
+            else
+            {
+                buffer[IND_LEN] = 0;
+            }
+
+            calcChecksum(buffer, LEN_MSGHEADER + buffer[IND_LEN]);
+
+            // Send message
+            writeData(buffer, LEN_MSGHEADERCS + buffer[IND_LEN]);
+
+            dataLen = 0;
+
+            // Read next message or else timeout
+            if (readMessageRaw(buffer, &msgLen) == MTRV_OK)
+            {
+                // Message received
+                if (buffer[IND_MID] == (mid + 1))
+                {
+                    // Acknowledge received
+                    if (buffer[IND_LEN] != EXTLENCODE)
+                    {
+                        dataLen = buffer[IND_LEN];
+                        memcpy(data, &buffer[IND_DATA0], dataLen);
+                    }
+                    else
+                    {
+                        dataLen = buffer[IND_LENEXTH] * 256 + buffer[IND_LENEXTL];
+                        memcpy(data, &buffer[IND_DATAEXT0], dataLen);
+                    }
+
+                    return (m_retVal = MTRV_OK);
+                }
+                else if (buffer[IND_MID] == MID_ERROR)
+                {
+                    m_deviceError = buffer[IND_DATA0];
+                    return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
+                }
+                else
+                {
+                    return (m_retVal = MTRV_UNEXPECTEDMSG);   // Unexpected message
+                }
+            }
+
+            return m_retVal;
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // setSetting (integer & no param variant)
+        //
+        // Sets a integer setting of the device. This setting
+        // can be an unsigned 1,2 or 4 bytes setting. Only valid
+        // for serial port connections.
+        //
+        // Input
+        //   mid        : Message ID of message to send
+        //   bid        : Bus ID of message to send (def 0xFF)
+        //   value      : Contains the integer value to be used
+        //   valuelen   : Length in bytes of the value
+        //
+        // Output
+        //   = MTRV_OK if an Ack message is received
+        //   = MTRV_RECVERRORMSG if an error message is received
+        //   = MTRV_TIMEOUT if timeout occurred
+        //
+        //
+        short CXsensMTiModule::setSetting(const unsigned char mid, const unsigned long value, const unsigned short valuelen, const unsigned char bid)
+        {
+            unsigned char buffer[MAXMSGLEN ];
+            short msgLen;
+
+            if (m_fileOpen)
+            {
+                return (m_retVal = MTRV_INVALIDFORFILEINPUT);
+            }
+
+            if (!m_portOpen)
+            {
+                return (m_retVal = MTRV_NOINPUTINITIALIZED);
+            }
+
+            msgLen = LEN_MSGHEADER;
+            buffer[IND_PREAMBLE] = PREAMBLE;
+            buffer[IND_BID] = bid;
+            buffer[IND_MID] = mid;
+            buffer[IND_LEN] = (unsigned char) valuelen;
+            swapEndian((unsigned char*) &value, &buffer[msgLen], valuelen);
+            calcChecksum(buffer, LEN_MSGHEADER + buffer[IND_LEN]);
+
+            // Send message
+            writeData(buffer, LEN_MSGHEADERCS + buffer[IND_LEN]);
+
+            // Read next received message
+            if (readMessageRaw(buffer, &msgLen) == MTRV_OK)
+            {
+                // Message received
+                if (buffer[IND_MID] == (mid + 1))
+                {
+                    return (m_retVal = MTRV_OK);                // Acknowledge received
+                }
+                else if (buffer[IND_MID] == MID_ERROR)
+                {
+                    m_deviceError = buffer[IND_DATA0];
+                    return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
+                }
+            }
+
+            return m_retVal;
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // setSetting (integer & param variant)
+        //
+        // Sets a integer setting of the device. This setting
+        // can be an unsigned 1,2 or 4 bytes setting. Only valid
+        // for serial port connections.
+        //
+        // Input
+        //   mid        : Message ID of message to send
+        //   param      : For messages that need a parameter (optional)
+        //   bid        : Bus ID of message to send (def 0xFF)
+        //   value      : Contains the integer value to be used
+        //   valuelen   : Length in bytes of the value
+        //
+        // Output
+        //   = MTRV_OK if an Ack message is received
+        //   = MTRV_RECVERRORMSG if an error message is received
+        //   = MTRV_TIMEOUT if timeout occurred
+        //
+        //
+        short CXsensMTiModule::setSetting(const unsigned char mid, const unsigned char param, const unsigned long value, const unsigned short valuelen, const unsigned char bid)
+        {
+            unsigned char buffer[MAXMSGLEN ];
+            short msgLen;
+
+            if (m_fileOpen)
+            {
+                return (m_retVal = MTRV_INVALIDFORFILEINPUT);
+            }
+
+            if (!m_portOpen)
+            {
+                return (m_retVal = MTRV_NOINPUTINITIALIZED);
+            }
+
+            msgLen = LEN_MSGHEADER;
+            buffer[IND_PREAMBLE] = PREAMBLE;
+            buffer[IND_BID] = bid;
+            buffer[IND_MID] = mid;
+
+            if (param != 0xFF)
+            {
+                msgLen++;
+                buffer[IND_LEN] = valuelen + 1;
+                buffer[IND_DATA0] = param;
+            }
+            else
+            {
+                buffer[IND_LEN] = (unsigned char) valuelen;
+            }
+
+            swapEndian((unsigned char*) &value, &buffer[msgLen], valuelen);
+            calcChecksum(buffer, LEN_MSGHEADER + buffer[IND_LEN]);
+
+            // Send message
+            writeData(buffer, LEN_MSGHEADERCS + buffer[IND_LEN]);
+
+            // Read next received message
+            if (readMessageRaw(buffer, &msgLen) == MTRV_OK)
+            {
+                // Message received
+                if (buffer[IND_MID] == (mid + 1))
+                {
+                    return (m_retVal = MTRV_OK);                // Acknowledge received
+                }
+                else if (buffer[IND_MID] == MID_ERROR)
+                {
+                    m_deviceError = buffer[IND_DATA0];
+                    return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
+                }
+            }
+
+            return m_retVal;
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // setSetting (float & no param variant)
+        //
+        // Sets a float setting of the device. Only valid
+        // for serial port connections.
+        //
+        // Input
+        //   mid        : Message ID of message to send
+        //   bid        : Bus ID of message to send (def 0xFF)
+        //   value      : Contains the float value to be used
+        //
+        // Output
+        //   = MTRV_OK if an Ack message is received
+        //   = MTRV_RECVERRORMSG if an error message is received
+        //   = MTRV_TIMEOUT if timeout occurred
+        //
+        short CXsensMTiModule::setSetting(const unsigned char mid, const float value, const unsigned char bid)
+        {
+            unsigned char buffer[MAXMSGLEN ];
+            short msgLen;
+
+            if (m_fileOpen)
+            {
+                return (m_retVal = MTRV_INVALIDFORFILEINPUT);
+            }
+
+            if (!m_portOpen)
+            {
+                return (m_retVal = MTRV_NOINPUTINITIALIZED);
+            }
+
+            msgLen = LEN_MSGHEADER;
+            buffer[IND_PREAMBLE] = PREAMBLE;
+            buffer[IND_BID] = bid;
+            buffer[IND_MID] = mid;
+            buffer[IND_LEN] = LEN_FLOAT;
+            swapEndian((unsigned char*) &value, &buffer[msgLen], LEN_FLOAT);
+            calcChecksum(buffer, LEN_MSGHEADER + LEN_FLOAT);
+
+            // Send message
+            writeData(buffer, LEN_MSGHEADERCS + LEN_FLOAT);
+
+            // Read next received message
+            if (readMessageRaw(buffer, &msgLen) == MTRV_OK)
+            {
+                // Message received
+                if (buffer[IND_MID] == (mid + 1))
+                {
+                    return (m_retVal = MTRV_OK);                // Acknowledge received
+                }
+                else if (buffer[IND_MID] == MID_ERROR)
+                {
+                    m_deviceError = buffer[IND_DATA0];
+                    return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
+                }
+            }
+
+            return m_retVal;
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // setSetting (float & param variant)
+        //
+        // Sets a float setting of the device. Only valid
+        // for serial port connections.
+        //
+        // Input
+        //   mid        : Message ID of message to send
+        //   param      : For messages that need a parameter (optional)
+        //   bid        : Bus ID of message to send (def 0xFF)
+        //   value      : Contains the float value to be used
+        //
+        // Output
+        //   = MTRV_OK if an Ack message is received
+        //   = MTRV_RECVERRORMSG if an error message is received
+        //   = MTRV_TIMEOUT if timeout occurred
+        //
+        //
+        short CXsensMTiModule::setSetting(const unsigned char mid, const unsigned char param, const float value, const unsigned char bid)
+        {
+            unsigned char buffer[MAXMSGLEN ];
+            short msgLen;
+
+            if (m_fileOpen)
+            {
+                return (m_retVal = MTRV_INVALIDFORFILEINPUT);
+            }
+
+            if (!m_portOpen)
+            {
+                return (m_retVal = MTRV_NOINPUTINITIALIZED);
+            }
+
+            msgLen = LEN_MSGHEADER;
+            buffer[IND_PREAMBLE] = PREAMBLE;
+            buffer[IND_BID] = bid;
+            buffer[IND_MID] = mid;
+
+            if (param != 0xFF)
+            {
+                msgLen++;
+                buffer[IND_LEN] = LEN_FLOAT + 1;
+                buffer[IND_DATA0] = param;
+            }
+            else
+            {
+                buffer[IND_LEN] = LEN_FLOAT;
+            }
+
+            swapEndian((unsigned char*) &value, &buffer[msgLen], LEN_FLOAT);
+            calcChecksum(buffer, LEN_MSGHEADER + buffer[IND_LEN]);
+
+            // Send message
+            writeData(buffer, LEN_MSGHEADERCS + buffer[IND_LEN]);
+
+            // Read next received message
+            if (readMessageRaw(buffer, &msgLen) == MTRV_OK)
+            {
+                // Message received
+                if (buffer[IND_MID] == (mid + 1))
+                {
+                    return (m_retVal = MTRV_OK);                // Acknowledge received
+                }
+                else if (buffer[IND_MID] == MID_ERROR)
+                {
+                    m_deviceError = buffer[IND_DATA0];
+                    return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
+                }
+            }
+
+            return m_retVal;
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // setSetting (float & param & store variant)
+        //
+        // Sets a float setting of the device and with the Store field.
+        // Only valid for serial port connections
+        //
+        // Input
+        //   mid        : Message ID of message to send
+        //   param      : For messages that need a parameter (optional)
+        //   value      : Contains the float value to be used
+        //   store      ; Store in non-volatile memory (1) or not (0)
+        //   bid        : Bus ID of message to send (def 0xFF)
+        //
+        // Output
+        //   = MTRV_OK if an Ack message is received
+        //   = MTRV_RECVERRORMSG if an error message is received
+        //   = MTRV_TIMEOUT if timeout occurred
+        //
+        //
+        short CXsensMTiModule::setSetting(const unsigned char mid, const unsigned char param, const float value, const bool store, const unsigned char bid)
+        {
+            unsigned char buffer[MAXMSGLEN ];
+            short msgLen;
+
+            if (m_fileOpen)
+            {
+                return (m_retVal = MTRV_INVALIDFORFILEINPUT);
+            }
+
+            if (!m_portOpen)
+            {
+                return (m_retVal = MTRV_NOINPUTINITIALIZED);
+            }
+
+            msgLen = LEN_MSGHEADER;
+            buffer[IND_PREAMBLE] = PREAMBLE;
+            buffer[IND_BID] = bid;
+            buffer[IND_MID] = mid;
+
+            if (param != 0xFF)
+            {
+                msgLen++;
+                buffer[IND_LEN] = LEN_FLOAT + 2;
+                buffer[IND_DATA0] = param;
+            }
+            else
+            {
+                buffer[IND_LEN] = LEN_FLOAT + 1;
+            }
+
+            swapEndian((unsigned char*) &value, &buffer[msgLen], LEN_FLOAT);
+            buffer[msgLen + LEN_FLOAT ] = store;
+            calcChecksum(buffer, LEN_MSGHEADER + buffer[IND_LEN]);
+
+            // Send message
+            writeData(buffer, LEN_MSGHEADERCS + buffer[IND_LEN]);
+
+            // Read next received message
+            if (readMessageRaw(buffer, &msgLen) == MTRV_OK)
+            {
+                // Message received
+                if (buffer[IND_MID] == (mid + 1))
+                {
+                    return (m_retVal = MTRV_OK);            // Acknowledge received
+                }
+                else if (buffer[IND_MID] == MID_ERROR)
+                {
+                    m_deviceError = buffer[IND_DATA0];
+                    return (m_retVal = MTRV_RECVERRORMSG);   // Error message received
+                }
+            }
+
+            return m_retVal;
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // getDeviceMode
+        //
+        // Requests the current output mode/setting of input (file or serialport)
+        //  the Outputmode, Outputsettings, DataLength & number of devices
+        //  are stored in member variables of the MTComm class. These values
+        //  are needed for the GetValue functions.
+        //  The function optionally returns the number of devices
+        //
+        // File: expects the Configuration message at the start of the file
+        //       which holds the OutputMode & OutputSettings. File position
+        //       is after the first message
+        //
+        // Input
+        // Output
+        //   numDevices : [optional] number of devices connected to port or
+        //                found in configuration file
+        //
+        //   returns MTRV_OK if the mode & settings are read
+        //
+        short CXsensMTiModule::getDeviceMode(unsigned short* numDevices)
+        {
+            unsigned char mid = 0 , data[MAXMSGLEN ];
+            short datalen;
+
+            if (numDevices != NULL)
+            {
+                *numDevices = 0;
+            }
+
+            // In case serial port is used (live device / XM or MT)
+            if (m_portOpen)
+            {
+                if (reqSetting(MID_INITBUS, data, datalen) != MTRV_OK)
+                {
+                    return m_retVal;
+                }
+
+                // Retrieve outputmode + outputsettings
+                for (int i = 0 ; i < datalen / LEN_DEVICEID ; i++)
+                {
+                    if (reqSetting(MID_REQOUTPUTMODE, m_storedOutputMode[BID_MT + i], BID_MT + i) != MTRV_OK)
+                    {
+                        return m_retVal;
+                    }
+
+                    if (reqSetting(MID_REQOUTPUTSETTINGS, m_storedOutputSettings[BID_MT + i], BID_MT + i) != MTRV_OK)
+                    {
+                        return m_retVal;
+                    }
+
+                    if (reqSetting(MID_REQDATALENGTH, m_storedDataLength[BID_MT + i], BID_MT + i) != MTRV_OK)
+                    {
+                        return m_retVal;
+                    }
+                }
+
+                if (numDevices != NULL)
+                {
+                    *numDevices = datalen / LEN_DEVICEID;
+                }
+
+                unsigned char masterDID[4];
+                short DIDlen;
+
+                if (reqSetting(MID_REQDID, masterDID, DIDlen) != MTRV_OK)
+                {
+                    return m_retVal;
+                }
+
+                if (memcmp(masterDID, data, LEN_DEVICEID) != 0)
+                {
+                    // Using an XbusMaster
+                    m_storedOutputMode[0] = OUTPUTMODE_XM;
+                    m_storedOutputSettings[0] = OUTPUTSETTINGS_XM;
+                    m_storedDataLength[0] = LEN_SAMPLECNT;
+                }
+                else
+                {
+                    m_storedOutputMode[0] = m_storedOutputMode[BID_MT ];
+                    m_storedOutputSettings[0] = m_storedOutputSettings[BID_MT ];
+                    m_storedDataLength[0] = m_storedDataLength[BID_MT ];
+                }
+
+                return (m_retVal = MTRV_OK);
+            }
+            else if (m_fileOpen)
+            {
+                // Configuration message should be the first message in the file
+                setFilePos(0);
+
+                if (readMessage(mid, data, datalen) == MTRV_OK)
+                {
+                    if (mid == MID_CONFIGURATION)
+                    {
+                        unsigned short _numDevices = 0;
+                        swapEndian(data + CONF_NUMDEVICES, (unsigned char*) &_numDevices, CONF_NUMDEVICESLEN);
+
+                        for (unsigned int i = 0 ; i < _numDevices ; i++)
+                        {
+                            m_storedOutputMode[BID_MT + i] = 0;
+                            swapEndian(data + CONF_OUTPUTMODE + i * CONF_BLOCKLEN, (unsigned char*)(m_storedOutputMode + BID_MT + i),
+                                       CONF_OUTPUTMODELEN);
+                            m_storedOutputSettings[BID_MT + i] = 0;
+                            swapEndian(data + CONF_OUTPUTSETTINGS + i * CONF_BLOCKLEN, (unsigned char*)(m_storedOutputSettings + BID_MT + i),
+                                       CONF_OUTPUTSETTINGSLEN);
+                            m_storedDataLength[BID_MT + i] = 0;
+                            swapEndian(data + CONF_DATALENGTH + i * CONF_BLOCKLEN, (unsigned char*)(m_storedDataLength + BID_MT + i),
+                                       CONF_DATALENGTHLEN);
+                        }
+
+                        if (numDevices != NULL)
+                        {
+                            *numDevices = _numDevices;
+                        }
+
+                        if (memcmp(data + CONF_MASTERDID, data + CONF_DID, LEN_DEVICEID) != 0)
+                        {
+                            // Using an XbusMaster
+                            m_storedOutputMode[0] = OUTPUTMODE_XM;
+                            m_storedOutputSettings[0] = OUTPUTSETTINGS_XM;
+                            m_storedDataLength[0] = LEN_SAMPLECNT;
+                        }
+                        else
+                        {
+                            m_storedOutputMode[0] = m_storedOutputMode[BID_MT ];
+                            m_storedOutputSettings[0] = m_storedOutputSettings[BID_MT ];
+                            m_storedDataLength[0] = m_storedDataLength[BID_MT ];
+                        }
+
+                        return (m_retVal = MTRV_OK);
+                    }
+                }
+
+                return (m_retVal = MTRV_NOTSUCCESSFUL);
+            }
+
+            return (m_retVal = MTRV_NOINPUTINITIALIZED);
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // setDeviceMode
+        //
+        // Sets the current output mode/setting of input (not for file-based
+        //   inputs)
+        //
+        // Input
+        //   OutputMode     : OutputMode to be set in device & stored in MTComm
+        //                      class member variable
+        //   OutputSettings : OutputSettings to be set in device & stored in
+        //                      MTComm class member variable
+        // Output
+        //
+        //   returns MTRV_OK if the mode & settings are read
+        //
+        short CXsensMTiModule::setDeviceMode(unsigned long OutputMode, unsigned long OutputSettings, const unsigned char bid)
+        {
+            // In case serial port is used (live XM / MT)
+            if (m_portOpen)
+            {
+                // Set OutputMode
+                if (setSetting(MID_SETOUTPUTMODE, OutputMode, LEN_OUTPUTMODE, bid) != MTRV_OK)
+                {
+                    return m_retVal;
+                }
+
+                if (bid == BID_MASTER || (bid == BID_MT && m_storedOutputMode[0] != OUTPUTMODE_XM))
+                {
+                    m_storedOutputMode[0] = m_storedOutputMode[BID_MT ] = OutputMode;
+                }
+                else
+                {
+                    m_storedOutputMode[bid] = OutputMode;
+                }
+
+                // Set OutputSettings
+                if (setSetting(MID_SETOUTPUTSETTINGS, OutputSettings, LEN_OUTPUTSETTINGS, bid) != MTRV_OK)
+                {
+                    return m_retVal;
+                }
+
+                if (bid == BID_MASTER || (bid == BID_MT && m_storedOutputMode[0] != OUTPUTMODE_XM))
+                {
+                    m_storedOutputSettings[0] = m_storedOutputSettings[BID_MT ] = OutputSettings;
+                }
+                else
+                {
+                    m_storedOutputSettings[bid] = OutputSettings;
+                }
+
+                // Get DataLength from device
+                if (OutputMode != OUTPUTMODE_XM)
+                {
+                    unsigned long value;
+
+                    if (reqSetting(MID_REQDATALENGTH, value, bid) == MTRV_OK)
+                    {
+                        if ((bid == BID_MASTER) || ((bid == BID_MT) && (m_storedOutputMode[0] != OUTPUTMODE_XM)))
+                        {
+                            m_storedDataLength[0] = m_storedDataLength[BID_MT ] = value;
+                        }
+                        else
+                        {
+                            m_storedDataLength[bid] = value;
+                        }
+                    }
+                }
+                else
+                {
+                    m_storedDataLength[0] = LEN_SAMPLECNT;
+                }
+
+                return (m_retVal = MTRV_OK);
+            }
+
+            return (m_retVal = MTRV_INVALIDFORFILEINPUT);
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // getMode
+        //
+        // Gets the output mode/setting used in MTComm class and the corresponding
+        //  datalength. These variables are set by the functions GetDeviceMode,
+        //  SetDeviceMode or SetMode
+        //
+        // Input
+        // Output
+        //   OutputMode     : OutputMode stored in MTComm class member variable
+        //   OutputSettings : OutputSettings stored in MTComm class member variable
+        //
+        //   returns always MTRV_OK
+        //
+        short CXsensMTiModule::getMode(unsigned long& OutputMode, unsigned long& OutputSettings, unsigned short& dataLength, const unsigned char bid)
+        {
+            unsigned char nbid = (bid == BID_MASTER) ? 0 : bid;
+            OutputMode = m_storedOutputMode[nbid];
+            OutputSettings = m_storedOutputSettings[nbid];
+            dataLength = (unsigned short) m_storedDataLength[nbid];
+            return (m_retVal = MTRV_OK);
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // setMode
+        //
+        // Sets the output mode/setting used in MTComm class. Use the function
+        //  GetDeviceMode to retrieve the current values of file/device.
+        // This function will also calculate the data length field
+        //
+        // Input
+        //   OutputMode     : OutputMode to be stored in MTComm class member variable
+        //   OutputSettings : OutputSettings to be stored in MTComm class member variable
+        // Output
+        //
+        //   returns always MTRV_OK
+        //
+        short CXsensMTiModule::setMode(unsigned long OutputMode, unsigned long OutputSettings, const unsigned char bid)
+        {
+            unsigned char nbid = bid;
+
+            if (nbid == BID_MASTER)
+            {
+                nbid = 0;
+            }
+
+            m_storedOutputMode[nbid] = OutputMode;
+            m_storedOutputSettings[nbid] = OutputSettings;
+
+            if (OutputMode == INVALIDSETTINGVALUE || OutputSettings == INVALIDSETTINGVALUE)
+            {
+                m_storedDataLength[nbid] = 0;
+            }
+            else
+            {
+                unsigned short dataLength = 0;
+
+                if (OutputMode & OUTPUTMODE_MT9)
+                {
+                    dataLength = ((OutputSettings & OUTPUTSETTINGS_TIMESTAMP_MASK) == OUTPUTSETTINGS_TIMESTAMP_SAMPLECNT) ? LEN_SAMPLECNT : 0 + LEN_RAWDATA;
+                }
+                else if (OutputMode == OUTPUTMODE_XM)
+                {
+                    // XbusMaster concatenates sample counter
+                    dataLength = LEN_SAMPLECNT;
+                }
+                else
+                {
+                    if (OutputMode & OUTPUTMODE_RAW)
+                    {
+                        dataLength = LEN_RAWDATA;
+                    }
+                    else
+                    {
+                        if (OutputMode & OUTPUTMODE_CALIB)
+                        {
+                            dataLength = LEN_CALIBDATA;
+                        }
+
+                        if (OutputMode & OUTPUTMODE_ORIENT)
+                        {
+                            switch (OutputSettings & OUTPUTSETTINGS_ORIENTMODE_MASK)
+                            {
+                                case OUTPUTSETTINGS_ORIENTMODE_QUATERNION:
+                                    dataLength += LEN_ORIENT_QUATDATA;
+                                    break;
+
+                                case OUTPUTSETTINGS_ORIENTMODE_EULER:
+                                    dataLength += LEN_ORIENT_EULERDATA;
+                                    break;
+
+                                case OUTPUTSETTINGS_ORIENTMODE_MATRIX:
+                                    dataLength += LEN_ORIENT_MATRIXDATA;
+                                    break;
+
+                                default:
+                                    break;
+                            }
+                        }
+                    }
+
+                    switch (OutputSettings & OUTPUTSETTINGS_TIMESTAMP_MASK)
+                    {
+                        case OUTPUTSETTINGS_TIMESTAMP_SAMPLECNT:
+                            dataLength += LEN_SAMPLECNT;
+                            break;
+
+                        default:
+                            break;
+                    }
+                }
+
+                m_storedDataLength[nbid] = dataLength;
+            }
+
+            // If not XbusMaster store also in BID_MT
+            if (bid == BID_MASTER && OutputMode != OUTPUTMODE_XM)
+            {
+                m_storedOutputMode[BID_MT ] = m_storedOutputMode[0];
+                m_storedOutputSettings[BID_MT ] = m_storedOutputSettings[0];
+                m_storedDataLength[BID_MT ] = m_storedDataLength[0];
+            }
+
+            return (m_retVal = MTRV_OK);
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // getValue (unsigned short variant)
+        //
+        // Retrieves a unsigned short value from the data input parameter
+        // This function is valid for the following value specifiers:
+        //      VALUE_RAW_TEMP
+        //      VALUE_SAMPLECNT
+        //
+        // Use getDeviceMode or setMode to initialize the Outputmode
+        // and Outputsettings member variables used to retrieve the correct
+        // value
+        //
+        // Input
+        //   valueSpec      : Specifier of the value to be retrieved
+        //   data[]         : Data field of a MTData / BusData message
+        //   bid            : bus identifier of the device of which the
+        //                      value should be returned (default = BID_MT)
+        // Output
+        //   value          : reference to unsigned short in which the retrieved
+        //                      value will be returned
+        //
+        //  Return value
+        //    MTRV_OK       : value is successfully retrieved
+        //    != MTRV_OK    : not successful
+        //
+        short CXsensMTiModule::getValue(const unsigned long valueSpec, unsigned short& value, const unsigned char data[], const unsigned char bid)
+        {
+            short offset = 0;
+            unsigned char nbid = bid;
+
+            if (nbid == BID_MASTER)
+            {
+                nbid = 0;
+            }
+
+            // Check for invalid mode/settings
+            if (m_storedOutputMode[nbid] == INVALIDSETTINGVALUE || m_storedOutputSettings[nbid] == INVALIDSETTINGVALUE)
+            {
+                return (m_retVal = MTRV_NOVALIDMODESPECIFIED);
+            }
+
+            // Calculate offset for XM input
+            if (m_storedOutputMode[0] == OUTPUTMODE_XM)
+            {
+                int i = 0;
+
+                while (i < nbid)
+                {
+                    offset += (short) m_storedDataLength[i++];
+                }
+            }
+
+            // Check if data is unsigned short & available in data
+            m_retVal = MTRV_INVALIDVALUESPEC;
+
+            if (valueSpec == VALUE_RAW_TEMP)
+            {
+                if (m_storedOutputMode[nbid] & (OUTPUTMODE_RAW | OUTPUTMODE_MT9))
+                {
+                    offset += (m_storedOutputMode[nbid] == OUTPUTMODE_MT9 && m_storedOutputSettings[nbid] == OUTPUTSETTINGS_TIMESTAMP_SAMPLECNT) ? LEN_SAMPLECNT : 0;
+                    swapEndian(data + offset + valueSpec * LEN_UNSIGSHORT * 3, (unsigned char*) &value, LEN_RAW_TEMP);
+                    m_retVal = MTRV_OK;
+                }
+            }
+            else if (valueSpec == VALUE_SAMPLECNT)
+            {
+                if ((m_storedOutputSettings[nbid] & OUTPUTSETTINGS_TIMESTAMP_MASK) == OUTPUTSETTINGS_TIMESTAMP_SAMPLECNT)
+                {
+                    if (!(m_storedOutputMode[nbid] == OUTPUTMODE_MT9))
+                    {
+                        offset += (short) m_storedDataLength[nbid] - LEN_SAMPLECNT;
+                    }
+
+                    swapEndian(data + offset, (unsigned char*) &value, LEN_SAMPLECNT);
+                    m_retVal = MTRV_OK;
+                }
+            }
+
+            return m_retVal;
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // getValue (array of unsigned short variant)
+        //
+        // Retrieves an array of unsigned short values from the data input
+        // parameter. This function is valid for the following value specifiers:
+        //      VALUE_RAW_ACC
+        //      VALUE_RAW_GYR
+        //      VALUE_RAW_MAG
+        //
+        // Use getDeviceMode or setMode to initialize the Outputmode
+        // and Outputsettings member variables used to retrieve the correct
+        // value
+        //
+        // Input
+        //   valueSpec      : Specifier of the value to be retrieved
+        //   data[]         : Data field of a MTData / BusData message
+        //   bid            : bus identifier of the device of which the
+        //                      value should be returned (default = BID_MT)
+        // Output
+        //   value[]        : pointer to array of unsigned shorts in which the
+        //                      retrieved values will be returned
+        //
+        //  Return value
+        //    MTRV_OK       : value is successfully retrieved
+        //    != MTRV_OK    : not successful
+        //
+        short CXsensMTiModule::getValue(const unsigned long valueSpec, unsigned short value[], const unsigned char data[], const unsigned char bid)
+        {
+            short offset = 0;
+            unsigned char nbid = bid;
+
+            if (nbid == BID_MASTER)
+            {
+                nbid = 0;
+            }
+
+            // Check for invalid mode/settings
+            if (m_storedOutputMode[nbid] == INVALIDSETTINGVALUE || m_storedOutputSettings[nbid] == INVALIDSETTINGVALUE)
+            {
+                return (m_retVal = MTRV_NOVALIDMODESPECIFIED);
+            }
+
+            // Calculate offset for XM input
+            if (m_storedOutputMode[0] == OUTPUTMODE_XM)
+            {
+                int i = 0;
+
+                while (i < nbid)
+                {
+                    offset += (short) m_storedDataLength[i++];
+                }
+            }
+
+            // Check if data is unsigned short, available in data & retrieve data
+            m_retVal = MTRV_INVALIDVALUESPEC;
+
+            //if (valueSpec >= VALUE_RAW_ACC && valueSpec <= VALUE_RAW_MAG)
+            if (valueSpec <= VALUE_RAW_MAG)
+            {
+                if (m_storedOutputMode[nbid] & (OUTPUTMODE_RAW | OUTPUTMODE_MT9))
+                {
+                    offset += (short)(valueSpec * LEN_UNSIGSHORT * 3);
+                    offset += (m_storedOutputMode[nbid] == OUTPUTMODE_MT9 && m_storedOutputSettings[nbid] == OUTPUTSETTINGS_TIMESTAMP_SAMPLECNT) ? LEN_SAMPLECNT : 0;
+
+                    for (int i = 0 ; i < 3 ; i++)
+                    {
+                        swapEndian(data + offset + i * LEN_UNSIGSHORT, (unsigned char*) value + i * LEN_UNSIGSHORT, LEN_UNSIGSHORT);
+                    }
+
+                    m_retVal = MTRV_OK;
+                }
+            }
+
+            return m_retVal;
+        }
+
+        ////////////////////////////////////////////////////////////////////
+        // getValue (array of floats variant)
+        //
+        // Retrieves an array of float values from the data input parameter.
+        // This function is valid for the following value specifiers:
+        //      VALUE_TEMP
+        //      VALUE_CALIB_ACC
+        //      VALUE_CALIB_GYR
+        //      VALUE_CALIB_MAG
+        //      VALUE_ORIENT_QUAT
+        //      VALUE_ORIENT_EULER
+        //      VALUE_ORIENT_MATRIX
+        //
+        // Use getDeviceMode or setMode to initialize the Outputmode
+        // and Outputsettings member variables used to retrieve the correct
+        // value
+        //
+        // Input
+        //   valueSpec      : Specifier of the value to be retrieved
+        //   data[]         : Data field of a MTData / BusData message
+        //   bid            : bus identifier of the device of which the
+        //                      value should be returned (default = BID_MT)
+        // Output
+        //   value[]        : pointer to array of floats in which the
+        //                      retrieved values will be returned
+        //
+        //  Return value
+        //    MTRV_OK       : value is successfully retrieved
+        //    != MTRV_OK    : not successful
+        //
+        short CXsensMTiModule::getValue(const unsigned long valueSpec, float value[], const unsigned char data[], const unsigned char bid)
+        {
+            short offset = 0;
+            int nElements = 0;
+            unsigned char nbid = bid;
+
+            if (nbid == BID_MASTER)
+            {
+                nbid = 0;
+            }
+
+            // Check for invalid mode/settings
+            if (m_storedOutputMode[nbid] == INVALIDSETTINGVALUE || m_storedOutputSettings[nbid] == INVALIDSETTINGVALUE)
+            {
+                return (m_retVal = MTRV_NOVALIDMODESPECIFIED);
+            }
+
+            // Calculate offset for XM input
+            if (m_storedOutputMode[0] == OUTPUTMODE_XM)
+            {
+                int i = 0;
+
+                while (i < nbid)
+                {
+                    offset += (short) m_storedDataLength[i++];
+                }
+            }
+
+            // Check if data is float & available in data
+            m_retVal = MTRV_INVALIDVALUESPEC;
+
+            if (valueSpec == VALUE_TEMP)
+            {
+                if (m_storedOutputMode[nbid] & OUTPUTMODE_TEMP)
+                {
+                    nElements = LEN_TEMPDATA / LEN_FLOAT;
+                    m_retVal = MTRV_OK;
+                }
+            }
+            else if (valueSpec == VALUE_CALIB_ACC)
+            {
+                offset += ((m_storedOutputMode[nbid] & OUTPUTMODE_TEMP) != 0) ? LEN_TEMPDATA : 0;
+
+                if ((m_storedOutputMode[nbid] & OUTPUTMODE_CALIB) && (m_storedOutputSettings[nbid] & OUTPUTSETTINGS_CALIBMODE_ACC_MASK) == 0)
+                {
+                    nElements = LEN_CALIB_ACCDATA / LEN_FLOAT;
+                    m_retVal = MTRV_OK;
+                }
+            }
+            else if (valueSpec == VALUE_CALIB_GYR)
+            {
+                offset += ((m_storedOutputMode[nbid] & OUTPUTMODE_TEMP) != 0) ? LEN_TEMPDATA : 0;
+
+                if ((m_storedOutputMode[nbid] & OUTPUTMODE_CALIB) && (m_storedOutputSettings[nbid] & OUTPUTSETTINGS_CALIBMODE_GYR_MASK) == 0)
+                {
+                    offset += ((m_storedOutputSettings[nbid] & OUTPUTSETTINGS_CALIBMODE_ACC_MASK) == 0) ? LEN_CALIB_ACCX * 3 : 0;
+                    nElements = LEN_CALIB_GYRDATA / LEN_FLOAT;
+                    m_retVal = MTRV_OK;
+                }
+            }
+            else if (valueSpec == VALUE_CALIB_MAG)
+            {
+                offset += ((m_storedOutputMode[nbid] & OUTPUTMODE_TEMP) != 0) ? LEN_TEMPDATA : 0;
+
+                if ((m_storedOutputMode[nbid] & OUTPUTMODE_CALIB) && (m_storedOutputSettings[nbid] & OUTPUTSETTINGS_CALIBMODE_MAG_MASK) == 0)
+                {
+                    offset += ((m_storedOutputSettings[nbid] & OUTPUTSETTINGS_CALIBMODE_ACC_MASK) == 0) ? LEN_CALIB_ACCX * 3 : 0;
+                    offset += ((m_storedOutputSettings[nbid] & OUTPUTSETTINGS_CALIBMODE_GYR_MASK) == 0) ? LEN_CALIB_GYRX * 3 : 0;
+                    nElements = LEN_CALIB_MAGDATA / LEN_FLOAT;
+                    m_retVal = MTRV_OK;
+                }
+            }
+            else if (valueSpec >= VALUE_ORIENT_QUAT && valueSpec <= VALUE_ORIENT_MATRIX)
+            {
+                offset += ((m_storedOutputMode[nbid] & OUTPUTMODE_TEMP) != 0) ? LEN_TEMPDATA : 0;
+
+                if ((m_storedOutputMode[nbid] & OUTPUTMODE_CALIB))
+                {
+                    offset += ((m_storedOutputSettings[nbid] & OUTPUTSETTINGS_CALIBMODE_ACC_MASK) == 0) ? LEN_CALIB_ACCX * 3 : 0;
+                    offset += ((m_storedOutputSettings[nbid] & OUTPUTSETTINGS_CALIBMODE_GYR_MASK) == 0) ? LEN_CALIB_GYRX * 3 : 0;
+                    offset += ((m_storedOutputSettings[nbid] & OUTPUTSETTINGS_CALIBMODE_MAG_MASK) == 0) ? LEN_CALIB_MAGX * 3 : 0;
+                }
+
+                if (m_storedOutputMode[nbid] & OUTPUTMODE_ORIENT)
+                {
+                    unsigned long orientmode = m_storedOutputSettings[nbid] & OUTPUTSETTINGS_ORIENTMODE_MASK;
+
+                    switch (valueSpec)
+                    {
+                        case VALUE_ORIENT_QUAT:
+                            if (orientmode == OUTPUTSETTINGS_ORIENTMODE_QUATERNION)
+                            {
+                                nElements = LEN_ORIENT_QUATDATA / LEN_FLOAT;
+                                m_retVal = MTRV_OK;
+                            }
+
+                            break;
+
+                        case VALUE_ORIENT_EULER:
+                            if (orientmode == OUTPUTSETTINGS_ORIENTMODE_EULER)
+                            {
+                                nElements = LEN_ORIENT_EULERDATA / LEN_FLOAT;
+                                m_retVal = MTRV_OK;
+                            }
+
+                            break;
+
+                        case VALUE_ORIENT_MATRIX:
+                            if (orientmode == OUTPUTSETTINGS_ORIENTMODE_MATRIX)
+                            {
+                                nElements = LEN_ORIENT_MATRIXDATA / LEN_FLOAT;
+                                m_retVal = MTRV_OK;
+                            }
+
+                            break;
+
+                        default:
+                            break;
+                    }
+                }
+            }
+
+            if (m_retVal == MTRV_OK)
+            {
+                if ((m_storedOutputSettings[nbid] & OUTPUTSETTINGS_DATAFORMAT_F1220) == 0)
+                {
+                    for (int i = 0 ; i < nElements ; i++)
+                    {
+                        swapEndian(data + offset + i * LEN_FLOAT, (unsigned char*) value + i * LEN_FLOAT, LEN_FLOAT);
+                    }
+                }
+                else
+                {
+                    int temp;
+
+                    for (int i = 0 ; i < nElements ; i++)
+                    {
+                        swapEndian(data + offset + i * LEN_FLOAT, (unsigned char*) &temp, 4);
+                        value[i] = (float) temp / 1048576;
+                    }
+                }
+            }
+
+            return m_retVal;
+        }
+
+        //////////////////////////////////////////////////////////////////////
+        // getLastDeviceError
+        //
+        // Returns the last reported device error of the latest received Error
+        //  message
+        //
+        // Output
+        //   Error code
+        short CXsensMTiModule::getLastDeviceError()
+        {
+            return m_deviceError;
+        }
+
+        //////////////////////////////////////////////////////////////////////
+        // getLastRetVal
+        //
+        // Returns the returned value of the last called function
+        //
+        // Output
+        //   Return value
+        short CXsensMTiModule::getLastRetVal()
+        {
+            return m_retVal;
+        }
+
+        //////////////////////////////////////////////////////////////////////
+        // setTimeOut
+        //
+        // Sets the time out value in milliseconds used by the functions
+        // Use 0 for infinite timeout
+        //
+        // Output
+        //   MTRV_OK is set, MTRV_INVALIDTIMEOUT if time value < 0
+        short CXsensMTiModule::setTimeOut(short timeOutMs)
+        {
+            if (timeOutMs >= 0)
+            {
+                m_timeOut = timeOutMs;
+                return (m_retVal = MTRV_OK);
+            }
+            else
+            {
+                return (m_retVal = MTRV_INVALIDTIMEOUT);
+            }
+        }
+
+        //////////////////////////////////////////////////////////////////////
+        // swapEndian
+        //
+        // Convert 2 or 4 bytes data from little to big endian or back
+        //
+        // Input
+        //   input  : Pointer to data to be converted
+        //   output : Pointer where converted data is stored
+        //   length : Length of setting (0,2 & 4)
+        //
+        // Remarks:
+        //   Allocate enough bytes for output buffer
+
+        void CXsensMTiModule::swapEndian(const unsigned char input[], unsigned char output[], const int length)
+        {
+            switch (length)
+            {
+                case 4:
+                    output[0] = input[3];
+                    output[1] = input[2];
+                    output[2] = input[1];
+                    output[3] = input[0];
+                    break;
+
+                case 2:
+                    output[0] = input[1];
+                    output[1] = input[0];
+                    break;
+
+                case 1:
+                    output[0] = input[0];
+                    break;
+
+                default:
+                    for (int i = 0 , j = length - 1 ; i < length ; i++ , j--)
+                    {
+                        output[j] = input[i];
+                    }
+
+                    break;
+            }
+        }
+
+        //////////////////////////////////////////////////////////////////////
+        // calcChecksum
+        //
+        // Calculate and append checksum to msgBuffer
+        //
+        void CXsensMTiModule::calcChecksum(unsigned char* msgBuffer, const int msgBufferLength)
+        {
+            unsigned char checkSum = 0;
+            int i;
+
+            for (i = 1; i < msgBufferLength ; i++)
+            {
+                checkSum += msgBuffer[i];
+            }
+
+            msgBuffer[msgBufferLength] = -checkSum;   // Store chksum
+        }
+
+        //////////////////////////////////////////////////////////////////////
+        // checkChecksum
+        //
+        // Checks if message checksum is valid
+        //
+        // Output
+        //   returns true checksum is OK
+        bool CXsensMTiModule::checkChecksum(const unsigned char* msgBuffer, const int msgBufferLength)
+        {
+            unsigned char checkSum = 0;
+            int i;
+
+            for (i = 1; i < msgBufferLength ; i++)
+            {
+                checkSum += msgBuffer[i];
+            }
+
+            if (checkSum == 0)
+            {
+                return true;
+            }
+            else
+            {
+                return false;
+            }
+        }
+    }
 }
 
 #endif
diff --git a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/Xsens/XsensMTiModule.h b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/Xsens/XsensMTiModule.h
old mode 100755
new mode 100644
index 8c4d0d0d0a17c06bf409c228934a978c8c1c3144..54ba05d75115b066cbdf6adb377df62b2a3422cb
--- a/source/RobotAPI/libraries/drivers/XsensIMU/IMU/Xsens/XsensMTiModule.h
+++ b/source/RobotAPI/libraries/drivers/XsensIMU/IMU/Xsens/XsensMTiModule.h
@@ -29,14 +29,14 @@
 //
 // v1.2.0
 // 27-02-2006 - Renamed Xbus class to Motion Tracker C++ Communication class, short MTComm
-//			  - Defines XBRV_* accordingly renamed to MTRV_*
-//			  - Fixed device length not correct for bid 0 when using Xbus Master and setDeviceMode function
+//            - Defines XBRV_* accordingly renamed to MTRV_*
+//            - Fixed device length not correct for bid 0 when using Xbus Master and setDeviceMode function
 //
 // v1.1.7
 // 15-02-2006 - Added fixed point signed 12.20 dataformat support
-//				Added selective calibrated data output per sensor type support
-//				Added outputmode temperature support
-//				Fixed warning C4244: '=' : conversion from '' to '', possible loss of data
+//              Added selective calibrated data output per sensor type support
+//              Added outputmode temperature support
+//              Fixed warning C4244: '=' : conversion from '' to '', possible loss of data
 // v1.1.6
 // 25-01-2006 - Added escape function for CLRDTR, CLRRTS, SETDTR, SETRTS, SETXOFF, SETXON, SETBREAK, CLRBREAK
 //
@@ -45,46 +45,46 @@
 //
 // v1.1.4
 // 08-11-2005 - Changed practically all uses of m_timeOut into uses of the new m_clkEnd
-//			  - Changed COM timeout in win32 to return immediately if data is available,
-//				but wait 1ms otherwise
+//            - Changed COM timeout in win32 to return immediately if data is available,
+//              but wait 1ms otherwise
 //
 // v1.1.3
 // 18-10-2005 - Added MID_REQPRODUCTCODE, MID_REQ/SETTRANSMITDELAY
-//			  - Added XBRV_TIMEOUTNODATA indicating timeout occurred due to no data read
+//            - Added XBRV_TIMEOUTNODATA indicating timeout occurred due to no data read
 //
 // v1.1.2
 // 16-09-2005 - Added eMTS version 0.1->1.0 changes (EMTS_FACTORYMODE)
-//			  - Added factory output mode defines
+//            - Added factory output mode defines
 //
 // v1.1.1
 // 01-09-2005 - Added defines for Extended output mode
-//			  - Added reqSetting (byte array in + out & no param variant)
+//            - Added reqSetting (byte array in + out & no param variant)
 //
 // v1.1
 // 08-08-2005 - Added file read and write support
-//			  - Added functions for data retrieval (getValue etc)
-//				  for easy data retrieval of acc, gyr, mag etc
-//			  - ReadMessageRaw:
-//				- added a temporary buffer for unprocessed bytes
-//				- check for invalid length messages
-//			  - Changed BID_MT into 1 and added BID_MASTER (=0xFF)
-//			  - Changed various ....SerialPort functions to .....Port
-//			  - Changed mtSendMessage functions to mtWriteMessage
-//			  - Added numerous defines
-//			  - Deleted obsolete functions
-//			  - Changed function getLastErrorCode into getLastDeviceError
-//			  - Changed OpenPort function for compatiblity with Bluetooth ports
-//			  - Added workaround for lockup of USB driver (close function) 
-//			  - Added workaround for clock() problem with read function of USB driver
+//            - Added functions for data retrieval (getValue etc)
+//                for easy data retrieval of acc, gyr, mag etc
+//            - ReadMessageRaw:
+//              - added a temporary buffer for unprocessed bytes
+//              - check for invalid length messages
+//            - Changed BID_MT into 1 and added BID_MASTER (=0xFF)
+//            - Changed various ....SerialPort functions to .....Port
+//            - Changed mtSendMessage functions to mtWriteMessage
+//            - Added numerous defines
+//            - Deleted obsolete functions
+//            - Changed function getLastErrorCode into getLastDeviceError
+//            - Changed OpenPort function for compatiblity with Bluetooth ports
+//            - Added workaround for lockup of USB driver (close function)
+//            - Added workaround for clock() problem with read function of USB driver
 //
 // v1.0.2
 // 29-06-2005 - Inserted initSerialPort with devicename input
-//			  - Changed return value defines names from X_ to XBRV_
-//			  - Removed unneeded includes for linux
+//            - Changed return value defines names from X_ to XBRV_
+//            - Removed unneeded includes for linux
 //
 // v1.0.1
 // 22-06-2005 - Fixed ReqSetting functions (byte array & param variant)
-//				mtSendRawString had wrong length input
+//              mtSendRawString had wrong length input
 //
 // v1.0.0
 // 20-06-2005 - Initial release
@@ -95,8 +95,8 @@
 //  Copyright (C) Xsens Technologies B.V., 2005.
 //
 //  This source code is intended only as a example of the implementation
-//	of the Xsens MT Communication protocol.
-//	It was written for cross platform capabilities.
+//  of the Xsens MT Communication protocol.
+//  It was written for cross platform capabilities.
 //
 //  THIS CODE AND INFORMATION IS PROVIDED "AS IS" WITHOUT WARRANTY OF ANY
 //  KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE
@@ -117,11 +117,11 @@
 #include <conio.h>
 #include <time.h>
 #else
-#include <fcntl.h>     	/* POSIX Standard: 6.5 File Control Operations     */
-#include <termios.h>   	/* terminal i/o system, talks to /dev/tty* ports  */
-#include <unistd.h>		/* Read function */
-#include <sys/time.h>	/* gettimeofday function */
-#include <sys/stat.h>	/* stat calls and structures*/
+#include <fcntl.h>      /* POSIX Standard: 6.5 File Control Operations     */
+#include <termios.h>    /* terminal i/o system, talks to /dev/tty* ports  */
+#include <unistd.h>     /* Read function */
+#include <sys/time.h>   /* gettimeofday function */
+#include <sys/stat.h>   /* stat calls and structures*/
 #endif
 
 #include "../Includes.h"
@@ -130,887 +130,887 @@
 
 namespace IMU
 {
-	namespace Xsens
-	{
+    namespace Xsens
+    {
 
-#ifndef	INVALID_SET_FILE_POINTER
-#define	INVALID_SET_FILE_POINTER	((DWORD)(-1))
+#ifndef INVALID_SET_FILE_POINTER
+#define INVALID_SET_FILE_POINTER    ((DWORD)(-1))
 #endif
 
-// Field message indexes
-#define IND_PREAMBLE				0
-#define IND_BID						1
-#define IND_MID						2
-#define IND_LEN						3
-#define IND_DATA0					4
-#define IND_LENEXTH					4
-#define IND_LENEXTL					5
-#define IND_DATAEXT0				6
-
-// Maximum number of sensors supported
-#define MAXDEVICES					20
-
-#define PREAMBLE					(const unsigned char)0xFA
-#define BID_MASTER					(const unsigned char)0xFF
-#define BID_MT						(const unsigned char)0x01
-#define EXTLENCODE					0xFF
-
-#define LEN_MSGHEADER				(const unsigned short)4
-#define LEN_MSGEXTHEADER			(const unsigned short)6
-#define LEN_MSGHEADERCS				(const unsigned short)5
-#define LEN_MSGEXTHEADERCS			(const unsigned short)7
-#define LEN_CHECKSUM				(const unsigned short)1
-#define LEN_UNSIGSHORT				(const unsigned short)2
-#define LEN_UNSIGINT				(const unsigned short)4
-#define LEN_FLOAT					(const unsigned short)4
-
-// Maximum message/data length
-#define MAXDATALEN					(const unsigned short)2048
-#define MAXSHORTDATALEN				(const unsigned short)254
-#define MAXMSGLEN					(const unsigned short)(MAXDATALEN+7)
-#define MAXSHORTMSGLEN				(const unsigned short)(MAXSHORTDATALEN+5)
-
-// DID Type (high nibble)
-#define DID_TYPEH_MASK				(const unsigned long)0x00F00000
-#define DID_TYPEH_MT				(const unsigned long)0x00000000
-#define DID_TYPEH_XM				(const unsigned long)0x00100000
-#define DID_TYPEH_MTI_MTX			(const unsigned long)0x00300000
-
-// All Message identifiers
-// WakeUp state messages
-#define MID_WAKEUP					(const unsigned char)0x3E
-#define MID_WAKEUPACK				(const unsigned char)0x3F
-
-// Config state messages
-#define MID_REQDID					(const unsigned char)0x00
-#define MID_DEVICEID				(const unsigned char)0x01
-#define LEN_DEVICEID				(const unsigned short)4
-#define MID_INITBUS					(const unsigned char)0x02
-#define MID_INITBUSRESULTS			(const unsigned char)0x03
-#define LEN_INITBUSRESULTS			(const unsigned short)4
-#define MID_REQPERIOD				(const unsigned char)0x04
-#define MID_REQPERIODACK			(const unsigned char)0x05
-#define LEN_PERIOD					(const unsigned short)2
-#define MID_SETPERIOD				(const unsigned char)0x04
-#define MID_SETPERIODACK			(const unsigned char)0x05
-// XbusMaster
-#define MID_SETBID					(const unsigned char)0x06
-#define MID_SETBIDACK				(const unsigned char)0x07
-#define MID_AUTOSTART				(const unsigned char)0x06
-#define MID_AUTOSTARTACK			(const unsigned char)0x07
-#define MID_BUSPWROFF				(const unsigned char)0x08
-#define MID_BUSPWROFFACK			(const unsigned char)0x09
-// End XbusMaster
-#define MID_REQDATALENGTH			(const unsigned char)0x0A
-#define MID_DATALENGTH				(const unsigned char)0x0B
-#define LEN_DATALENGTH				(const unsigned short)2
-#define MID_REQCONFIGURATION		(const unsigned char)0x0C
-#define MID_CONFIGURATION			(const unsigned char)0x0D
-#define LEN_CONFIGURATION			(const unsigned short)118
-#define MID_RESTOREFACTORYDEF		(const unsigned char)0x0E
-#define MID_RESTOREFACTORYDEFACK	(const unsigned char)0x0F
-
-#define MID_GOTOMEASUREMENT			(const unsigned char)0x10
-#define MID_GOTOMEASUREMENTACK		(const unsigned char)0x11
-#define MID_REQFWREV				(const unsigned char)0x12
-#define MID_FIRMWAREREV				(const unsigned char)0x13
-#define LEN_FIRMWAREREV				(const unsigned short)3
-// XbusMaster
-#define MID_REQBTDISABLE			(const unsigned char)0x14
-#define MID_REQBTDISABLEACK			(const unsigned char)0x15
-#define MID_DISABLEBT				(const unsigned char)0x14
-#define MID_DISABLEBTACK			(const unsigned char)0x15
-#define MID_REQOPMODE				(const unsigned char)0x16
-#define MID_REQOPMODEACK			(const unsigned char)0x17
-#define MID_SETOPMODE				(const unsigned char)0x16
-#define MID_SETOPMODEACK			(const unsigned char)0x17
-// End XbusMaster
-#define MID_REQBAUDRATE				(const unsigned char)0x18
-#define MID_REQBAUDRATEACK			(const unsigned char)0x19
-#define LEN_BAUDRATE				(const unsigned short)1
-#define MID_SETBAUDRATE				(const unsigned char)0x18
-#define MID_SETBAUDRATEACK			(const unsigned char)0x19
-// XbusMaster
-#define MID_REQSYNCMODE				(const unsigned char)0x1A
-#define MID_REQSYNCMODEACK			(const unsigned char)0x1B
-#define MID_SETSYNCMODE				(const unsigned char)0x1A
-#define MID_SETSYNCMODEACK			(const unsigned char)0x1B
-// End XbusMaster
-#define MID_REQPRODUCTCODE			(const unsigned char)0x1C
-#define MID_PRODUCTCODE				(const unsigned char)0x1D
-
-#define MID_REQOUTPUTMODE			(const unsigned char)0xD0
-#define MID_REQOUTPUTMODEACK		(const unsigned char)0xD1
-#define LEN_OUTPUTMODE		 		(const unsigned short)2
-#define MID_SETOUTPUTMODE			(const unsigned char)0xD0
-#define MID_SETOUTPUTMODEACK		(const unsigned char)0xD1
-
-#define MID_REQOUTPUTSETTINGS		(const unsigned char)0xD2
-#define MID_REQOUTPUTSETTINGSACK	(const unsigned char)0xD3
-#define LEN_OUTPUTSETTINGS		 	(const unsigned short)4
-#define MID_SETOUTPUTSETTINGS		(const unsigned char)0xD2
-#define MID_SETOUTPUTSETTINGSACK	(const unsigned char)0xD3
-
-#define MID_REQOUTPUTSKIPFACTOR		(const unsigned char)0xD4
-#define MID_REQOUTPUTSKIPFACTORACK	(const unsigned char)0xD5
-#define LEN_OUTPUTSKIPFACTOR		(const unsigned short)2
-#define MID_SETOUTPUTSKIPFACTOR		(const unsigned char)0xD4
-#define MID_SETOUTPUTSKIPFACTORACK	(const unsigned char)0xD5
-
-#define MID_REQSYNCINSETTINGS		(const unsigned char)0xD6
-#define MID_REQSYNCINSETTINGSACK	(const unsigned char)0xD7
-#define LEN_SYNCINMODE				(const unsigned short)2
-#define LEN_SYNCINSKIPFACTOR		(const unsigned short)2
-#define LEN_SYNCINOFFSET			(const unsigned short)4
-#define MID_SETSYNCINSETTINGS		(const unsigned char)0xD6
-#define MID_SETSYNCINSETTINGSACK	(const unsigned char)0xD7
-
-#define MID_REQSYNCOUTSETTINGS		(const unsigned char)0xD8
-#define MID_REQSYNCOUTSETTINGSACK	(const unsigned char)0xD9
-#define LEN_SYNCOUTMODE				(const unsigned short)2
-#define LEN_SYNCOUTSKIPFACTOR		(const unsigned short)2
-#define LEN_SYNCOUTOFFSET			(const unsigned short)4
-#define LEN_SYNCOUTPULSEWIDTH		(const unsigned short)4
-#define MID_SETSYNCOUTSETTINGS		(const unsigned char)0xD8
-#define MID_SETSYNCOUTSETTINGSACK	(const unsigned char)0xD9
-
-#define MID_REQERRORMODE			(const unsigned char)0xDA
-#define MID_REQERRORMODEACK			(const unsigned char)0xDB
-#define LEN_ERRORMODE				(const unsigned short)2
-#define MID_SETERRORMODE			(const unsigned char)0xDA
-#define MID_SETERRORMODEACK			(const unsigned char)0xDB
-
-#define MID_REQTRANSMITDELAY		(const unsigned char)0xDC
-#define MID_REQTRANSMITDELAYACK		(const unsigned char)0xDD
-#define LEN_TRANSMITDELAY			(const unsigned short)2
-#define MID_SETTRANSMITDELAY		(const unsigned char)0xDC
-#define MID_SETTRANSMITDELAYACK		(const unsigned char)0xDD		
-
-// Xbus Master
-#define MID_REQXMERRORMODE			(const unsigned char)0x82
-#define MID_REQXMERRORMODEACK		(const unsigned char)0x83
-#define LEN_XMERRORMODE				(const unsigned short)2
-#define MID_SETXMERRORMODE			(const unsigned char)0x82
-#define MID_SETXMERRORMODEACK		(const unsigned char)0x83
-
-#define MID_REQBUFFERSIZE			(const unsigned char)0x84
-#define MID_REQBUFFERSIZEACK		(const unsigned char)0x85
-#define LEN_BUFFERSIZE				(const unsigned short)2
-#define MID_SETBUFFERSIZE			(const unsigned char)0x84
-#define MID_SETBUFFERSIZEACK		(const unsigned char)0x85			
-// End Xbus Master
-
-#define MID_REQHEADING				(const unsigned char)0x82
-#define MID_REQHEADINGACK			(const unsigned char)0x83
-#define LEN_HEADING		 			(const unsigned short)4
-#define MID_SETHEADING				(const unsigned char)0x82
-#define MID_SETHEADINGACK			(const unsigned char)0x83
-
-#define MID_REQLOCATIONID			(const unsigned char)0x84
-#define MID_REQLOCATIONIDACK		(const unsigned char)0x85
-#define LEN_LOCATIONID				(const unsigned short)2
-#define MID_SETLOCATIONID			(const unsigned char)0x84
-#define MID_SETLOCATIONIDACK		(const unsigned char)0x85
-
-#define MID_REQEXTOUTPUTMODE		(const unsigned char)0x86
-#define MID_REQEXTOUTPUTMODEACK		(const unsigned char)0x87
-#define LEN_EXTOUTPUTMODE			(const unsigned short)2
-#define MID_SETEXTOUTPUTMODE		(const unsigned char)0x86
-#define MID_SETEXTOUTPUTMODEACK		(const unsigned char)0x87
-
-// XbusMaster
-#define MID_REQBATLEVEL				(const unsigned char)0x88
-#define MID_BATLEVEL				(const unsigned char)0x89
-// End XbusMaster
-
-#define MID_REQINITTRACKMODE		(const unsigned char)0x88
-#define MID_REQINITTRACKMODEACK		(const unsigned char)0x89
-#define LEN_INITTRACKMODE			(const unsigned short)2
-#define MID_SETINITTRACKMODE		(const unsigned char)0x88
-#define MID_SETINITTRACKMODEACK		(const unsigned char)0x89
-
-#define MID_STOREFILTERSTATE		(const unsigned char)0x8A
-#define MID_STOREFILTERSTATEACK		(const unsigned char)0x8B
-
-// Measurement state
-#define MID_GOTOCONFIG				(const unsigned char)0x30
-#define MID_GOTOCONFIGACK			(const unsigned char)0x31
-#define MID_BUSDATA					(const unsigned char)0x32
-#define MID_MTDATA					(const unsigned char)0x32
-
-// Manual
-#define MID_PREPAREDATA				(const unsigned char)0x32
-#define MID_REQDATA					(const unsigned char)0x34
-#define MID_REQDATAACK				(const unsigned char)0x35
-
-// MTData defines 
-// Length of data blocks in bytes
-#define LEN_RAWDATA					(const unsigned short)20
-#define LEN_CALIBDATA				(const unsigned short)36
-#define LEN_CALIB_ACCDATA			(const unsigned short)12
-#define LEN_CALIB_GYRDATA			(const unsigned short)12
-#define LEN_CALIB_MAGDATA			(const unsigned short)12
-#define LEN_ORIENT_QUATDATA			(const unsigned short)16
-#define LEN_ORIENT_EULERDATA		(const unsigned short)12
-#define LEN_ORIENT_MATRIXDATA		(const unsigned short)36
-#define LEN_SAMPLECNT				(const unsigned short)2
-#define LEN_TEMPDATA				(const unsigned short)4
-
-// Length of data blocks in floats
-#define LEN_CALIBDATA_FLT			(const unsigned short)9
-#define LEN_ORIENT_QUATDATA_FLT		(const unsigned short)4
-#define LEN_ORIENT_EULERDATA_FLT	(const unsigned short)3
-#define LEN_ORIENT_MATRIXDATA_FLT	(const unsigned short)9
-
-// Indices of fields in DATA field of MTData message in bytes
-// use in combination with LEN_CALIB etc
-// Un-calibrated raw data
-#define IND_RAW_ACCX				0
-#define IND_RAW_ACCY				2
-#define IND_RAW_ACCZ				4
-#define IND_RAW_GYRX				6
-#define IND_RAW_GYRY				8
-#define IND_RAW_GYRZ				10
-#define IND_RAW_MAGX				12
-#define IND_RAW_MAGY				14
-#define IND_RAW_MAGZ				16
-#define IND_RAW_TEMP				18
-// Calibrated data
-#define IND_CALIB_ACCX				0
-#define IND_CALIB_ACCY				4
-#define IND_CALIB_ACCZ				8
-#define IND_CALIB_GYRX				12
-#define IND_CALIB_GYRY				16
-#define IND_CALIB_GYRZ				20
-#define IND_CALIB_MAGX				24
-#define IND_CALIB_MAGY				28
-#define IND_CALIB_MAGZ				32
-// Orientation data - quat
-#define IND_ORIENT_Q0				0
-#define IND_ORIENT_Q1				4
-#define IND_ORIENT_Q2				8
-#define IND_ORIENT_Q3				12
-// Orientation data - euler
-#define IND_ORIENT_ROLL				0
-#define IND_ORIENT_PITCH			4
-#define IND_ORIENT_YAW				8
-// Orientation data - matrix
-#define IND_ORIENT_A				0
-#define IND_ORIENT_B				4
-#define IND_ORIENT_C				8
-#define IND_ORIENT_D				12
-#define IND_ORIENT_E				16
-#define IND_ORIENT_F				20
-#define IND_ORIENT_G				24
-#define IND_ORIENT_H				28
-#define IND_ORIENT_I				32
-// Orientation data - euler
-#define IND_SAMPLECNTH				0
-#define IND_SAMPLECNTL				1
-
-// Indices of fields in DATA field of MTData message
-// Un-calibrated raw data
-#define FLDNUM_RAW_ACCX				0
-#define FLDNUM_RAW_ACCY				1
-#define FLDNUM_RAW_ACCZ				2
-#define FLDNUM_RAW_GYRX				3
-#define FLDNUM_RAW_GYRY				4
-#define FLDNUM_RAW_GYRZ				5
-#define FLDNUM_RAW_MAGX				6
-#define FLDNUM_RAW_MAGY				7
-#define FLDNUM_RAW_MAGZ				8
-#define FLDNUM_RAW_TEMP				9
-// Calibrated data
-#define FLDNUM_CALIB_ACCX			0
-#define FLDNUM_CALIB_ACCY			1
-#define FLDNUM_CALIB_ACCZ			2
-#define FLDNUM_CALIB_GYRX			3
-#define FLDNUM_CALIB_GYRY			4
-#define FLDNUM_CALIB_GYRZ			5
-#define FLDNUM_CALIB_MAGX			6
-#define FLDNUM_CALIB_MAGY			7
-#define FLDNUM_CALIB_MAGZ			8
-// Orientation data - quat
-#define FLDNUM_ORIENT_Q0			0
-#define FLDNUM_ORIENT_Q1			1
-#define FLDNUM_ORIENT_Q2			2
-#define FLDNUM_ORIENT_Q3			3
-// Orientation data - euler
-#define FLDNUM_ORIENT_ROLL			0
-#define FLDNUM_ORIENT_PITCH			1
-#define FLDNUM_ORIENT_YAW			2
-// Orientation data - matrix
-#define FLDNUM_ORIENT_A				0
-#define FLDNUM_ORIENT_B				1
-#define FLDNUM_ORIENT_C				2
-#define FLDNUM_ORIENT_D				3
-#define FLDNUM_ORIENT_E				4
-#define FLDNUM_ORIENT_F				5
-#define FLDNUM_ORIENT_G				6
-#define FLDNUM_ORIENT_H				7
-#define FLDNUM_ORIENT_I				8
-// Length
-// Uncalibrated raw data
-#define LEN_RAW_ACCX				2
-#define LEN_RAW_ACCY				2
-#define LEN_RAW_ACCZ				2
-#define LEN_RAW_GYRX				2
-#define LEN_RAW_GYRY				2
-#define LEN_RAW_GYRZ				2
-#define LEN_RAW_MAGX				2
-#define LEN_RAW_MAGY				2
-#define LEN_RAW_MAGZ				2
-#define LEN_RAW_TEMP				2
-// Calibrated data
-#define LEN_CALIB_ACCX				4
-#define LEN_CALIB_ACCY				4
-#define LEN_CALIB_ACCZ				4
-#define LEN_CALIB_GYRX				4
-#define LEN_CALIB_GYRY				4
-#define LEN_CALIB_GYRZ				4
-#define LEN_CALIB_MAGX				4
-#define LEN_CALIB_MAGY				4
-#define LEN_CALIB_MAGZ				4
-// Orientation data - quat
-#define LEN_ORIENT_Q0				4
-#define LEN_ORIENT_Q1				4
-#define LEN_ORIENT_Q2				4
-#define LEN_ORIENT_Q3				4
-// Orientation data - euler
-#define LEN_ORIENT_ROLL				4
-#define LEN_ORIENT_PITCH			4
-#define LEN_ORIENT_YAW				4
-// Orientation data - matrix
-#define LEN_ORIENT_A				4
-#define LEN_ORIENT_B				4
-#define LEN_ORIENT_C				4
-#define LEN_ORIENT_D				4
-#define LEN_ORIENT_E				4
-#define LEN_ORIENT_F				4
-#define LEN_ORIENT_G				4
-#define LEN_ORIENT_H				4
-#define LEN_ORIENT_I				4
-
-// Defines for getDataValue
-#define VALUE_RAW_ACC				0
-#define VALUE_RAW_GYR				1
-#define VALUE_RAW_MAG				2
-#define VALUE_RAW_TEMP				3
-#define VALUE_CALIB_ACC				4
-#define VALUE_CALIB_GYR				5
-#define VALUE_CALIB_MAG				6
-#define VALUE_ORIENT_QUAT			7
-#define	VALUE_ORIENT_EULER			8
-#define	VALUE_ORIENT_MATRIX			9
-#define VALUE_SAMPLECNT				10
-#define	VALUE_TEMP					11
-
-#define INVALIDSETTINGVALUE			0xFFFFFFFF
-
-// Valid in all states
-#define MID_RESET					(const unsigned char)0x40
-#define MID_RESETACK				(const unsigned char)0x41
-#define MID_ERROR					(const unsigned char)0x42
-#define LEN_ERROR					(const unsigned short)1
-// XbusMaster
-#define MID_XMPWROFF				(const unsigned char)0x44
-// End XbusMaster
-
-#define MID_REQFILTERSETTINGS		(const unsigned char)0xA0
-#define MID_REQFILTERSETTINGSACK	(const unsigned char)0xA1
-#define LEN_FILTERSETTINGS			(const unsigned short)4
-#define MID_SETFILTERSETTINGS		(const unsigned char)0xA0
-#define MID_SETFILTERSETTINGSACK	(const unsigned char)0xA1
-#define MID_REQAMD					(const unsigned char)0xA2
-#define MID_REQAMDACK				(const unsigned char)0xA3
-#define LEN_AMD						(const unsigned short)2
-#define MID_SETAMD					(const unsigned char)0xA2
-#define MID_SETAMDACK				(const unsigned char)0xA3
-#define MID_RESETORIENTATION		(const unsigned char)0xA4
-#define MID_RESETORIENTATIONACK		(const unsigned char)0xA5
-#define LEN_RESETORIENTATION		(const unsigned short)2
-
-// All Messages
-// WakeUp state messages
-#define MSG_WAKEUPLEN				5
-#define MSG_WAKEUPACK				(const unsigned char *)"\xFA\xFF\x3F\x00"
-#define MSG_WAKEUPACKLEN			4
-// Config state messages
-#define MSG_REQDID					(const unsigned char *)"\xFA\xFF\x00\x00"
-#define MSG_REQDIDLEN				4
-#define MSG_DEVICEIDLEN				9
-#define MSG_INITBUS					(const unsigned char *)"\xFA\xFF\x02\x00"
-#define MSG_INITBUSLEN				4
-#define MSG_INITBUSRESMAXLEN		(5 + 4 * MAXSENSORS)
-#define MSG_REQPERIOD				(const unsigned char *)"\xFA\xFF\x04\x00"
-#define MSG_REQPERIODLEN			4
-#define MSG_REQPERIODACKLEN			7
-#define MSG_SETPERIOD				(const unsigned char *)"\xFA\xFF\x04\x02"
-#define MSG_SETPERIODLEN			6
-#define MSG_SETPERIODACKLEN			5
-#define MSG_SETBID					(const unsigned char *)"\xFA\xFF\x06\x05"
-#define MSG_SETBIDLEN				9
-#define MSG_SETBIDACKLEN			5
-#define MSG_AUTOSTART				(const unsigned char *)"\xFA\xFF\x06\x00"
-#define MSG_AUTOSTARTLEN			4
-#define MSG_AUTOSTARTACKLEN			5
-#define MSG_BUSPWROFF				(const unsigned char *)"\xFA\xFF\x08\x00"
-#define MSG_BUSPWROFFLEN			4
-#define MSG_BUSPWROFFACKLEN			5
-#define MSG_RESTOREFACTORYDEF		(const unsigned char *)"\xFA\xFF\x0E\x00"
-#define MSG_RESTOREFACTORYDEFLEN	4
-#define MSG_RESTOREFACTORYDEFACKLEN	5
-#define MSG_REQDATALENGTH			(const unsigned char *)"\xFA\xFF\x0A\x00"
-#define MSG_REQDATALENGTHLEN		4
-#define MSG_DATALENGTHLEN			7
-#define MSG_REQCONFIGURATION		(const unsigned char *)"\xFA\xFF\x0C\x00"
-#define MSG_REQCONFIGURATIONLEN		4
-#define MSG_GOTOMEASUREMENT			(const unsigned char *)"\xFA\xFF\x10\x00"
-#define MSG_GOTOMEASUREMENTLEN		4
-#define MSG_GOTOMEASMAN				(const unsigned char *)"\xFA\x01\x10\x00"
-#define MSG_GOTOMEASMANLEN			4
-#define MSG_GOTOMEASACKLEN			5
-#define MSG_REQFWREV				(const unsigned char *)"\xFA\xFF\x12\x00"
-#define MSG_REQFWREVLEN				4
-#define MSG_FIRMWAREREVLEN			8
-#define MSG_REQBTDISABLED			(const unsigned char *)"\xFA\xFF\x14\x00"
-#define MSG_REQBTDISABLEDLEN		4
-#define MSG_REQBTDISABLEDACKLEN		6
-#define MSG_DISABLEBT				(const unsigned char *)"\xFA\xFF\x14\x01"
-#define MSG_DISABLEBTLEN			5
-#define MSG_DISABLEBTACKLEN			5
-#define MSG_REQOPMODE				(const unsigned char *)"\xFA\xFF\x16\x00"
-#define MSG_REQOPMODELEN			4
-#define MSG_REQOPMODEACKLEN			6
-#define MSG_SETOPMODE				(const unsigned char *)"\xFA\xFF\x16\x01"
-#define MSG_SETOPMODELEN			5
-#define MSG_SETOPMODEACKLEN			5
-#define MSG_REQBAUDRATE				(const unsigned char *)"\xFA\xFF\x18\x00"
-#define MSG_REQBAUDRATELEN			4
-#define MSG_REQBAUDRATEACKLEN		6	
-#define MSG_SETBAUDRATE				(const unsigned char *)"\xFA\xFF\x18\x01"
-#define MSG_SETBAUDRATELEN			5
-#define MSG_SETBAUDRATEACKLEN		5
-#define MSG_REQSYNCMODE				(const unsigned char *)"\xFA\xFF\x1A\x00"
-#define MSG_REQSYNCMODELEN			4
-#define MSG_REQSYNCMODEACKLEN		6
-#define MSG_SETSYNCMODE				(const unsigned char *)"\xFA\xFF\x1A\x01"
-#define MSG_SETSYNCMODELEN			5
-#define MSG_SETSYNCMODEACKLEN		6
-#define MSG_REQMTS					(const unsigned char *)"\xFA\xFF\x90\x01"
-#define MSG_REQMTSLEN				5
-#define MSG_MTSDATA					61
-#define MSG_STORECUSMTS				(const unsigned char *)"\xFA\xFF\x92\x58"
-#define MSG_STORECUSMTSLEN			92
-#define MSG_STORECUSMTSACKLEN		5
-#define MSG_REVTOORGMTS				(const unsigned char *)"\xFA\xFF\x94\x00"
-#define MSG_REVTOORGMTSLEN			4
-#define MSG_REVTOORGMTSACKLEN		5
-#define MSG_STOREMTS				(const unsigned char *)"\xFA\xFF\x96\x41"
-#define MSG_STOREMTSLEN				69
-#define MSG_STOREMTSACKLEN			5
-#define MSG_REQSYNCOUTMODE			(const unsigned char *)"\xFA\xFF\xD8\x01\x00"
-#define MSG_REQSYNCOUTMODELEN		5
-#define MSG_REQSYNCOUTSKIPFACTOR	(const unsigned char *)"\xFA\xFF\xD8\x01\x01"
-#define MSG_REQSYNCOUTSKIPFACTORLEN	5
-#define MSG_REQSYNCOUTOFFSET		(const unsigned char *)"\xFA\xFF\xD8\x01\x02"
-#define MSG_REQSYNCOUTOFFSETLEN		5
-#define MSG_REQSYNCOUTPULSEWIDTH	(const unsigned char *)"\xFA\xFF\xD8\x01\x03"
-#define MSG_REQSYNCOUTPULSEWIDTHLEN	5
-#define MSG_REQERRORMODE			(const unsigned char *)"\xFA\xFF\xDA\x00"
-#define MSG_REQERRORMODELEN			4
-#define MSG_REQERRORMODEACKLEN		7
-// Measurement state - auto messages
-#define MSG_GOTOCONFIG				(const unsigned char *)"\xFA\xFF\x30\x00"
-#define MSG_GOTOCONFIGLEN			4
-#define MSG_GOTOCONFIGACKLEN		5
-// Measurement state - manual messages (Use DID = 0x01)
-#define MSG_GOTOCONFIGM				(const unsigned char *)"\xFA\x01\x30\x00"
-#define MSG_GOTOCONFIGMLEN			4
-#define MSG_GOTOCONFIGMACKLEN		5
-#define MSG_PREPAREDATA				(const unsigned char *)"\xFA\x01\x32\x00"
-#define MSG_PREPAREDATALEN			4
-#define MSG_REQDATA					(const unsigned char *)"\xFA\x01\x34\x00"
-#define MSG_REQDATALEN				4
-// Valid in all states
-#define MSG_RESET					(const unsigned char *)"\xFA\xFF\x40\x00"
-#define MSG_RESETLEN				4
-#define MSG_RESETACKLEN				5
-#define MSG_XMPWROFF				(const unsigned char *)"\xFA\xFF\x44\x00"
-#define MSG_XMPWROFFLEN				4
-#define MSG_XMPWROFFACKLEN			5
-
-// Baudrate defines for SetBaudrate message
-#define BAUDRATE_9K6				0x09
-#define BAUDRATE_14K4				0x08
-#define BAUDRATE_19K2				0x07
-#define BAUDRATE_28K8				0x06
-#define BAUDRATE_38K4				0x05
-#define BAUDRATE_57K6				0x04
-#define BAUDRATE_76K8				0x03
-#define BAUDRATE_115K2				0x02
-#define BAUDRATE_230K4				0x01
-#define BAUDRATE_460K8				0x00
-#define BAUDRATE_921K6				0x80
-
-// Xbus protocol error codes (Error)
-#define ERROR_NOBUSCOMM				0x01
-#define ERROR_BUSNOTREADY			0x02
-#define ERROR_PERIODINVALID			0x03
-#define ERROR_MESSAGEINVALID		0x04
-#define ERROR_INITOFBUSFAILED1		0x10
-#define ERROR_INITOFBUSFAILED2		0x11
-#define ERROR_INITOFBUSFAILED3		0x12
-#define ERROR_SETBIDPROCFAILED1		0x14
-#define ERROR_SETBIDPROCFAILED2		0x15
-#define ERROR_MEASUREMENTFAILED1	0x18
-#define ERROR_MEASUREMENTFAILED2	0x19
-#define ERROR_MEASUREMENTFAILED3	0x1A
-#define ERROR_MEASUREMENTFAILED4	0x1B
-#define ERROR_MEASUREMENTFAILED5	0x1C
-#define ERROR_MEASUREMENTFAILED6	0x1D
-#define ERROR_TIMEROVERFLOW			0x1E
-#define ERROR_BAUDRATEINVALID		0x20
-#define ERROR_PARAMETERINVALID		0x21
-#define ERROR_MEASUREMENTFAILED7	0x23
-
-// Error modes (SetErrorMode)
-#define ERRORMODE_IGNORE					0x0000
-#define ERRORMODE_INCSAMPLECNT				0x0001
-#define ERRORMODE_INCSAMPLECNT_SENDERROR	0x0002
-#define ERRORMODE_SENDERROR_GOTOCONFIG		0x0003
-
-// Configuration message defines
-#define CONF_MASTERDID				0
-#define CONF_PERIOD					4
-#define CONF_OUTPUTSKIPFACTOR		6
-#define CONF_SYNCIN_MODE			8
-#define CONF_SYNCIN_SKIPFACTOR		10
-#define CONF_SYNCIN_OFFSET			12
-#define CONF_DATE					16
-#define CONF_TIME					24
-#define CONF_NUMDEVICES				96
-// Configuration sensor block properties
-#define CONF_DID					98
-#define CONF_DATALENGTH				102
-#define CONF_OUTPUTMODE				104
-#define CONF_OUTPUTSETTINGS			106
-#define	CONF_BLOCKLEN				20
-// To calculate the offset in data field for output mode of sensor #2 use
-//		CONF_OUTPUTMODE + 1*CONF_BLOCKLEN
-#define CONF_MASTERDIDLEN			4
-#define CONF_PERIODLEN				2
-#define CONF_OUTPUTSKIPFACTORLEN	2
-#define CONF_SYNCIN_MODELEN			2
-#define CONF_SYNCIN_SKIPFACTORLEN	2
-#define CONF_SYNCIN_OFFSETLEN		4
-#define CONF_DATELEN				8
-#define CONF_TIMELEN				8
-#define CONF_RESERVED_CLIENTLEN		32
-#define CONF_RESERVED_HOSTLEN		32
-#define CONF_NUMDEVICESLEN			2
-// Configuration sensor block properties
-#define CONF_DIDLEN					4
-#define CONF_DATALENGTHLEN			2
-#define CONF_OUTPUTMODELEN			2
-#define CONF_OUTPUTSETTINGSLEN		4
-
-// Clock frequency for offset & pulse width
-#define SYNC_CLOCKFREQ				29.4912e6
-
-// SyncIn params
-#define PARAM_SYNCIN_MODE			(const unsigned char)0x00
-#define PARAM_SYNCIN_SKIPFACTOR		(const unsigned char)0x01
-#define PARAM_SYNCIN_OFFSET			(const unsigned char)0x02
-
-// SyncIn mode
-#define SYNCIN_DISABLED				0x0000
-#define SYNCIN_EDGE_RISING			0x0001
-#define SYNCIN_EDGE_FALLING			0x0002
-#define SYNCIN_EDGE_BOTH			0x0003
-#define SYNCIN_TYPE_SENDLASTDATA	0x0004
-#define SYNCIN_TYPE_DOSAMPLING		0x0000
-#define SYNCIN_EDGE_MASK			0x0003
-#define SYNCIN_TYPE_MASK			0x000C
-
-// SyncOut params
-#define PARAM_SYNCOUT_MODE			(const unsigned char)0x00
-#define PARAM_SYNCOUT_SKIPFACTOR	(const unsigned char)0x01
-#define PARAM_SYNCOUT_OFFSET		(const unsigned char)0x02
-#define PARAM_SYNCOUT_PULSEWIDTH	(const unsigned char)0x03
-
-// SyncOut mode
-#define SYNCOUT_DISABLED		0x0000
-#define SYNCOUT_TYPE_TOGGLE		0x0001
-#define SYNCOUT_TYPE_PULSE		0x0002
-#define SYNCOUT_POL_NEG			0x0000
-#define SYNCOUT_POL_POS			0x0010
-#define SYNCOUT_TYPE_MASK		0x000F
-#define SYNCOUT_POL_MASK		0x0010
-
-// Sample frequencies (SetPeriod)
-#define PERIOD_10HZ				0x2D00
-#define PERIOD_12HZ				0x2580
-#define PERIOD_15HZ				0x1E00
-#define PERIOD_16HZ				0x1C20
-#define PERIOD_18HZ				0x1900
-#define PERIOD_20HZ				0x1680
-#define PERIOD_24HZ				0x12C0
-#define PERIOD_25HZ				0x1200
-#define PERIOD_30HZ				0x0F00
-#define PERIOD_32HZ				0x0E10
-#define PERIOD_36HZ				0x0C80
-#define PERIOD_40HZ				0x0B40
-#define PERIOD_45HZ				0x0A00
-#define PERIOD_48HZ				0x0960
-#define PERIOD_50HZ				0x0900
-#define PERIOD_60HZ				0x0780
-#define PERIOD_64HZ				0x0708
-#define PERIOD_72HZ				0x0640
-#define PERIOD_75HZ				0x0600
-#define PERIOD_80HZ				0x05A0
-#define PERIOD_90HZ				0x0500
-#define PERIOD_96HZ				0x04B0
-#define PERIOD_100HZ			0x0480
-#define PERIOD_120HZ			0x03C0
-#define PERIOD_128HZ			0x0384
-#define PERIOD_144HZ			0x0320
-#define PERIOD_150HZ			0x0300
-#define PERIOD_160HZ			0x02D0
-#define PERIOD_180HZ			0x0280
-#define PERIOD_192HZ			0x0258
-#define PERIOD_200HZ			0x0240
-#define PERIOD_225HZ			0x0200
-#define PERIOD_240HZ			0x01E0
-#define PERIOD_256HZ			0x01C2
-#define PERIOD_288HZ			0x0190
-#define PERIOD_300HZ			0x0180
-#define PERIOD_320HZ			0x0168
-#define PERIOD_360HZ			0x0140
-#define PERIOD_384HZ			0x012C
-#define PERIOD_400HZ			0x0120
-#define PERIOD_450HZ			0x0100
-#define PERIOD_480HZ			0x00F0
-#define PERIOD_512HZ			0x00E1
-
-// OutputModes
-#define OUTPUTMODE_MT9				0x8000
-#define OUTPUTMODE_XM				0x0000
-#define OUTPUTMODE_RAW				0x4000
-#define OUTPUTMODE_TEMP				0x0001
-#define OUTPUTMODE_CALIB			0x0002
-#define OUTPUTMODE_ORIENT			0x0004
-
-// OutputSettings
-#define OUTPUTSETTINGS_XM						0x00000001
-#define OUTPUTSETTINGS_TIMESTAMP_NONE			0x00000000
-#define OUTPUTSETTINGS_TIMESTAMP_SAMPLECNT		0x00000001
-#define OUTPUTSETTINGS_ORIENTMODE_QUATERNION	0x00000000
-#define OUTPUTSETTINGS_ORIENTMODE_EULER			0x00000004
-#define OUTPUTSETTINGS_ORIENTMODE_MATRIX		0x00000008
-#define OUTPUTSETTINGS_CALIBMODE_ACCGYRMAG		0x00000000
-#define OUTPUTSETTINGS_CALIBMODE_ACC			0x00000060
-#define OUTPUTSETTINGS_CALIBMODE_ACCGYR			0x00000040
-#define OUTPUTSETTINGS_CALIBMODE_ACCMAG			0x00000020
-#define OUTPUTSETTINGS_CALIBMODE_GYR			0x00000050
-#define OUTPUTSETTINGS_CALIBMODE_GYRMAG			0x00000010
-#define OUTPUTSETTINGS_CALIBMODE_MAG			0x00000030
-#define OUTPUTSETTINGS_DATAFORMAT_FLOAT			0x00000000
-#define OUTPUTSETTINGS_DATAFORMAT_F1220			0x00000100
-#define OUTPUTSETTINGS_TIMESTAMP_MASK			0x00000003
-#define OUTPUTSETTINGS_ORIENTMODE_MASK			0x0000000C
-#define OUTPUTSETTINGS_CALIBMODE_ACC_MASK		0x00000010
-#define OUTPUTSETTINGS_CALIBMODE_GYR_MASK		0x00000020
-#define OUTPUTSETTINGS_CALIBMODE_MAG_MASK		0x00000040
-#define OUTPUTSETTINGS_CALIBMODE_MASK			0x00000070
-#define OUTPUTSETTINGS_DATAFORMAT_MASK			0x00000300
-
-// Extended Output Modes
-#define EXTOUTPUTMODE_DISABLED			0x0000
-#define EXTOUTPUTMODE_EULER				0x0001
-
-// Factory Output Mode
-#define FACTORYOUTPUTMODE_DISABLE		0x0000
-#define FACTORYOUTPUTMODE_DEFAULT		0x0001
-#define FACTORYOUTPUTMODE_CUSTOM		0x0002
-
-// Initial tracking mode (SetInitTrackMode)
-#define INITTRACKMODE_DISABLED		0x0000
-#define INITTRACKMODE_ENABLED		0x0001
-
-// Filter settings params
-#define PARAM_FILTER_GAIN			(const unsigned char)0x00
-#define PARAM_FILTER_RHO			(const unsigned char)0x01
-#define DONOTSTORE					0x00
-#define STORE						0x01
-
-// AMDSetting (SetAMD)
-#define AMDSETTING_DISABLED			0x0000
-#define AMDSETTING_ENABLED			0x0001
-
-// Reset orientation message type
-#define RESETORIENTATION_STORE		0
-#define RESETORIENTATION_HEADING	1
-#define RESETORIENTATION_GLOBAL		2
-#define RESETORIENTATION_OBJECT		3
-#define RESETORIENTATION_ALIGN		4
-
-// Send raw string mode
-#define SENDRAWSTRING_INIT			0
-#define SENDRAWSTRING_DEFAULT		1
-#define SENDRAWSTRING_SEND			2
-
-// Timeouts	
-#define TO_DEFAULT					500
-#define TO_INIT						250
-#define TO_RETRY					50
-
-// openPort baudrates
+        // Field message indexes
+#define IND_PREAMBLE                0
+#define IND_BID                     1
+#define IND_MID                     2
+#define IND_LEN                     3
+#define IND_DATA0                   4
+#define IND_LENEXTH                 4
+#define IND_LENEXTL                 5
+#define IND_DATAEXT0                6
+
+        // Maximum number of sensors supported
+#define MAXDEVICES                  20
+
+#define PREAMBLE                    (const unsigned char)0xFA
+#define BID_MASTER                  (const unsigned char)0xFF
+#define BID_MT                      (const unsigned char)0x01
+#define EXTLENCODE                  0xFF
+
+#define LEN_MSGHEADER               (const unsigned short)4
+#define LEN_MSGEXTHEADER            (const unsigned short)6
+#define LEN_MSGHEADERCS             (const unsigned short)5
+#define LEN_MSGEXTHEADERCS          (const unsigned short)7
+#define LEN_CHECKSUM                (const unsigned short)1
+#define LEN_UNSIGSHORT              (const unsigned short)2
+#define LEN_UNSIGINT                (const unsigned short)4
+#define LEN_FLOAT                   (const unsigned short)4
+
+        // Maximum message/data length
+#define MAXDATALEN                  (const unsigned short)2048
+#define MAXSHORTDATALEN             (const unsigned short)254
+#define MAXMSGLEN                   (const unsigned short)(MAXDATALEN+7)
+#define MAXSHORTMSGLEN              (const unsigned short)(MAXSHORTDATALEN+5)
+
+        // DID Type (high nibble)
+#define DID_TYPEH_MASK              (const unsigned long)0x00F00000
+#define DID_TYPEH_MT                (const unsigned long)0x00000000
+#define DID_TYPEH_XM                (const unsigned long)0x00100000
+#define DID_TYPEH_MTI_MTX           (const unsigned long)0x00300000
+
+        // All Message identifiers
+        // WakeUp state messages
+#define MID_WAKEUP                  (const unsigned char)0x3E
+#define MID_WAKEUPACK               (const unsigned char)0x3F
+
+        // Config state messages
+#define MID_REQDID                  (const unsigned char)0x00
+#define MID_DEVICEID                (const unsigned char)0x01
+#define LEN_DEVICEID                (const unsigned short)4
+#define MID_INITBUS                 (const unsigned char)0x02
+#define MID_INITBUSRESULTS          (const unsigned char)0x03
+#define LEN_INITBUSRESULTS          (const unsigned short)4
+#define MID_REQPERIOD               (const unsigned char)0x04
+#define MID_REQPERIODACK            (const unsigned char)0x05
+#define LEN_PERIOD                  (const unsigned short)2
+#define MID_SETPERIOD               (const unsigned char)0x04
+#define MID_SETPERIODACK            (const unsigned char)0x05
+        // XbusMaster
+#define MID_SETBID                  (const unsigned char)0x06
+#define MID_SETBIDACK               (const unsigned char)0x07
+#define MID_AUTOSTART               (const unsigned char)0x06
+#define MID_AUTOSTARTACK            (const unsigned char)0x07
+#define MID_BUSPWROFF               (const unsigned char)0x08
+#define MID_BUSPWROFFACK            (const unsigned char)0x09
+        // End XbusMaster
+#define MID_REQDATALENGTH           (const unsigned char)0x0A
+#define MID_DATALENGTH              (const unsigned char)0x0B
+#define LEN_DATALENGTH              (const unsigned short)2
+#define MID_REQCONFIGURATION        (const unsigned char)0x0C
+#define MID_CONFIGURATION           (const unsigned char)0x0D
+#define LEN_CONFIGURATION           (const unsigned short)118
+#define MID_RESTOREFACTORYDEF       (const unsigned char)0x0E
+#define MID_RESTOREFACTORYDEFACK    (const unsigned char)0x0F
+
+#define MID_GOTOMEASUREMENT         (const unsigned char)0x10
+#define MID_GOTOMEASUREMENTACK      (const unsigned char)0x11
+#define MID_REQFWREV                (const unsigned char)0x12
+#define MID_FIRMWAREREV             (const unsigned char)0x13
+#define LEN_FIRMWAREREV             (const unsigned short)3
+        // XbusMaster
+#define MID_REQBTDISABLE            (const unsigned char)0x14
+#define MID_REQBTDISABLEACK         (const unsigned char)0x15
+#define MID_DISABLEBT               (const unsigned char)0x14
+#define MID_DISABLEBTACK            (const unsigned char)0x15
+#define MID_REQOPMODE               (const unsigned char)0x16
+#define MID_REQOPMODEACK            (const unsigned char)0x17
+#define MID_SETOPMODE               (const unsigned char)0x16
+#define MID_SETOPMODEACK            (const unsigned char)0x17
+        // End XbusMaster
+#define MID_REQBAUDRATE             (const unsigned char)0x18
+#define MID_REQBAUDRATEACK          (const unsigned char)0x19
+#define LEN_BAUDRATE                (const unsigned short)1
+#define MID_SETBAUDRATE             (const unsigned char)0x18
+#define MID_SETBAUDRATEACK          (const unsigned char)0x19
+        // XbusMaster
+#define MID_REQSYNCMODE             (const unsigned char)0x1A
+#define MID_REQSYNCMODEACK          (const unsigned char)0x1B
+#define MID_SETSYNCMODE             (const unsigned char)0x1A
+#define MID_SETSYNCMODEACK          (const unsigned char)0x1B
+        // End XbusMaster
+#define MID_REQPRODUCTCODE          (const unsigned char)0x1C
+#define MID_PRODUCTCODE             (const unsigned char)0x1D
+
+#define MID_REQOUTPUTMODE           (const unsigned char)0xD0
+#define MID_REQOUTPUTMODEACK        (const unsigned char)0xD1
+#define LEN_OUTPUTMODE              (const unsigned short)2
+#define MID_SETOUTPUTMODE           (const unsigned char)0xD0
+#define MID_SETOUTPUTMODEACK        (const unsigned char)0xD1
+
+#define MID_REQOUTPUTSETTINGS       (const unsigned char)0xD2
+#define MID_REQOUTPUTSETTINGSACK    (const unsigned char)0xD3
+#define LEN_OUTPUTSETTINGS          (const unsigned short)4
+#define MID_SETOUTPUTSETTINGS       (const unsigned char)0xD2
+#define MID_SETOUTPUTSETTINGSACK    (const unsigned char)0xD3
+
+#define MID_REQOUTPUTSKIPFACTOR     (const unsigned char)0xD4
+#define MID_REQOUTPUTSKIPFACTORACK  (const unsigned char)0xD5
+#define LEN_OUTPUTSKIPFACTOR        (const unsigned short)2
+#define MID_SETOUTPUTSKIPFACTOR     (const unsigned char)0xD4
+#define MID_SETOUTPUTSKIPFACTORACK  (const unsigned char)0xD5
+
+#define MID_REQSYNCINSETTINGS       (const unsigned char)0xD6
+#define MID_REQSYNCINSETTINGSACK    (const unsigned char)0xD7
+#define LEN_SYNCINMODE              (const unsigned short)2
+#define LEN_SYNCINSKIPFACTOR        (const unsigned short)2
+#define LEN_SYNCINOFFSET            (const unsigned short)4
+#define MID_SETSYNCINSETTINGS       (const unsigned char)0xD6
+#define MID_SETSYNCINSETTINGSACK    (const unsigned char)0xD7
+
+#define MID_REQSYNCOUTSETTINGS      (const unsigned char)0xD8
+#define MID_REQSYNCOUTSETTINGSACK   (const unsigned char)0xD9
+#define LEN_SYNCOUTMODE             (const unsigned short)2
+#define LEN_SYNCOUTSKIPFACTOR       (const unsigned short)2
+#define LEN_SYNCOUTOFFSET           (const unsigned short)4
+#define LEN_SYNCOUTPULSEWIDTH       (const unsigned short)4
+#define MID_SETSYNCOUTSETTINGS      (const unsigned char)0xD8
+#define MID_SETSYNCOUTSETTINGSACK   (const unsigned char)0xD9
+
+#define MID_REQERRORMODE            (const unsigned char)0xDA
+#define MID_REQERRORMODEACK         (const unsigned char)0xDB
+#define LEN_ERRORMODE               (const unsigned short)2
+#define MID_SETERRORMODE            (const unsigned char)0xDA
+#define MID_SETERRORMODEACK         (const unsigned char)0xDB
+
+#define MID_REQTRANSMITDELAY        (const unsigned char)0xDC
+#define MID_REQTRANSMITDELAYACK     (const unsigned char)0xDD
+#define LEN_TRANSMITDELAY           (const unsigned short)2
+#define MID_SETTRANSMITDELAY        (const unsigned char)0xDC
+#define MID_SETTRANSMITDELAYACK     (const unsigned char)0xDD
+
+        // Xbus Master
+#define MID_REQXMERRORMODE          (const unsigned char)0x82
+#define MID_REQXMERRORMODEACK       (const unsigned char)0x83
+#define LEN_XMERRORMODE             (const unsigned short)2
+#define MID_SETXMERRORMODE          (const unsigned char)0x82
+#define MID_SETXMERRORMODEACK       (const unsigned char)0x83
+
+#define MID_REQBUFFERSIZE           (const unsigned char)0x84
+#define MID_REQBUFFERSIZEACK        (const unsigned char)0x85
+#define LEN_BUFFERSIZE              (const unsigned short)2
+#define MID_SETBUFFERSIZE           (const unsigned char)0x84
+#define MID_SETBUFFERSIZEACK        (const unsigned char)0x85
+        // End Xbus Master
+
+#define MID_REQHEADING              (const unsigned char)0x82
+#define MID_REQHEADINGACK           (const unsigned char)0x83
+#define LEN_HEADING                 (const unsigned short)4
+#define MID_SETHEADING              (const unsigned char)0x82
+#define MID_SETHEADINGACK           (const unsigned char)0x83
+
+#define MID_REQLOCATIONID           (const unsigned char)0x84
+#define MID_REQLOCATIONIDACK        (const unsigned char)0x85
+#define LEN_LOCATIONID              (const unsigned short)2
+#define MID_SETLOCATIONID           (const unsigned char)0x84
+#define MID_SETLOCATIONIDACK        (const unsigned char)0x85
+
+#define MID_REQEXTOUTPUTMODE        (const unsigned char)0x86
+#define MID_REQEXTOUTPUTMODEACK     (const unsigned char)0x87
+#define LEN_EXTOUTPUTMODE           (const unsigned short)2
+#define MID_SETEXTOUTPUTMODE        (const unsigned char)0x86
+#define MID_SETEXTOUTPUTMODEACK     (const unsigned char)0x87
+
+        // XbusMaster
+#define MID_REQBATLEVEL             (const unsigned char)0x88
+#define MID_BATLEVEL                (const unsigned char)0x89
+        // End XbusMaster
+
+#define MID_REQINITTRACKMODE        (const unsigned char)0x88
+#define MID_REQINITTRACKMODEACK     (const unsigned char)0x89
+#define LEN_INITTRACKMODE           (const unsigned short)2
+#define MID_SETINITTRACKMODE        (const unsigned char)0x88
+#define MID_SETINITTRACKMODEACK     (const unsigned char)0x89
+
+#define MID_STOREFILTERSTATE        (const unsigned char)0x8A
+#define MID_STOREFILTERSTATEACK     (const unsigned char)0x8B
+
+        // Measurement state
+#define MID_GOTOCONFIG              (const unsigned char)0x30
+#define MID_GOTOCONFIGACK           (const unsigned char)0x31
+#define MID_BUSDATA                 (const unsigned char)0x32
+#define MID_MTDATA                  (const unsigned char)0x32
+
+        // Manual
+#define MID_PREPAREDATA             (const unsigned char)0x32
+#define MID_REQDATA                 (const unsigned char)0x34
+#define MID_REQDATAACK              (const unsigned char)0x35
+
+        // MTData defines
+        // Length of data blocks in bytes
+#define LEN_RAWDATA                 (const unsigned short)20
+#define LEN_CALIBDATA               (const unsigned short)36
+#define LEN_CALIB_ACCDATA           (const unsigned short)12
+#define LEN_CALIB_GYRDATA           (const unsigned short)12
+#define LEN_CALIB_MAGDATA           (const unsigned short)12
+#define LEN_ORIENT_QUATDATA         (const unsigned short)16
+#define LEN_ORIENT_EULERDATA        (const unsigned short)12
+#define LEN_ORIENT_MATRIXDATA       (const unsigned short)36
+#define LEN_SAMPLECNT               (const unsigned short)2
+#define LEN_TEMPDATA                (const unsigned short)4
+
+        // Length of data blocks in floats
+#define LEN_CALIBDATA_FLT           (const unsigned short)9
+#define LEN_ORIENT_QUATDATA_FLT     (const unsigned short)4
+#define LEN_ORIENT_EULERDATA_FLT    (const unsigned short)3
+#define LEN_ORIENT_MATRIXDATA_FLT   (const unsigned short)9
+
+        // Indices of fields in DATA field of MTData message in bytes
+        // use in combination with LEN_CALIB etc
+        // Un-calibrated raw data
+#define IND_RAW_ACCX                0
+#define IND_RAW_ACCY                2
+#define IND_RAW_ACCZ                4
+#define IND_RAW_GYRX                6
+#define IND_RAW_GYRY                8
+#define IND_RAW_GYRZ                10
+#define IND_RAW_MAGX                12
+#define IND_RAW_MAGY                14
+#define IND_RAW_MAGZ                16
+#define IND_RAW_TEMP                18
+        // Calibrated data
+#define IND_CALIB_ACCX              0
+#define IND_CALIB_ACCY              4
+#define IND_CALIB_ACCZ              8
+#define IND_CALIB_GYRX              12
+#define IND_CALIB_GYRY              16
+#define IND_CALIB_GYRZ              20
+#define IND_CALIB_MAGX              24
+#define IND_CALIB_MAGY              28
+#define IND_CALIB_MAGZ              32
+        // Orientation data - quat
+#define IND_ORIENT_Q0               0
+#define IND_ORIENT_Q1               4
+#define IND_ORIENT_Q2               8
+#define IND_ORIENT_Q3               12
+        // Orientation data - euler
+#define IND_ORIENT_ROLL             0
+#define IND_ORIENT_PITCH            4
+#define IND_ORIENT_YAW              8
+        // Orientation data - matrix
+#define IND_ORIENT_A                0
+#define IND_ORIENT_B                4
+#define IND_ORIENT_C                8
+#define IND_ORIENT_D                12
+#define IND_ORIENT_E                16
+#define IND_ORIENT_F                20
+#define IND_ORIENT_G                24
+#define IND_ORIENT_H                28
+#define IND_ORIENT_I                32
+        // Orientation data - euler
+#define IND_SAMPLECNTH              0
+#define IND_SAMPLECNTL              1
+
+        // Indices of fields in DATA field of MTData message
+        // Un-calibrated raw data
+#define FLDNUM_RAW_ACCX             0
+#define FLDNUM_RAW_ACCY             1
+#define FLDNUM_RAW_ACCZ             2
+#define FLDNUM_RAW_GYRX             3
+#define FLDNUM_RAW_GYRY             4
+#define FLDNUM_RAW_GYRZ             5
+#define FLDNUM_RAW_MAGX             6
+#define FLDNUM_RAW_MAGY             7
+#define FLDNUM_RAW_MAGZ             8
+#define FLDNUM_RAW_TEMP             9
+        // Calibrated data
+#define FLDNUM_CALIB_ACCX           0
+#define FLDNUM_CALIB_ACCY           1
+#define FLDNUM_CALIB_ACCZ           2
+#define FLDNUM_CALIB_GYRX           3
+#define FLDNUM_CALIB_GYRY           4
+#define FLDNUM_CALIB_GYRZ           5
+#define FLDNUM_CALIB_MAGX           6
+#define FLDNUM_CALIB_MAGY           7
+#define FLDNUM_CALIB_MAGZ           8
+        // Orientation data - quat
+#define FLDNUM_ORIENT_Q0            0
+#define FLDNUM_ORIENT_Q1            1
+#define FLDNUM_ORIENT_Q2            2
+#define FLDNUM_ORIENT_Q3            3
+        // Orientation data - euler
+#define FLDNUM_ORIENT_ROLL          0
+#define FLDNUM_ORIENT_PITCH         1
+#define FLDNUM_ORIENT_YAW           2
+        // Orientation data - matrix
+#define FLDNUM_ORIENT_A             0
+#define FLDNUM_ORIENT_B             1
+#define FLDNUM_ORIENT_C             2
+#define FLDNUM_ORIENT_D             3
+#define FLDNUM_ORIENT_E             4
+#define FLDNUM_ORIENT_F             5
+#define FLDNUM_ORIENT_G             6
+#define FLDNUM_ORIENT_H             7
+#define FLDNUM_ORIENT_I             8
+        // Length
+        // Uncalibrated raw data
+#define LEN_RAW_ACCX                2
+#define LEN_RAW_ACCY                2
+#define LEN_RAW_ACCZ                2
+#define LEN_RAW_GYRX                2
+#define LEN_RAW_GYRY                2
+#define LEN_RAW_GYRZ                2
+#define LEN_RAW_MAGX                2
+#define LEN_RAW_MAGY                2
+#define LEN_RAW_MAGZ                2
+#define LEN_RAW_TEMP                2
+        // Calibrated data
+#define LEN_CALIB_ACCX              4
+#define LEN_CALIB_ACCY              4
+#define LEN_CALIB_ACCZ              4
+#define LEN_CALIB_GYRX              4
+#define LEN_CALIB_GYRY              4
+#define LEN_CALIB_GYRZ              4
+#define LEN_CALIB_MAGX              4
+#define LEN_CALIB_MAGY              4
+#define LEN_CALIB_MAGZ              4
+        // Orientation data - quat
+#define LEN_ORIENT_Q0               4
+#define LEN_ORIENT_Q1               4
+#define LEN_ORIENT_Q2               4
+#define LEN_ORIENT_Q3               4
+        // Orientation data - euler
+#define LEN_ORIENT_ROLL             4
+#define LEN_ORIENT_PITCH            4
+#define LEN_ORIENT_YAW              4
+        // Orientation data - matrix
+#define LEN_ORIENT_A                4
+#define LEN_ORIENT_B                4
+#define LEN_ORIENT_C                4
+#define LEN_ORIENT_D                4
+#define LEN_ORIENT_E                4
+#define LEN_ORIENT_F                4
+#define LEN_ORIENT_G                4
+#define LEN_ORIENT_H                4
+#define LEN_ORIENT_I                4
+
+        // Defines for getDataValue
+#define VALUE_RAW_ACC               0
+#define VALUE_RAW_GYR               1
+#define VALUE_RAW_MAG               2
+#define VALUE_RAW_TEMP              3
+#define VALUE_CALIB_ACC             4
+#define VALUE_CALIB_GYR             5
+#define VALUE_CALIB_MAG             6
+#define VALUE_ORIENT_QUAT           7
+#define VALUE_ORIENT_EULER          8
+#define VALUE_ORIENT_MATRIX         9
+#define VALUE_SAMPLECNT             10
+#define VALUE_TEMP                  11
+
+#define INVALIDSETTINGVALUE         0xFFFFFFFF
+
+        // Valid in all states
+#define MID_RESET                   (const unsigned char)0x40
+#define MID_RESETACK                (const unsigned char)0x41
+#define MID_ERROR                   (const unsigned char)0x42
+#define LEN_ERROR                   (const unsigned short)1
+        // XbusMaster
+#define MID_XMPWROFF                (const unsigned char)0x44
+        // End XbusMaster
+
+#define MID_REQFILTERSETTINGS       (const unsigned char)0xA0
+#define MID_REQFILTERSETTINGSACK    (const unsigned char)0xA1
+#define LEN_FILTERSETTINGS          (const unsigned short)4
+#define MID_SETFILTERSETTINGS       (const unsigned char)0xA0
+#define MID_SETFILTERSETTINGSACK    (const unsigned char)0xA1
+#define MID_REQAMD                  (const unsigned char)0xA2
+#define MID_REQAMDACK               (const unsigned char)0xA3
+#define LEN_AMD                     (const unsigned short)2
+#define MID_SETAMD                  (const unsigned char)0xA2
+#define MID_SETAMDACK               (const unsigned char)0xA3
+#define MID_RESETORIENTATION        (const unsigned char)0xA4
+#define MID_RESETORIENTATIONACK     (const unsigned char)0xA5
+#define LEN_RESETORIENTATION        (const unsigned short)2
+
+        // All Messages
+        // WakeUp state messages
+#define MSG_WAKEUPLEN               5
+#define MSG_WAKEUPACK               (const unsigned char *)"\xFA\xFF\x3F\x00"
+#define MSG_WAKEUPACKLEN            4
+        // Config state messages
+#define MSG_REQDID                  (const unsigned char *)"\xFA\xFF\x00\x00"
+#define MSG_REQDIDLEN               4
+#define MSG_DEVICEIDLEN             9
+#define MSG_INITBUS                 (const unsigned char *)"\xFA\xFF\x02\x00"
+#define MSG_INITBUSLEN              4
+#define MSG_INITBUSRESMAXLEN        (5 + 4 * MAXSENSORS)
+#define MSG_REQPERIOD               (const unsigned char *)"\xFA\xFF\x04\x00"
+#define MSG_REQPERIODLEN            4
+#define MSG_REQPERIODACKLEN         7
+#define MSG_SETPERIOD               (const unsigned char *)"\xFA\xFF\x04\x02"
+#define MSG_SETPERIODLEN            6
+#define MSG_SETPERIODACKLEN         5
+#define MSG_SETBID                  (const unsigned char *)"\xFA\xFF\x06\x05"
+#define MSG_SETBIDLEN               9
+#define MSG_SETBIDACKLEN            5
+#define MSG_AUTOSTART               (const unsigned char *)"\xFA\xFF\x06\x00"
+#define MSG_AUTOSTARTLEN            4
+#define MSG_AUTOSTARTACKLEN         5
+#define MSG_BUSPWROFF               (const unsigned char *)"\xFA\xFF\x08\x00"
+#define MSG_BUSPWROFFLEN            4
+#define MSG_BUSPWROFFACKLEN         5
+#define MSG_RESTOREFACTORYDEF       (const unsigned char *)"\xFA\xFF\x0E\x00"
+#define MSG_RESTOREFACTORYDEFLEN    4
+#define MSG_RESTOREFACTORYDEFACKLEN 5
+#define MSG_REQDATALENGTH           (const unsigned char *)"\xFA\xFF\x0A\x00"
+#define MSG_REQDATALENGTHLEN        4
+#define MSG_DATALENGTHLEN           7
+#define MSG_REQCONFIGURATION        (const unsigned char *)"\xFA\xFF\x0C\x00"
+#define MSG_REQCONFIGURATIONLEN     4
+#define MSG_GOTOMEASUREMENT         (const unsigned char *)"\xFA\xFF\x10\x00"
+#define MSG_GOTOMEASUREMENTLEN      4
+#define MSG_GOTOMEASMAN             (const unsigned char *)"\xFA\x01\x10\x00"
+#define MSG_GOTOMEASMANLEN          4
+#define MSG_GOTOMEASACKLEN          5
+#define MSG_REQFWREV                (const unsigned char *)"\xFA\xFF\x12\x00"
+#define MSG_REQFWREVLEN             4
+#define MSG_FIRMWAREREVLEN          8
+#define MSG_REQBTDISABLED           (const unsigned char *)"\xFA\xFF\x14\x00"
+#define MSG_REQBTDISABLEDLEN        4
+#define MSG_REQBTDISABLEDACKLEN     6
+#define MSG_DISABLEBT               (const unsigned char *)"\xFA\xFF\x14\x01"
+#define MSG_DISABLEBTLEN            5
+#define MSG_DISABLEBTACKLEN         5
+#define MSG_REQOPMODE               (const unsigned char *)"\xFA\xFF\x16\x00"
+#define MSG_REQOPMODELEN            4
+#define MSG_REQOPMODEACKLEN         6
+#define MSG_SETOPMODE               (const unsigned char *)"\xFA\xFF\x16\x01"
+#define MSG_SETOPMODELEN            5
+#define MSG_SETOPMODEACKLEN         5
+#define MSG_REQBAUDRATE             (const unsigned char *)"\xFA\xFF\x18\x00"
+#define MSG_REQBAUDRATELEN          4
+#define MSG_REQBAUDRATEACKLEN       6
+#define MSG_SETBAUDRATE             (const unsigned char *)"\xFA\xFF\x18\x01"
+#define MSG_SETBAUDRATELEN          5
+#define MSG_SETBAUDRATEACKLEN       5
+#define MSG_REQSYNCMODE             (const unsigned char *)"\xFA\xFF\x1A\x00"
+#define MSG_REQSYNCMODELEN          4
+#define MSG_REQSYNCMODEACKLEN       6
+#define MSG_SETSYNCMODE             (const unsigned char *)"\xFA\xFF\x1A\x01"
+#define MSG_SETSYNCMODELEN          5
+#define MSG_SETSYNCMODEACKLEN       6
+#define MSG_REQMTS                  (const unsigned char *)"\xFA\xFF\x90\x01"
+#define MSG_REQMTSLEN               5
+#define MSG_MTSDATA                 61
+#define MSG_STORECUSMTS             (const unsigned char *)"\xFA\xFF\x92\x58"
+#define MSG_STORECUSMTSLEN          92
+#define MSG_STORECUSMTSACKLEN       5
+#define MSG_REVTOORGMTS             (const unsigned char *)"\xFA\xFF\x94\x00"
+#define MSG_REVTOORGMTSLEN          4
+#define MSG_REVTOORGMTSACKLEN       5
+#define MSG_STOREMTS                (const unsigned char *)"\xFA\xFF\x96\x41"
+#define MSG_STOREMTSLEN             69
+#define MSG_STOREMTSACKLEN          5
+#define MSG_REQSYNCOUTMODE          (const unsigned char *)"\xFA\xFF\xD8\x01\x00"
+#define MSG_REQSYNCOUTMODELEN       5
+#define MSG_REQSYNCOUTSKIPFACTOR    (const unsigned char *)"\xFA\xFF\xD8\x01\x01"
+#define MSG_REQSYNCOUTSKIPFACTORLEN 5
+#define MSG_REQSYNCOUTOFFSET        (const unsigned char *)"\xFA\xFF\xD8\x01\x02"
+#define MSG_REQSYNCOUTOFFSETLEN     5
+#define MSG_REQSYNCOUTPULSEWIDTH    (const unsigned char *)"\xFA\xFF\xD8\x01\x03"
+#define MSG_REQSYNCOUTPULSEWIDTHLEN 5
+#define MSG_REQERRORMODE            (const unsigned char *)"\xFA\xFF\xDA\x00"
+#define MSG_REQERRORMODELEN         4
+#define MSG_REQERRORMODEACKLEN      7
+        // Measurement state - auto messages
+#define MSG_GOTOCONFIG              (const unsigned char *)"\xFA\xFF\x30\x00"
+#define MSG_GOTOCONFIGLEN           4
+#define MSG_GOTOCONFIGACKLEN        5
+        // Measurement state - manual messages (Use DID = 0x01)
+#define MSG_GOTOCONFIGM             (const unsigned char *)"\xFA\x01\x30\x00"
+#define MSG_GOTOCONFIGMLEN          4
+#define MSG_GOTOCONFIGMACKLEN       5
+#define MSG_PREPAREDATA             (const unsigned char *)"\xFA\x01\x32\x00"
+#define MSG_PREPAREDATALEN          4
+#define MSG_REQDATA                 (const unsigned char *)"\xFA\x01\x34\x00"
+#define MSG_REQDATALEN              4
+        // Valid in all states
+#define MSG_RESET                   (const unsigned char *)"\xFA\xFF\x40\x00"
+#define MSG_RESETLEN                4
+#define MSG_RESETACKLEN             5
+#define MSG_XMPWROFF                (const unsigned char *)"\xFA\xFF\x44\x00"
+#define MSG_XMPWROFFLEN             4
+#define MSG_XMPWROFFACKLEN          5
+
+        // Baudrate defines for SetBaudrate message
+#define BAUDRATE_9K6                0x09
+#define BAUDRATE_14K4               0x08
+#define BAUDRATE_19K2               0x07
+#define BAUDRATE_28K8               0x06
+#define BAUDRATE_38K4               0x05
+#define BAUDRATE_57K6               0x04
+#define BAUDRATE_76K8               0x03
+#define BAUDRATE_115K2              0x02
+#define BAUDRATE_230K4              0x01
+#define BAUDRATE_460K8              0x00
+#define BAUDRATE_921K6              0x80
+
+        // Xbus protocol error codes (Error)
+#define ERROR_NOBUSCOMM             0x01
+#define ERROR_BUSNOTREADY           0x02
+#define ERROR_PERIODINVALID         0x03
+#define ERROR_MESSAGEINVALID        0x04
+#define ERROR_INITOFBUSFAILED1      0x10
+#define ERROR_INITOFBUSFAILED2      0x11
+#define ERROR_INITOFBUSFAILED3      0x12
+#define ERROR_SETBIDPROCFAILED1     0x14
+#define ERROR_SETBIDPROCFAILED2     0x15
+#define ERROR_MEASUREMENTFAILED1    0x18
+#define ERROR_MEASUREMENTFAILED2    0x19
+#define ERROR_MEASUREMENTFAILED3    0x1A
+#define ERROR_MEASUREMENTFAILED4    0x1B
+#define ERROR_MEASUREMENTFAILED5    0x1C
+#define ERROR_MEASUREMENTFAILED6    0x1D
+#define ERROR_TIMEROVERFLOW         0x1E
+#define ERROR_BAUDRATEINVALID       0x20
+#define ERROR_PARAMETERINVALID      0x21
+#define ERROR_MEASUREMENTFAILED7    0x23
+
+        // Error modes (SetErrorMode)
+#define ERRORMODE_IGNORE                    0x0000
+#define ERRORMODE_INCSAMPLECNT              0x0001
+#define ERRORMODE_INCSAMPLECNT_SENDERROR    0x0002
+#define ERRORMODE_SENDERROR_GOTOCONFIG      0x0003
+
+        // Configuration message defines
+#define CONF_MASTERDID              0
+#define CONF_PERIOD                 4
+#define CONF_OUTPUTSKIPFACTOR       6
+#define CONF_SYNCIN_MODE            8
+#define CONF_SYNCIN_SKIPFACTOR      10
+#define CONF_SYNCIN_OFFSET          12
+#define CONF_DATE                   16
+#define CONF_TIME                   24
+#define CONF_NUMDEVICES             96
+        // Configuration sensor block properties
+#define CONF_DID                    98
+#define CONF_DATALENGTH             102
+#define CONF_OUTPUTMODE             104
+#define CONF_OUTPUTSETTINGS         106
+#define CONF_BLOCKLEN               20
+        // To calculate the offset in data field for output mode of sensor #2 use
+        //      CONF_OUTPUTMODE + 1*CONF_BLOCKLEN
+#define CONF_MASTERDIDLEN           4
+#define CONF_PERIODLEN              2
+#define CONF_OUTPUTSKIPFACTORLEN    2
+#define CONF_SYNCIN_MODELEN         2
+#define CONF_SYNCIN_SKIPFACTORLEN   2
+#define CONF_SYNCIN_OFFSETLEN       4
+#define CONF_DATELEN                8
+#define CONF_TIMELEN                8
+#define CONF_RESERVED_CLIENTLEN     32
+#define CONF_RESERVED_HOSTLEN       32
+#define CONF_NUMDEVICESLEN          2
+        // Configuration sensor block properties
+#define CONF_DIDLEN                 4
+#define CONF_DATALENGTHLEN          2
+#define CONF_OUTPUTMODELEN          2
+#define CONF_OUTPUTSETTINGSLEN      4
+
+        // Clock frequency for offset & pulse width
+#define SYNC_CLOCKFREQ              29.4912e6
+
+        // SyncIn params
+#define PARAM_SYNCIN_MODE           (const unsigned char)0x00
+#define PARAM_SYNCIN_SKIPFACTOR     (const unsigned char)0x01
+#define PARAM_SYNCIN_OFFSET         (const unsigned char)0x02
+
+        // SyncIn mode
+#define SYNCIN_DISABLED             0x0000
+#define SYNCIN_EDGE_RISING          0x0001
+#define SYNCIN_EDGE_FALLING         0x0002
+#define SYNCIN_EDGE_BOTH            0x0003
+#define SYNCIN_TYPE_SENDLASTDATA    0x0004
+#define SYNCIN_TYPE_DOSAMPLING      0x0000
+#define SYNCIN_EDGE_MASK            0x0003
+#define SYNCIN_TYPE_MASK            0x000C
+
+        // SyncOut params
+#define PARAM_SYNCOUT_MODE          (const unsigned char)0x00
+#define PARAM_SYNCOUT_SKIPFACTOR    (const unsigned char)0x01
+#define PARAM_SYNCOUT_OFFSET        (const unsigned char)0x02
+#define PARAM_SYNCOUT_PULSEWIDTH    (const unsigned char)0x03
+
+        // SyncOut mode
+#define SYNCOUT_DISABLED        0x0000
+#define SYNCOUT_TYPE_TOGGLE     0x0001
+#define SYNCOUT_TYPE_PULSE      0x0002
+#define SYNCOUT_POL_NEG         0x0000
+#define SYNCOUT_POL_POS         0x0010
+#define SYNCOUT_TYPE_MASK       0x000F
+#define SYNCOUT_POL_MASK        0x0010
+
+        // Sample frequencies (SetPeriod)
+#define PERIOD_10HZ             0x2D00
+#define PERIOD_12HZ             0x2580
+#define PERIOD_15HZ             0x1E00
+#define PERIOD_16HZ             0x1C20
+#define PERIOD_18HZ             0x1900
+#define PERIOD_20HZ             0x1680
+#define PERIOD_24HZ             0x12C0
+#define PERIOD_25HZ             0x1200
+#define PERIOD_30HZ             0x0F00
+#define PERIOD_32HZ             0x0E10
+#define PERIOD_36HZ             0x0C80
+#define PERIOD_40HZ             0x0B40
+#define PERIOD_45HZ             0x0A00
+#define PERIOD_48HZ             0x0960
+#define PERIOD_50HZ             0x0900
+#define PERIOD_60HZ             0x0780
+#define PERIOD_64HZ             0x0708
+#define PERIOD_72HZ             0x0640
+#define PERIOD_75HZ             0x0600
+#define PERIOD_80HZ             0x05A0
+#define PERIOD_90HZ             0x0500
+#define PERIOD_96HZ             0x04B0
+#define PERIOD_100HZ            0x0480
+#define PERIOD_120HZ            0x03C0
+#define PERIOD_128HZ            0x0384
+#define PERIOD_144HZ            0x0320
+#define PERIOD_150HZ            0x0300
+#define PERIOD_160HZ            0x02D0
+#define PERIOD_180HZ            0x0280
+#define PERIOD_192HZ            0x0258
+#define PERIOD_200HZ            0x0240
+#define PERIOD_225HZ            0x0200
+#define PERIOD_240HZ            0x01E0
+#define PERIOD_256HZ            0x01C2
+#define PERIOD_288HZ            0x0190
+#define PERIOD_300HZ            0x0180
+#define PERIOD_320HZ            0x0168
+#define PERIOD_360HZ            0x0140
+#define PERIOD_384HZ            0x012C
+#define PERIOD_400HZ            0x0120
+#define PERIOD_450HZ            0x0100
+#define PERIOD_480HZ            0x00F0
+#define PERIOD_512HZ            0x00E1
+
+        // OutputModes
+#define OUTPUTMODE_MT9              0x8000
+#define OUTPUTMODE_XM               0x0000
+#define OUTPUTMODE_RAW              0x4000
+#define OUTPUTMODE_TEMP             0x0001
+#define OUTPUTMODE_CALIB            0x0002
+#define OUTPUTMODE_ORIENT           0x0004
+
+        // OutputSettings
+#define OUTPUTSETTINGS_XM                       0x00000001
+#define OUTPUTSETTINGS_TIMESTAMP_NONE           0x00000000
+#define OUTPUTSETTINGS_TIMESTAMP_SAMPLECNT      0x00000001
+#define OUTPUTSETTINGS_ORIENTMODE_QUATERNION    0x00000000
+#define OUTPUTSETTINGS_ORIENTMODE_EULER         0x00000004
+#define OUTPUTSETTINGS_ORIENTMODE_MATRIX        0x00000008
+#define OUTPUTSETTINGS_CALIBMODE_ACCGYRMAG      0x00000000
+#define OUTPUTSETTINGS_CALIBMODE_ACC            0x00000060
+#define OUTPUTSETTINGS_CALIBMODE_ACCGYR         0x00000040
+#define OUTPUTSETTINGS_CALIBMODE_ACCMAG         0x00000020
+#define OUTPUTSETTINGS_CALIBMODE_GYR            0x00000050
+#define OUTPUTSETTINGS_CALIBMODE_GYRMAG         0x00000010
+#define OUTPUTSETTINGS_CALIBMODE_MAG            0x00000030
+#define OUTPUTSETTINGS_DATAFORMAT_FLOAT         0x00000000
+#define OUTPUTSETTINGS_DATAFORMAT_F1220         0x00000100
+#define OUTPUTSETTINGS_TIMESTAMP_MASK           0x00000003
+#define OUTPUTSETTINGS_ORIENTMODE_MASK          0x0000000C
+#define OUTPUTSETTINGS_CALIBMODE_ACC_MASK       0x00000010
+#define OUTPUTSETTINGS_CALIBMODE_GYR_MASK       0x00000020
+#define OUTPUTSETTINGS_CALIBMODE_MAG_MASK       0x00000040
+#define OUTPUTSETTINGS_CALIBMODE_MASK           0x00000070
+#define OUTPUTSETTINGS_DATAFORMAT_MASK          0x00000300
+
+        // Extended Output Modes
+#define EXTOUTPUTMODE_DISABLED          0x0000
+#define EXTOUTPUTMODE_EULER             0x0001
+
+        // Factory Output Mode
+#define FACTORYOUTPUTMODE_DISABLE       0x0000
+#define FACTORYOUTPUTMODE_DEFAULT       0x0001
+#define FACTORYOUTPUTMODE_CUSTOM        0x0002
+
+        // Initial tracking mode (SetInitTrackMode)
+#define INITTRACKMODE_DISABLED      0x0000
+#define INITTRACKMODE_ENABLED       0x0001
+
+        // Filter settings params
+#define PARAM_FILTER_GAIN           (const unsigned char)0x00
+#define PARAM_FILTER_RHO            (const unsigned char)0x01
+#define DONOTSTORE                  0x00
+#define STORE                       0x01
+
+        // AMDSetting (SetAMD)
+#define AMDSETTING_DISABLED         0x0000
+#define AMDSETTING_ENABLED          0x0001
+
+        // Reset orientation message type
+#define RESETORIENTATION_STORE      0
+#define RESETORIENTATION_HEADING    1
+#define RESETORIENTATION_GLOBAL     2
+#define RESETORIENTATION_OBJECT     3
+#define RESETORIENTATION_ALIGN      4
+
+        // Send raw string mode
+#define SENDRAWSTRING_INIT          0
+#define SENDRAWSTRING_DEFAULT       1
+#define SENDRAWSTRING_SEND          2
+
+        // Timeouts
+#define TO_DEFAULT                  500
+#define TO_INIT                     250
+#define TO_RETRY                    50
+
+        // openPort baudrates
 #ifdef WIN32
-#define PBR_9600					CBR_9600
-#define PBR_14K4					CBR_14400
-#define PBR_19K2					CBR_19200
-#define PBR_28K8					28800
-#define PBR_38K4					CBR_38400
-#define PBR_57K6					CBR_57600
-#define PBR_76K8					76800
-#define PBR_115K2					CBR_115200
-#define PBR_230K4					230400
-#define PBR_460K8					460800
-#define PBR_921K6					921600
+#define PBR_9600                    CBR_9600
+#define PBR_14K4                    CBR_14400
+#define PBR_19K2                    CBR_19200
+#define PBR_28K8                    28800
+#define PBR_38K4                    CBR_38400
+#define PBR_57K6                    CBR_57600
+#define PBR_76K8                    76800
+#define PBR_115K2                   CBR_115200
+#define PBR_230K4                   230400
+#define PBR_460K8                   460800
+#define PBR_921K6                   921600
 #else
-#define PBR_9600					B9600
-#define PBR_14K4					B14400
-#define PBR_19K2					B19200
-#define PBR_28K8					B28800
-#define PBR_38K4					B38400
-#define PBR_57K6					B57600
-#define PBR_76K8					B76800
-#define PBR_115K2					B115200
-#define PBR_230K4					B230400
-#define PBR_460K8					B460800
-#define PBR_921K6					B921600
+#define PBR_9600                    B9600
+#define PBR_14K4                    B14400
+#define PBR_19K2                    B19200
+#define PBR_28K8                    B28800
+#define PBR_38K4                    B38400
+#define PBR_57K6                    B57600
+#define PBR_76K8                    B76800
+#define PBR_115K2                   B115200
+#define PBR_230K4                   B230400
+#define PBR_460K8                   B460800
+#define PBR_921K6                   B921600
 #endif
 
-// setFilePos defines
+        // setFilePos defines
 #ifdef WIN32
-#define FILEPOS_BEGIN				FILE_BEGIN
-#define FILEPOS_CURRENT				FILE_CURRENT
-#define FILEPOS_END					FILE_END
+#define FILEPOS_BEGIN               FILE_BEGIN
+#define FILEPOS_CURRENT             FILE_CURRENT
+#define FILEPOS_END                 FILE_END
 #else
-#define FILEPOS_BEGIN				SEEK_SET
-#define FILEPOS_CURRENT				SEEK_CUR
-#define FILEPOS_END					SEEK_END
+#define FILEPOS_BEGIN               SEEK_SET
+#define FILEPOS_CURRENT             SEEK_CUR
+#define FILEPOS_END                 SEEK_END
 #endif
 
-// Return values
-#define MTRV_OK						0	// Operation successful
-#define MTRV_NOTSUCCESSFUL			1	// General no success return value
-#define MTRV_TIMEOUT				2	// Operation aborted because of a timeout
-#define MTRV_TIMEOUTNODATA			3	// Operation aborted because of no data read
-#define MTRV_CHECKSUMFAULT			4	// Checksum fault occured
-#define MTRV_NODATA					5	// No data is received
-#define MTRV_RECVERRORMSG			6	// A error message is received
-#define MTRV_OUTOFMEMORY			7	// No internal memory available
-#define MTRV_UNKNOWDATA				8	// An invalid message is read
-#define MTRV_INVALIDTIMEOUT			9	// An invalid value is used to set the timeout
-#define MTRV_UNEXPECTEDMSG			10	// Unexpected message received (e.g. no acknowledge message received)
-#define MTRV_INPUTCANNOTBEOPENED	11	// The specified file / serial port can not be opened
-#define MTRV_ANINPUTALREADYOPEN		12	// File and serial port can not be opened at same time
-#define MTRV_ENDOFFILE				13	// End of file is reached
-#define MTRV_NOINPUTINITIALIZED		14	// No file or serial port opened for reading/writing
-#define MTRV_NOVALIDMODESPECIFIED	15	// No valid outputmode or outputsettings are specified (use 
-// mtGetDeviceMode or mtSetMode)
-#define MTRV_INVALIDVALUESPEC		16	// Value specifier does not match value type or not available in data
-#define MTRV_INVALIDFORFILEINPUT	17	// Function is not valid for file based interfaces
-
-		class CXsensMTiModule
-		{
-			public:
-			CXsensMTiModule();
-			virtual ~CXsensMTiModule();
-
-			// Low level general functions
-			clock_t clockms();
-
-			// Low level COM port / file functions
-			short openPort(const int portNumber, const unsigned long baudrate = PBR_115K2, const unsigned long inqueueSize = 4096, const unsigned long outqueueSize = 1024);
-			short openPort(const char *portName, const unsigned long baudrate = PBR_115K2, const unsigned long inqueueSize = 4096, const unsigned long outqueueSize = 1024);
-			short openFile(const char *fileName, bool createAlways = false);
-			bool isPortOpen();
-			bool isFileOpen();
-			int readData(unsigned char* msgBuffer, const int nBytesToRead);
-			int writeData(const unsigned char* msgBuffer, const int nBytesToWrite);
-			void flush();
-			void escape(unsigned long function);
-			void setPortQueueSize(const unsigned long inqueueSize = 4096, const unsigned long outqueueSize = 1024);
-			short setFilePos(long relPos, unsigned long moveMethod = FILEPOS_BEGIN);
-			short getFileSize(unsigned long &fileSize);
-			short close();
-
-			// Read & write message functions
-			short readMessage(unsigned char &mid, unsigned char data[], short &dataLen, unsigned char *bid = NULL);
-			short readDataMessage(unsigned char data[], short &dataLen);
-			short readMessageRaw(unsigned char *msgBuffer, short *msgBufferLength);
-			short writeMessage(const unsigned char mid, const unsigned long dataValue = 0, const unsigned char dataValueLen = 0, const unsigned char bid = BID_MASTER);
-			short writeMessage(const unsigned char mid, const unsigned char data[], const unsigned short &dataLen, const unsigned char bid = BID_MASTER);
-			short waitForMessage(const unsigned char mid, unsigned char data[] = NULL, short *dataLen = NULL, unsigned char *bid = NULL);
-
-			// Request & set setting functions
-			short reqSetting(const unsigned char mid, unsigned long &value, const unsigned char bid = BID_MASTER);
-			short reqSetting(const unsigned char mid, const unsigned char param, unsigned long &value, const unsigned char bid = BID_MASTER);
-			short reqSetting(const unsigned char mid, float &value, const unsigned char bid = BID_MASTER);
-			short reqSetting(const unsigned char mid, const unsigned char param, float &value, const unsigned char bid = BID_MASTER);
-			short reqSetting(const unsigned char mid, unsigned char data[], short &dataLen, const unsigned char bid = BID_MASTER);
-			short reqSetting(const unsigned char mid, unsigned char dataIn[], short dataInLen, unsigned char dataOut[], short &dataOutLen, const unsigned char bid = BID_MASTER);
-			short reqSetting(const unsigned char mid, const unsigned char param, unsigned char data[], short &dataLen, const unsigned char bid = BID_MASTER);
-			short setSetting(const unsigned char mid, const unsigned long value, const unsigned short valuelen, const unsigned char bid = BID_MASTER);
-			short setSetting(const unsigned char mid, const unsigned char param, const unsigned long value, const unsigned short valuelen, const unsigned char bid = BID_MASTER);
-			short setSetting(const unsigned char mid, const float value, const unsigned char bid = BID_MASTER);
-			short setSetting(const unsigned char mid, const unsigned char param, const float value, const unsigned char bid = BID_MASTER);
-			short setSetting(const unsigned char mid, const unsigned char param, const float value, const bool store, const unsigned char bid = BID_MASTER);
-			// Data-related functions
-			short getDeviceMode(unsigned short *numDevices = NULL);
-			short setDeviceMode(unsigned long OutputMode, unsigned long OutputSettings, const unsigned char bid = BID_MASTER);
-			short getMode(unsigned long &OutputMode, unsigned long &OutputSettings, unsigned short &dataLength, const unsigned char bid = BID_MASTER);
-			short setMode(unsigned long OutputMode, unsigned long OutputSettings, const unsigned char bid = BID_MASTER);
-			short getValue(const unsigned long valueSpec, unsigned short &value, const unsigned char data[], const unsigned char bid = BID_MT);
-			short getValue(const unsigned long valueSpec, unsigned short value[], const unsigned char data[], const unsigned char bid = BID_MT);
-			short getValue(const unsigned long valueSpec, float value[], const unsigned char data[], const unsigned char bid = BID_MT);
-
-			// Generic MTComm functions
-			short getLastDeviceError();
-			short getLastRetVal();
-			short setTimeOut(short timeOutMs);
-			static void swapEndian(const unsigned char input[], unsigned char output[], const int length);
-			void calcChecksum(unsigned char *msgBuffer, const int msgBufferLength);
-			bool checkChecksum(const unsigned char *msgBuffer, const int msgBufferLength);
-			protected:
-			// member variables
+        // Return values
+#define MTRV_OK                     0   // Operation successful
+#define MTRV_NOTSUCCESSFUL          1   // General no success return value
+#define MTRV_TIMEOUT                2   // Operation aborted because of a timeout
+#define MTRV_TIMEOUTNODATA          3   // Operation aborted because of no data read
+#define MTRV_CHECKSUMFAULT          4   // Checksum fault occured
+#define MTRV_NODATA                 5   // No data is received
+#define MTRV_RECVERRORMSG           6   // A error message is received
+#define MTRV_OUTOFMEMORY            7   // No internal memory available
+#define MTRV_UNKNOWDATA             8   // An invalid message is read
+#define MTRV_INVALIDTIMEOUT         9   // An invalid value is used to set the timeout
+#define MTRV_UNEXPECTEDMSG          10  // Unexpected message received (e.g. no acknowledge message received)
+#define MTRV_INPUTCANNOTBEOPENED    11  // The specified file / serial port can not be opened
+#define MTRV_ANINPUTALREADYOPEN     12  // File and serial port can not be opened at same time
+#define MTRV_ENDOFFILE              13  // End of file is reached
+#define MTRV_NOINPUTINITIALIZED     14  // No file or serial port opened for reading/writing
+#define MTRV_NOVALIDMODESPECIFIED   15  // No valid outputmode or outputsettings are specified (use 
+        // mtGetDeviceMode or mtSetMode)
+#define MTRV_INVALIDVALUESPEC       16  // Value specifier does not match value type or not available in data
+#define MTRV_INVALIDFORFILEINPUT    17  // Function is not valid for file based interfaces
+
+        class CXsensMTiModule
+        {
+        public:
+            CXsensMTiModule();
+            virtual ~CXsensMTiModule();
+
+            // Low level general functions
+            clock_t clockms();
+
+            // Low level COM port / file functions
+            short openPort(const int portNumber, const unsigned long baudrate = PBR_115K2, const unsigned long inqueueSize = 4096, const unsigned long outqueueSize = 1024);
+            short openPort(const char* portName, const unsigned long baudrate = PBR_115K2, const unsigned long inqueueSize = 4096, const unsigned long outqueueSize = 1024);
+            short openFile(const char* fileName, bool createAlways = false);
+            bool isPortOpen();
+            bool isFileOpen();
+            int readData(unsigned char* msgBuffer, const int nBytesToRead);
+            int writeData(const unsigned char* msgBuffer, const int nBytesToWrite);
+            void flush();
+            void escape(unsigned long function);
+            void setPortQueueSize(const unsigned long inqueueSize = 4096, const unsigned long outqueueSize = 1024);
+            short setFilePos(long relPos, unsigned long moveMethod = FILEPOS_BEGIN);
+            short getFileSize(unsigned long& fileSize);
+            short close();
+
+            // Read & write message functions
+            short readMessage(unsigned char& mid, unsigned char data[], short& dataLen, unsigned char* bid = NULL);
+            short readDataMessage(unsigned char data[], short& dataLen);
+            short readMessageRaw(unsigned char* msgBuffer, short* msgBufferLength);
+            short writeMessage(const unsigned char mid, const unsigned long dataValue = 0, const unsigned char dataValueLen = 0, const unsigned char bid = BID_MASTER);
+            short writeMessage(const unsigned char mid, const unsigned char data[], const unsigned short& dataLen, const unsigned char bid = BID_MASTER);
+            short waitForMessage(const unsigned char mid, unsigned char data[] = NULL, short* dataLen = NULL, unsigned char* bid = NULL);
+
+            // Request & set setting functions
+            short reqSetting(const unsigned char mid, unsigned long& value, const unsigned char bid = BID_MASTER);
+            short reqSetting(const unsigned char mid, const unsigned char param, unsigned long& value, const unsigned char bid = BID_MASTER);
+            short reqSetting(const unsigned char mid, float& value, const unsigned char bid = BID_MASTER);
+            short reqSetting(const unsigned char mid, const unsigned char param, float& value, const unsigned char bid = BID_MASTER);
+            short reqSetting(const unsigned char mid, unsigned char data[], short& dataLen, const unsigned char bid = BID_MASTER);
+            short reqSetting(const unsigned char mid, unsigned char dataIn[], short dataInLen, unsigned char dataOut[], short& dataOutLen, const unsigned char bid = BID_MASTER);
+            short reqSetting(const unsigned char mid, const unsigned char param, unsigned char data[], short& dataLen, const unsigned char bid = BID_MASTER);
+            short setSetting(const unsigned char mid, const unsigned long value, const unsigned short valuelen, const unsigned char bid = BID_MASTER);
+            short setSetting(const unsigned char mid, const unsigned char param, const unsigned long value, const unsigned short valuelen, const unsigned char bid = BID_MASTER);
+            short setSetting(const unsigned char mid, const float value, const unsigned char bid = BID_MASTER);
+            short setSetting(const unsigned char mid, const unsigned char param, const float value, const unsigned char bid = BID_MASTER);
+            short setSetting(const unsigned char mid, const unsigned char param, const float value, const bool store, const unsigned char bid = BID_MASTER);
+            // Data-related functions
+            short getDeviceMode(unsigned short* numDevices = NULL);
+            short setDeviceMode(unsigned long OutputMode, unsigned long OutputSettings, const unsigned char bid = BID_MASTER);
+            short getMode(unsigned long& OutputMode, unsigned long& OutputSettings, unsigned short& dataLength, const unsigned char bid = BID_MASTER);
+            short setMode(unsigned long OutputMode, unsigned long OutputSettings, const unsigned char bid = BID_MASTER);
+            short getValue(const unsigned long valueSpec, unsigned short& value, const unsigned char data[], const unsigned char bid = BID_MT);
+            short getValue(const unsigned long valueSpec, unsigned short value[], const unsigned char data[], const unsigned char bid = BID_MT);
+            short getValue(const unsigned long valueSpec, float value[], const unsigned char data[], const unsigned char bid = BID_MT);
+
+            // Generic MTComm functions
+            short getLastDeviceError();
+            short getLastRetVal();
+            short setTimeOut(short timeOutMs);
+            static void swapEndian(const unsigned char input[], unsigned char output[], const int length);
+            void calcChecksum(unsigned char* msgBuffer, const int msgBufferLength);
+            bool checkChecksum(const unsigned char* msgBuffer, const int msgBufferLength);
+        protected:
+            // member variables
 #ifdef WIN32
-			HANDLE m_handle;
+            HANDLE m_handle;
 #else
-			int m_handle;
+            int m_handle;
 #endif
-			bool m_portOpen;
-			bool m_fileOpen;
-			short m_deviceError;
-			short m_retVal;
-			short m_timeOut;
-			clock_t m_clkEnd;
-
-			// OutputMode, OutputSettings & DataLength for connected devices + 1 for master
-			unsigned long m_storedOutputMode[MAXDEVICES + 1];
-			unsigned long m_storedOutputSettings[MAXDEVICES + 1];
-			unsigned long m_storedDataLength[MAXDEVICES + 1];
-
-			// Temporary buffer for excess bytes read in ReadMessageRaw
-			unsigned char m_tempBuffer[MAXMSGLEN ];
-			int m_nTempBufferLen;
-
-			private:
-		};
-	}
+            bool m_portOpen;
+            bool m_fileOpen;
+            short m_deviceError;
+            short m_retVal;
+            short m_timeOut;
+            clock_t m_clkEnd;
+
+            // OutputMode, OutputSettings & DataLength for connected devices + 1 for master
+            unsigned long m_storedOutputMode[MAXDEVICES + 1];
+            unsigned long m_storedOutputSettings[MAXDEVICES + 1];
+            unsigned long m_storedDataLength[MAXDEVICES + 1];
+
+            // Temporary buffer for excess bytes read in ReadMessageRaw
+            unsigned char m_tempBuffer[MAXMSGLEN ];
+            int m_nTempBufferLen;
+
+        private:
+        };
+    }
 }
 
 #endif
diff --git a/source/RobotAPI/libraries/drivers/XsensIMU/XsensIMU.cpp b/source/RobotAPI/libraries/drivers/XsensIMU/XsensIMU.cpp
index 2857dca6918e593c1df02fa28bf5e38630d90d75..6b90025cab677fdd40a37d60f249babbfa37b094 100644
--- a/source/RobotAPI/libraries/drivers/XsensIMU/XsensIMU.cpp
+++ b/source/RobotAPI/libraries/drivers/XsensIMU/XsensIMU.cpp
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    RobotAPI::ArmarXObjects::XsensIMU
  * @author     Markus Grotz ( markus-grotz at web dot de )
  * @date       2015
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -36,37 +35,40 @@ PropertyDefinitionsPtr XsensIMU::createPropertyDefinitions()
 
 void XsensIMU::frameAcquisitionTaskLoop()
 {
-    while(!sensorTask->isStopped()) {
+    while (!sensorTask->isStopped())
+    {
 
-        while(HasPendingEvents()) {
+        while (HasPendingEvents())
+        {
 
-        ProcessPendingEvent();
+            ProcessPendingEvent();
 
-        TimestampVariantPtr now = TimestampVariant::nowPtr();
-        IMUData data;
+            TimestampVariantPtr now = TimestampVariant::nowPtr();
+            IMUData data;
 
-        data.acceleration.push_back(m_Accelaration[0]);
-        data.acceleration.push_back(m_Accelaration[1]);
-        data.acceleration.push_back(m_Accelaration[2]);
+            data.acceleration.push_back(m_Accelaration[0]);
+            data.acceleration.push_back(m_Accelaration[1]);
+            data.acceleration.push_back(m_Accelaration[2]);
 
-        data.gyroscopeRotation.push_back(m_GyroscopeRotation[0]);
-        data.gyroscopeRotation.push_back(m_GyroscopeRotation[1]);
-        data.gyroscopeRotation.push_back(m_GyroscopeRotation[2]);
+            data.gyroscopeRotation.push_back(m_GyroscopeRotation[0]);
+            data.gyroscopeRotation.push_back(m_GyroscopeRotation[1]);
+            data.gyroscopeRotation.push_back(m_GyroscopeRotation[2]);
 
 
-        data.magneticRotation.push_back(m_MagneticRotation[0]);
-        data.magneticRotation.push_back(m_MagneticRotation[1]);
-        data.magneticRotation.push_back(m_MagneticRotation[2]);
+            data.magneticRotation.push_back(m_MagneticRotation[0]);
+            data.magneticRotation.push_back(m_MagneticRotation[1]);
+            data.magneticRotation.push_back(m_MagneticRotation[2]);
 
 
-        data.orientationQuaternion.push_back(m_OrientationQuaternion[0]);
-        data.orientationQuaternion.push_back(m_OrientationQuaternion[1]);
-        data.orientationQuaternion.push_back(m_OrientationQuaternion[2]);
-        data.orientationQuaternion.push_back(m_OrientationQuaternion[3]);
+            data.orientationQuaternion.push_back(m_OrientationQuaternion[0]);
+            data.orientationQuaternion.push_back(m_OrientationQuaternion[1]);
+            data.orientationQuaternion.push_back(m_OrientationQuaternion[2]);
+            data.orientationQuaternion.push_back(m_OrientationQuaternion[3]);
 
-        IMUTopicPrx->reportSensorValues("device", "name", data, now);
+            IMUTopicPrx->reportSensorValues("device", "name", data, now);
 
         }
+
         usleep(10000);
     }
 }
diff --git a/source/RobotAPI/libraries/drivers/XsensIMU/XsensIMU.h b/source/RobotAPI/libraries/drivers/XsensIMU/XsensIMU.h
index 206796a20064c0fded18f4312c34ee710d860fcf..abc5540be19d3b43f4044653f7e148d66a73f929 100644
--- a/source/RobotAPI/libraries/drivers/XsensIMU/XsensIMU.h
+++ b/source/RobotAPI/libraries/drivers/XsensIMU/XsensIMU.h
@@ -2,14 +2,13 @@
  * This file is part of ArmarX.
  *
  * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as
- * published by the Free Software Foundation; either version 2 of
- * the License, or (at your option) any later version.
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU Lesser General Public License for more details.
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
  * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
  * @package    RobotAPI::ArmarXObjects::XsensIMU
  * @author     Markus Grotz ( markus-grotz at web dot de )
  * @date       2015
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -25,9 +24,9 @@
 #define _ARMARX_COMPONENT_RobotAPI_XsensIMU_H
 
 
-#include <Core/core/Component.h>
-#include <Core/core/services/tasks/RunningTask.h>
-#include <Core/observers/variant/TimestampVariant.h>
+#include <ArmarXCore/core/Component.h>
+#include <ArmarXCore/core/services/tasks/RunningTask.h>
+#include <ArmarXCore/observers/variant/TimestampVariant.h>
 
 
 #include <RobotAPI/components/units/InertialMeasurementUnit.h>
@@ -96,7 +95,7 @@ namespace armarx
         void onExitIMU();
 
 
-     private:
+    private:
 
         RunningTask<XsensIMU>::pointer_type sensorTask;
         IMU::CIMUDevice IMUDevice;
diff --git a/source/RobotAPI/libraries/widgets/CMakeLists.txt b/source/RobotAPI/libraries/widgets/CMakeLists.txt
new file mode 100644
index 0000000000000000000000000000000000000000..1b64636d881dffc647e0958140a32f17871a1cf0
--- /dev/null
+++ b/source/RobotAPI/libraries/widgets/CMakeLists.txt
@@ -0,0 +1,55 @@
+armarx_set_target("RobotAPI Library: RobotAPIWidgets")
+
+find_package(Qt4 COMPONENTS QtCore QtGui QtDesigner)
+armarx_build_if(QT_FOUND "Qt not available")
+find_package(Coin3D REQUIRED)
+armarx_build_if(Coin3D_FOUND "Coin3D not available")
+find_package(SoQt REQUIRED)
+armarx_build_if(SOQT_FOUND "SoQt not available")
+find_package(jsoncpp QUIET)
+armarx_build_if(jsoncpp_FOUND "jsoncpp not available")
+find_package(Simox QUIET)
+armarx_build_if(Simox_FOUND "Simox-VirtualRobot not available")
+
+include(${QT_USE_FILE})
+include_directories(${Eigen3_INCLUDE_DIR})
+include_directories(
+        ${Coin3D_INCLUDE_DIRS}
+        ${SoQt_INCLUDE_DIRS}
+        ${jsoncpp_INCLUDE_DIR}
+        ${Simox_INCLUDE_DIRS})
+
+
+set(LIB_NAME       RobotAPIWidgets)
+
+
+
+set(LIBS ArmarXCore RobotAPICore ${QT_LIBRARIES})
+
+set(LIB_FILES
+    DebugLayerControlWidget.cpp
+)
+
+set(LIB_HEADERS
+    DebugLayerControlWidget.h
+)
+
+set(GUI_UIS
+    DebugLayerControlWidget.ui
+)
+
+# and finally a resource file
+#SET( QT_RESOURCES
+#   armarxicons.qrc
+#)
+#QT4_ADD_RESOURCES( QT_RC_SRCS ${QT_RESOURCES} )
+
+qt4_wrap_cpp(LIB_FILES
+    DebugLayerControlWidget.h
+    )
+qt4_wrap_ui(UI_HEADER ${GUI_UIS})
+
+list(APPEND LIB_HEADERS ${UI_HEADER})
+#list(APPEND LIB_FILES ${QT_RC_SRCS})
+
+armarx_add_library("${LIB_NAME}"  "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
diff --git a/source/RobotAPI/libraries/widgets/DebugLayerControlWidget.cpp b/source/RobotAPI/libraries/widgets/DebugLayerControlWidget.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..8d59a733879f76dd088a93e9b1e76836efa405c2
--- /dev/null
+++ b/source/RobotAPI/libraries/widgets/DebugLayerControlWidget.cpp
@@ -0,0 +1,107 @@
+#include "DebugLayerControlWidget.h"
+#include <RobotAPI/libraries/widgets/ui_DebugLayerControlWidget.h>
+
+#define UPDATE_INTERVAL 1.0 // update every second
+
+DebugLayerControlWidget::DebugLayerControlWidget(QWidget *parent) :
+    QWidget(parent),
+    ui(new Ui::DebugLayerControlWidget)
+{
+    entityDrawer = NULL;
+    ui->setupUi(this);
+
+    //init timer
+    SoSensorManager* sensor_mgr = SoDB::getSensorManager();
+    timerSensor = new SoTimerSensor(onTimer, this);
+    timerSensor->setInterval(SbTime(UPDATE_INTERVAL));
+    sensor_mgr->insertTimerSensor(timerSensor);
+
+    //connect signal mapper
+    QObject::connect(&layerSignalMapperVisible,SIGNAL(mapped(QString)),this,SLOT(layerToggleVisibility(QString)));
+    QObject::connect(&layerSignalMapperRemove,SIGNAL(mapped(QString)),this,SLOT(layerRemove(QString)));
+}
+
+DebugLayerControlWidget::~DebugLayerControlWidget()
+{
+    //destroy timer
+    if (timerSensor)
+    {
+        SoSensorManager* sensor_mgr = SoDB::getSensorManager();
+        sensor_mgr->removeTimerSensor(timerSensor);
+    }
+    delete ui;
+}
+
+void DebugLayerControlWidget::setEntityDrawer(DebugDrawerComponentPtr entityDrawer)
+{
+    this->entityDrawer = entityDrawer;
+}
+
+void DebugLayerControlWidget::updateLayers()
+{
+    //ui.layerTable->clear();
+    if (entityDrawer) {
+        armarx::LayerInformationSequence layers = entityDrawer->layerInformation();
+        ui->layerTable->setRowCount(layers.size());
+
+        for (std::size_t i=0;i<layers.size();++i)
+        {
+            const auto& layer=layers.at(i);
+            QString name=QString::fromStdString(layer.layerName);
+
+            //store visibility
+            layerVisibility[layer.layerName]=layer.visible;
+
+            //add name and number of elements
+            ui->layerTable->setItem(i,0,new QTableWidgetItem{name});
+            ui->layerTable->setItem(i,1,new QTableWidgetItem{QString::number(layer.elementCount)});
+
+            //add visibility checkbox
+            std::unique_ptr<QCheckBox> box{new QCheckBox};
+            box->setChecked(layer.visible);
+            layerSignalMapperVisible.setMapping(box.get(),name);
+            QObject::connect(box.get(), SIGNAL(stateChanged(int)), &layerSignalMapperVisible, SLOT(map()));
+            ui->layerTable->setCellWidget(i,2,box.release());
+
+            //add remove button
+            std::unique_ptr<QPushButton> removeB{new QPushButton("remove")};
+            layerSignalMapperRemove.setMapping(removeB.get(),name);
+            QObject::connect(removeB.get(), SIGNAL(clicked()), &layerSignalMapperRemove, SLOT(map()));
+            ui->layerTable->setCellWidget(i, 3, removeB.release());
+        }
+    } else {
+        VR_INFO << "No Debug Drawer" << std::endl;
+    }
+}
+
+void DebugLayerControlWidget::layerToggleVisibility(QString layerName)
+{
+    //VR_INFO << "should toggle: " << layerName.toStdString() << std::endl;
+    auto name = layerName.toStdString();
+    if (layerVisibility.find(name)!=layerVisibility.end())
+    {
+        if (entityDrawer)
+        {
+            entityDrawer->enableLayerVisu(name, !layerVisibility.at(name));
+        }
+    } else
+        VR_INFO << "name not present" << std::endl;
+}
+
+void DebugLayerControlWidget::layerRemove(QString layerName)
+{
+    auto name = layerName.toStdString();
+    VR_INFO << "remove layer: " << name << std::endl;
+
+    if (entityDrawer->hasLayer(name)) {
+        entityDrawer->removeLayer(name);
+    } else
+        VR_INFO << "name not present" << std::endl;
+}
+
+void DebugLayerControlWidget::onTimer(void* data, SoSensor *sensor)
+{
+    DebugLayerControlWidget* controller = static_cast<DebugLayerControlWidget*>(data);
+    if (controller)
+        controller->updateLayers();
+}
diff --git a/source/RobotAPI/libraries/widgets/DebugLayerControlWidget.h b/source/RobotAPI/libraries/widgets/DebugLayerControlWidget.h
new file mode 100644
index 0000000000000000000000000000000000000000..9bc1e4201a9aee717980b25c55e0fa159811771e
--- /dev/null
+++ b/source/RobotAPI/libraries/widgets/DebugLayerControlWidget.h
@@ -0,0 +1,93 @@
+/*
+* This file is part of ArmarX.
+*
+* ArmarX is free software; you can redistribute it and/or modify
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
+*
+* ArmarX is distributed in the hope that it will be useful, but
+* WITHOUT ANY WARRANTY; without even the implied warranty of
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
+*
+* You should have received a copy of the GNU General Public License
+* along with this program. If not, see <http://www.gnu.org/licenses/>.
+*
+* @package    MemoryX::WorkingMemoryGui
+* @author     Dominik Muth
+* @copyright  2015 KIT
+* @license    http://www.gnu.org/licenses/gpl-2.0.txt
+*             GNU General Public License
+
+*/
+
+#ifndef DEBUGLAYERWIDGET_H
+#define DEBUGLAYERWIDGET_H
+
+/* ArmarX headers */
+
+#include <ArmarXCore/core/Component.h>
+#include <RobotAPI/components/DebugDrawer/DebugDrawerComponent.h>
+
+/* QT headers */
+#include <QWidget>
+#include <QCheckBox>
+#include <QSignalMapper>
+#include <QPushButton>
+
+/* STD headers */
+#include <unordered_map>
+
+/* Inventor headers */
+#include <Inventor/sensors/SoTimerSensor.h>
+#include <Inventor/SoDB.h>
+#include <Inventor/Qt/SoQt.h>
+
+/* System headers */
+#include <string>
+
+using namespace armarx;
+
+namespace Ui {
+class DebugLayerControlWidget;
+}
+
+class DebugLayerControlWidget : public QWidget
+{
+    Q_OBJECT
+
+public:
+    DebugLayerControlWidget(QWidget *parent = 0);
+    ~DebugLayerControlWidget();
+    void setEntityDrawer(DebugDrawerComponentPtr entityDrawer);
+
+public slots:
+    void updateLayers();
+
+    void layerToggleVisibility(QString layerName);
+
+protected:
+    DebugDrawerComponentPtr entityDrawer;
+    SoTimerSensor* timerSensor;
+    /**
+     * @brief Maps events to toggle a layer's visibility from checkboxes contained in the table to layerToggleVisibility.
+     */
+    QSignalMapper layerSignalMapperVisible;
+    /**
+     * @brief Maps events to remove a layer.
+     */
+    QSignalMapper layerSignalMapperRemove;
+    /**
+     * @brief Stores whether a layer is currently visible.
+     */
+    std::unordered_map<std::string,bool> layerVisibility;
+
+    static void onTimer(void *data, SoSensor *sensor);
+
+protected slots:
+    void layerRemove(QString layerName);
+private:
+    Ui::DebugLayerControlWidget *ui;
+};
+
+#endif // DEBUGLAYERWIDGET_H
diff --git a/source/RobotAPI/libraries/widgets/DebugLayerControlWidget.ui b/source/RobotAPI/libraries/widgets/DebugLayerControlWidget.ui
new file mode 100644
index 0000000000000000000000000000000000000000..448cdf6afebefce720a80353177509ff142f5c43
--- /dev/null
+++ b/source/RobotAPI/libraries/widgets/DebugLayerControlWidget.ui
@@ -0,0 +1,72 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<ui version="4.0">
+ <class>DebugLayerControlWidget</class>
+ <widget class="QWidget" name="DebugLayerControlWidget">
+  <property name="geometry">
+   <rect>
+    <x>0</x>
+    <y>0</y>
+    <width>447</width>
+    <height>197</height>
+   </rect>
+  </property>
+  <property name="windowTitle">
+   <string>Form</string>
+  </property>
+  <layout class="QGridLayout" name="gridLayout">
+   <item row="0" column="0">
+    <widget class="QGroupBox" name="groupBoxLayer">
+     <property name="title">
+      <string>Visualisation layer</string>
+     </property>
+     <layout class="QGridLayout" name="gridLayout_2">
+      <item row="0" column="0">
+       <widget class="QTableWidget" name="layerTable">
+        <property name="editTriggers">
+         <set>QAbstractItemView::NoEditTriggers</set>
+        </property>
+        <property name="showDropIndicator" stdset="0">
+         <bool>false</bool>
+        </property>
+        <property name="dragDropOverwriteMode">
+         <bool>false</bool>
+        </property>
+        <property name="alternatingRowColors">
+         <bool>true</bool>
+        </property>
+        <property name="selectionMode">
+         <enum>QAbstractItemView::NoSelection</enum>
+        </property>
+        <property name="selectionBehavior">
+         <enum>QAbstractItemView::SelectRows</enum>
+        </property>
+        <column>
+         <property name="text">
+          <string>Name</string>
+         </property>
+        </column>
+        <column>
+         <property name="text">
+          <string>Elements</string>
+         </property>
+        </column>
+        <column>
+         <property name="text">
+          <string>Visible</string>
+         </property>
+        </column>
+        <column>
+         <property name="text">
+          <string/>
+         </property>
+        </column>
+       </widget>
+      </item>
+     </layout>
+    </widget>
+   </item>
+  </layout>
+ </widget>
+ <resources/>
+ <connections/>
+</ui>
diff --git a/source/RobotAPI/statecharts/StatechartProfilesTestGroup/CMakeLists.txt b/source/RobotAPI/statecharts/StatechartProfilesTestGroup/CMakeLists.txt
index 07a53d84ebfbb07ece2b65c832d0f45e4dd58ea1..3605bd699ce4a853e232b6d4b01bff5c410f9321 100644
--- a/source/RobotAPI/statecharts/StatechartProfilesTestGroup/CMakeLists.txt
+++ b/source/RobotAPI/statecharts/StatechartProfilesTestGroup/CMakeLists.txt
@@ -26,7 +26,7 @@ armarx_component_set_name("StatechartProfilesTestGroup")
 
 set(COMPONENT_LIBS
 #   RobotAPIInterfaces RobotAPICore
-    ArmarXInterfaces ArmarXCore ArmarXCoreStatechart ArmarXCoreObservers)
+    ArmarXCoreInterfaces ArmarXCore ArmarXCoreStatechart ArmarXCoreObservers)
 
 # Sources
 
diff --git a/source/RobotAPI/statecharts/StatechartProfilesTestGroup/StatechartProfilesTestGroupRemoteStateOfferer.cpp b/source/RobotAPI/statecharts/StatechartProfilesTestGroup/StatechartProfilesTestGroupRemoteStateOfferer.cpp
index c81db898dd7187b88f4e355c5969f17c06e429db..55462636f80a3e2c8565963cc5e9402c249654ee 100644
--- a/source/RobotAPI/statecharts/StatechartProfilesTestGroup/StatechartProfilesTestGroupRemoteStateOfferer.cpp
+++ b/source/RobotAPI/statecharts/StatechartProfilesTestGroup/StatechartProfilesTestGroupRemoteStateOfferer.cpp
@@ -7,7 +7,7 @@
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
@@ -16,7 +16,7 @@
  * @package    RobotAPI::StatechartProfilesTestGroup::StatechartProfilesTestGroupRemoteStateOfferer
  * @author     Valerij Wittenbeck ( valerij dot wittenbeck at student dot kit dot edu )
  * @date       2015
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
diff --git a/source/RobotAPI/statecharts/StatechartProfilesTestGroup/StatechartProfilesTestGroupRemoteStateOfferer.h b/source/RobotAPI/statecharts/StatechartProfilesTestGroup/StatechartProfilesTestGroupRemoteStateOfferer.h
index 1b93984f8ca05e506ef907c8cbf4478ce1e9d1a5..6965ea51d112b69542941d9facaa84fac9bb6d09 100644
--- a/source/RobotAPI/statecharts/StatechartProfilesTestGroup/StatechartProfilesTestGroupRemoteStateOfferer.h
+++ b/source/RobotAPI/statecharts/StatechartProfilesTestGroup/StatechartProfilesTestGroupRemoteStateOfferer.h
@@ -7,7 +7,7 @@
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
@@ -16,14 +16,14 @@
  * @package    RobotAPI::StatechartProfilesTestGroup
  * @author     Valerij Wittenbeck ( valerij dot wittenbeck at student dot kit dot edu )
  * @date       2015
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 #ifndef _ARMARX_XMLUSERCODE_RobotAPI_StatechartProfilesTestGroup_REMOTESTATEOFFERER_H
 #define _ARMARX_XMLUSERCODE_RobotAPI_StatechartProfilesTestGroup_REMOTESTATEOFFERER_H
 
-#include <Core/statechart/xmlstates/XMLRemoteStateOfferer.h>
+#include <ArmarXCore/statechart/xmlstates/XMLRemoteStateOfferer.h>
 #include "StatechartProfilesTestGroupStatechartContext.generated.h"
 
 namespace armarx
diff --git a/source/RobotAPI/statecharts/StatechartProfilesTestGroup/TestState.cpp b/source/RobotAPI/statecharts/StatechartProfilesTestGroup/TestState.cpp
index 609d625909cf0f82524519c2e79c05c8c96902b3..2fce6241e256a383313569c5e266fe4afbbc2089 100644
--- a/source/RobotAPI/statecharts/StatechartProfilesTestGroup/TestState.cpp
+++ b/source/RobotAPI/statecharts/StatechartProfilesTestGroup/TestState.cpp
@@ -7,7 +7,7 @@
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
@@ -16,7 +16,7 @@
  * @package    RobotAPI::StatechartProfilesTestGroup
  * @author     Valerij Wittenbeck ( valerij dot wittenbeck at student dot kit dot edu )
  * @date       2015
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -59,11 +59,11 @@ void TestState::run()
     // runs in seperate thread, thus can do complex operations
     // should check constantly whether isRunningTaskStopped() returns true
 
-// uncomment this if you need a continous run function. Make sure to use sleep or use blocking wait to reduce cpu load.
-//    while (!isRunningTaskStopped()) // stop run function if returning true
-//    {
-//        // do your calculations
-//    }
+    // uncomment this if you need a continous run function. Make sure to use sleep or use blocking wait to reduce cpu load.
+    //    while (!isRunningTaskStopped()) // stop run function if returning true
+    //    {
+    //        // do your calculations
+    //    }
 
 }
 
diff --git a/source/RobotAPI/statecharts/StatechartProfilesTestGroup/TestState.h b/source/RobotAPI/statecharts/StatechartProfilesTestGroup/TestState.h
index 6a2e87bdf12270ca84fce63547c0ea6155292d04..99a3e281ae9389a08bdd3a8a90fa932de337e8e3 100644
--- a/source/RobotAPI/statecharts/StatechartProfilesTestGroup/TestState.h
+++ b/source/RobotAPI/statecharts/StatechartProfilesTestGroup/TestState.h
@@ -7,7 +7,7 @@
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
@@ -16,7 +16,7 @@
  * @package    RobotAPI::StatechartProfilesTestGroup
  * @author     Valerij Wittenbeck ( valerij dot wittenbeck at student dot kit dot edu )
  * @date       2015
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
diff --git a/source/RobotAPI/statecharts/WeissHapticGroup/CMakeLists.txt b/source/RobotAPI/statecharts/WeissHapticGroup/CMakeLists.txt
index 1bb8a3e825f4e4af96ddd3666d76d9b5a21094fc..b0fea04f1a90ab5dc83cc8dd3c2938bca46b7637 100644
--- a/source/RobotAPI/statecharts/WeissHapticGroup/CMakeLists.txt
+++ b/source/RobotAPI/statecharts/WeissHapticGroup/CMakeLists.txt
@@ -26,7 +26,7 @@ endif()
 
 set(COMPONENT_LIBS
     RobotAPIInterfaces RobotAPICore RobotAPIUnits
-    ArmarXInterfaces ArmarXCore ArmarXCoreStatechart ArmarXCoreObservers)
+    ArmarXCoreInterfaces ArmarXCore ArmarXCoreStatechart ArmarXCoreObservers)
 
 # Sources
 
diff --git a/source/RobotAPI/statecharts/WeissHapticGroup/WeissHapticGroupRemoteStateOfferer.cpp b/source/RobotAPI/statecharts/WeissHapticGroup/WeissHapticGroupRemoteStateOfferer.cpp
index a8f0c6b0e2bb73a32a26da3ba4a23afef190c40c..f0d2820e6bc419494ff8465a88a7f9e6deef6daa 100644
--- a/source/RobotAPI/statecharts/WeissHapticGroup/WeissHapticGroupRemoteStateOfferer.cpp
+++ b/source/RobotAPI/statecharts/WeissHapticGroup/WeissHapticGroupRemoteStateOfferer.cpp
@@ -7,7 +7,7 @@
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
@@ -16,7 +16,7 @@
  * @package    RobotAPI::WeissHapticGroup::WeissHapticGroupRemoteStateOfferer
  * @author     Simon Ottenhaus ( simon dot ottenhaus at kit dot edu )
  * @date       2015
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
diff --git a/source/RobotAPI/statecharts/WeissHapticGroup/WeissHapticGroupRemoteStateOfferer.h b/source/RobotAPI/statecharts/WeissHapticGroup/WeissHapticGroupRemoteStateOfferer.h
index 232ed4f3261a52cfb2ea1d2b6c3d3479a488bc74..bb5cd13a26d5e446db364bee0131b4d240b93634 100644
--- a/source/RobotAPI/statecharts/WeissHapticGroup/WeissHapticGroupRemoteStateOfferer.h
+++ b/source/RobotAPI/statecharts/WeissHapticGroup/WeissHapticGroupRemoteStateOfferer.h
@@ -7,7 +7,7 @@
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
@@ -16,14 +16,14 @@
  * @package    RobotAPI::WeissHapticGroup
  * @author     Simon Ottenhaus ( simon dot ottenhaus at kit dot edu )
  * @date       2015
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
 #ifndef _ARMARX_XMLUSERCODE_RobotAPI_WeissHapticGroup_REMOTESTATEOFFERER_H
 #define _ARMARX_XMLUSERCODE_RobotAPI_WeissHapticGroup_REMOTESTATEOFFERER_H
 
-#include <Core/statechart/xmlstates/XMLRemoteStateOfferer.h>
+#include <ArmarXCore/statechart/xmlstates/XMLRemoteStateOfferer.h>
 #include "WeissHapticGroupStatechartContext.generated.h"
 
 namespace armarx
diff --git a/source/RobotAPI/statecharts/WeissHapticGroup/WeissHapticGroupStatechartContext.generated.h b/source/RobotAPI/statecharts/WeissHapticGroup/WeissHapticGroupStatechartContext.generated.h
index 947ae7ed0391362ec7e483b4003c67748d58e4b3..a9286cbdde6732fe3bff44c5b4bd969176476347 100644
--- a/source/RobotAPI/statecharts/WeissHapticGroup/WeissHapticGroupStatechartContext.generated.h
+++ b/source/RobotAPI/statecharts/WeissHapticGroup/WeissHapticGroupStatechartContext.generated.h
@@ -1,9 +1,9 @@
 #ifndef ARMARX_COMPONENT_ARMARX_WEISSHAPTICGROUP_WEISSHAPTICGROUPSTATECHARTCONTEXT_H
 #define ARMARX_COMPONENT_ARMARX_WEISSHAPTICGROUP_WEISSHAPTICGROUPSTATECHARTCONTEXT_H
 
-#include <Core/core/Component.h>
-#include <Core/core/system/ImportExportComponent.h>
-#include <Core/statechart/StatechartContext.h>
+#include <ArmarXCore/core/Component.h>
+#include <ArmarXCore/core/system/ImportExportComponent.h>
+#include <ArmarXCore/statechart/StatechartContext.h>
 #include <RobotAPI/interface/units/HapticUnit.h>
 #include <RobotAPI/interface/units/WeissHapticUnit.h>
 
@@ -26,11 +26,11 @@ namespace armarx
                     defineOptionalProperty<std::string>("WeissHapticUnitName", "WeissHapticUnit", "Name of the weiss haptic unit that should be used");
                 }
             }; // class PropertyDefinitions
-            
+
         private:
             HapticUnitObserverInterfacePrx hapticObserver;
             WeissHapticUnitInterfacePrx weissHapticUnit;
-            
+
         public:
             std::string getDefaultName() const
             {
@@ -46,8 +46,14 @@ namespace armarx
                 hapticObserver = getProxy<HapticUnitObserverInterfacePrx>(getProperty<std::string>("HapticUnitObserverName").getValue());
                 weissHapticUnit = getProxy<WeissHapticUnitInterfacePrx>(getProperty<std::string>("WeissHapticUnitName").getValue());
             }
-            HapticUnitObserverInterfacePrx getHapticObserver() const { return hapticObserver; }
-            WeissHapticUnitInterfacePrx getWeissHapticUnit() const { return weissHapticUnit; }
+            HapticUnitObserverInterfacePrx getHapticObserver() const
+            {
+                return hapticObserver;
+            }
+            WeissHapticUnitInterfacePrx getWeissHapticUnit() const
+            {
+                return weissHapticUnit;
+            }
             virtual PropertyDefinitionsPtr createPropertyDefinitions()
             {
                 return PropertyDefinitionsPtr(new WeissHapticGroupStatechartContext::PropertyDefinitions(getConfigIdentifier()));
diff --git a/source/RobotAPI/statecharts/WeissHapticGroup/WeissHapticSensorTest.cpp b/source/RobotAPI/statecharts/WeissHapticGroup/WeissHapticSensorTest.cpp
index ac0edd94540c762281d997bea5684cc08bf3fb58..88a2741e8a690e1188f4a728ae1f93092e2d1040 100644
--- a/source/RobotAPI/statecharts/WeissHapticGroup/WeissHapticSensorTest.cpp
+++ b/source/RobotAPI/statecharts/WeissHapticGroup/WeissHapticSensorTest.cpp
@@ -7,7 +7,7 @@
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
@@ -16,7 +16,7 @@
  * @package    RobotAPI::WeissHapticGroup
  * @author     Simon Ottenhaus ( simon dot ottenhaus at kit dot edu )
  * @date       2015
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
@@ -44,14 +44,16 @@ void WeissHapticSensorTest::onEnter()
     HapticUnitObserverInterfacePrx hapticObserver = context->getHapticObserver();
     ChannelRegistry channels = hapticObserver->getAvailableChannels(false);
     std::map<std::string, DatafieldRefPtr> tactileDatafields_MaximumValueMap;
-    if(channels.size() == 0)
+
+    if (channels.size() == 0)
     {
         ARMARX_WARNING << "No tactile pads found";
     }
     else
     {
         ARMARX_INFO << "Creating tactile channels";
-        for(std::pair<std::string, ChannelRegistryEntry> pair : channels)
+
+        for (std::pair<std::string, ChannelRegistryEntry> pair : channels)
         {
             std::string tactilePad = pair.first;
             DatafieldRefBasePtr matrixDatafield = new DatafieldRef(hapticObserver, tactilePad, "matrix");
@@ -60,6 +62,7 @@ void WeissHapticSensorTest::onEnter()
             tactileDatafields_MaximumValueMap.insert(std::make_pair(tactilePad, DatafieldRefPtr::dynamicCast(matrixMax)));
         }
     }
+
     local.setTactileDatafields_MaximumValue(tactileDatafields_MaximumValueMap);
 
 
@@ -74,7 +77,8 @@ void WeissHapticSensorTest::run()
         std::stringstream ss;
         std::stringstream ssNames;
         int max = 0;
-        for(std::pair<std::string, DatafieldRefPtr> pair : tactileDatafields_MaximumValueMap)
+
+        for (std::pair<std::string, DatafieldRefPtr> pair : tactileDatafields_MaximumValueMap)
         {
             std::string tactilePad = pair.first;
             DatafieldRefPtr matrixMax = pair.second;
@@ -83,6 +87,7 @@ void WeissHapticSensorTest::run()
             ssNames << tactilePad << "; ";
             max = std::max(max, padMax);
         }
+
         ARMARX_IMPORTANT << "tactile max value: " << max << ";  \n\n" << ss.str() << "\n" << ssNames.str();
 
         usleep(10000); // 100ms
diff --git a/source/RobotAPI/statecharts/WeissHapticGroup/WeissHapticSensorTest.generated.h b/source/RobotAPI/statecharts/WeissHapticGroup/WeissHapticSensorTest.generated.h
index a4cd708d5e6efbb5207bf86e3fe58518bb58d65e..8e2979669ade0da92d0a7f9a409e7617f3e5b4f3 100644
--- a/source/RobotAPI/statecharts/WeissHapticGroup/WeissHapticSensorTest.generated.h
+++ b/source/RobotAPI/statecharts/WeissHapticGroup/WeissHapticSensorTest.generated.h
@@ -1,9 +1,9 @@
 #ifndef _ARMARX_XMLUSERCODE_ARMARX_WEISSHAPTICGROUP_WEISSHAPTICSENSORTESTGENERATEDBASE_H
 #define _ARMARX_XMLUSERCODE_ARMARX_WEISSHAPTICGROUP_WEISSHAPTICSENSORTESTGENERATEDBASE_H
 
-#include <Core/statechart/xmlstates/XMLState.h>
+#include <ArmarXCore/statechart/xmlstates/XMLState.h>
 #include "WeissHapticGroupStatechartContext.generated.h"
-#include <Core/observers/ObserverObjectFactories.h>
+#include <ArmarXCore/observers/ObserverObjectFactories.h>
 #include <RobotAPI/interface/units/HapticUnit.h>
 #include <RobotAPI/interface/units/WeissHapticUnit.h>
 
@@ -20,32 +20,32 @@ namespace armarx
             class WeissHapticSensorTestIn
             {
             private:
-                WeissHapticSensorTestGeneratedBase<StateType> *parent;
-                
+                WeissHapticSensorTestGeneratedBase<StateType>* parent;
+
             public:
-                WeissHapticSensorTestIn(WeissHapticSensorTestGeneratedBase<StateType> *parent)
+                WeissHapticSensorTestIn(WeissHapticSensorTestGeneratedBase<StateType>* parent)
                     : parent(parent)
                 {
                 }
             }; // class WeissHapticSensorTestIn
-            
+
             class WeissHapticSensorTestLocal
             {
             private:
-                WeissHapticSensorTestGeneratedBase<StateType> *parent;
-                
+                WeissHapticSensorTestGeneratedBase<StateType>* parent;
+
             public:
-                WeissHapticSensorTestLocal(WeissHapticSensorTestGeneratedBase<StateType> *parent)
+                WeissHapticSensorTestLocal(WeissHapticSensorTestGeneratedBase<StateType>* parent)
                     : parent(parent)
                 {
                 }
-                
+
             public:
                 std::map<std::string, ::armarx::DatafieldRefPtr> getTactileDatafields_MaximumValue() const
                 {
                     return parent->State::getLocal< ::armarx::StringValueMap>("TactileDatafields_MaximumValue")->::armarx::StringValueMap::toStdMap< ::armarx::DatafieldRefPtr>();
                 }
-                void setTactileDatafields_MaximumValue(const std::map<std::string, ::armarx::DatafieldRefPtr> & value) const
+                void setTactileDatafields_MaximumValue(const std::map<std::string, ::armarx::DatafieldRefPtr>& value) const
                 {
                     ::armarx::StringValueMapPtr container = ::armarx::StringValueMap::FromStdMap< ::armarx::DatafieldRefPtr>(value);
                     parent->State::setLocal("TactileDatafields_MaximumValue", *container);
@@ -55,24 +55,24 @@ namespace armarx
                     return parent->State::isLocalParameterSet("TactileDatafields_MaximumValue");
                 }
             }; // class WeissHapticSensorTestLocal
-            
+
             class WeissHapticSensorTestOut
             {
             private:
-                WeissHapticSensorTestGeneratedBase<StateType> *parent;
-                
+                WeissHapticSensorTestGeneratedBase<StateType>* parent;
+
             public:
-                WeissHapticSensorTestOut(WeissHapticSensorTestGeneratedBase<StateType> *parent)
+                WeissHapticSensorTestOut(WeissHapticSensorTestGeneratedBase<StateType>* parent)
                     : parent(parent)
                 {
                 }
             }; // class WeissHapticSensorTestOut
-            
+
         protected:
             const WeissHapticSensorTestIn in;
             const WeissHapticSensorTestLocal local;
             const WeissHapticSensorTestOut out;
-            
+
         public:
             WeissHapticSensorTestGeneratedBase(const XMLStateConstructorParams& stateData)
                 : XMLStateTemplate < StateType > (stateData),
@@ -81,7 +81,7 @@ namespace armarx
                   out(WeissHapticSensorTestOut(this))
             {
             }
-            WeissHapticSensorTestGeneratedBase(const WeissHapticSensorTestGeneratedBase &source)
+            WeissHapticSensorTestGeneratedBase(const WeissHapticSensorTestGeneratedBase& source)
                 : IceUtil::Shared(source),
                   armarx::StateIceBase(source),
                   armarx::StateBase(source),
@@ -93,7 +93,7 @@ namespace armarx
                   out(WeissHapticSensorTestOut(this))
             {
             }
-            
+
         public:
             HapticUnitObserverInterfacePrx getHapticObserver() const
             {
diff --git a/source/RobotAPI/statecharts/WeissHapticGroup/WeissHapticSensorTest.h b/source/RobotAPI/statecharts/WeissHapticGroup/WeissHapticSensorTest.h
index 34b84f98978965e66af0c0f79a2c9322ca177df3..4e132b7e77c656ee9950fe79eec1934c1e7e3133 100644
--- a/source/RobotAPI/statecharts/WeissHapticGroup/WeissHapticSensorTest.h
+++ b/source/RobotAPI/statecharts/WeissHapticGroup/WeissHapticSensorTest.h
@@ -7,7 +7,7 @@
  *
  * ArmarX is distributed in the hope that it will be useful, but
  * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  * GNU General Public License for more details.
  *
  * You should have received a copy of the GNU General Public License
@@ -16,7 +16,7 @@
  * @package    RobotAPI::WeissHapticGroup
  * @author     Simon Ottenhaus ( simon dot ottenhaus at kit dot edu )
  * @date       2015
- * @copyright  http://www.gnu.org/licenses/gpl.txt
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
 
diff --git a/source/RobotAPI/statecharts/operations/CMakeLists.txt b/source/RobotAPI/statecharts/operations/CMakeLists.txt
index 82eaea4f7afe6ee67f637961eab4cab903f7710d..3da984c75299d62e1c519836d6f270d53e1d46ee 100644
--- a/source/RobotAPI/statecharts/operations/CMakeLists.txt
+++ b/source/RobotAPI/statecharts/operations/CMakeLists.txt
@@ -10,12 +10,12 @@ include_directories(${Eigen3_INCLUDE_DIR})
 include_directories(${Simox_INCLUDE_DIRS})
 
 set(LIB_NAME       RobotAPIOperations)
-set(LIB_VERSION    0.1.0)
-set(LIB_SOVERSION  0)
+
+
 
 set(LIBS RobotAPIUnits ArmarXCoreStatechart ArmarXCoreObservers)
 
 set(LIB_FILES RobotControl.cpp)
 set(LIB_HEADERS RobotControl.h)
 
-armarx_add_library("${LIB_NAME}" "${LIB_VERSION}" "${LIB_SOVERSION}" "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
+armarx_add_library("${LIB_NAME}"  "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
diff --git a/source/RobotAPI/statecharts/operations/RobotControl.cpp b/source/RobotAPI/statecharts/operations/RobotControl.cpp
index 40cfd172bec1eefd44013b4fcb5530c430daa36d..47c178faafd6d44ddb8c597dc59cad5fdb4085c2 100644
--- a/source/RobotAPI/statecharts/operations/RobotControl.cpp
+++ b/source/RobotAPI/statecharts/operations/RobotControl.cpp
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,7 +16,7 @@
 * @package    ArmarX::
 * @author     Mirko Waechter ( mirko.waechter at kit dot edu)
 * @date       2012
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
@@ -25,9 +24,9 @@
 
 #include <RobotAPI/components/units/KinematicUnitObserver.h>
 
-#include <Core/observers/variant/ChannelRef.h>
-#include <Core/statechart/DynamicRemoteState.h>
-#include <Core/core/exceptions/local/ExpressionException.h>
+#include <ArmarXCore/observers/variant/ChannelRef.h>
+#include <ArmarXCore/statechart/DynamicRemoteState.h>
+#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 
 namespace armarx
 {
@@ -59,7 +58,7 @@ namespace armarx
     }
 
 
-    void RobotControl::hardReset(const Ice::Current &)
+    void RobotControl::hardReset(const Ice::Current&)
     {
         removeInstance(robotFunctionalState->getLocalUniqueId());
         startRobotStatechart();
@@ -74,7 +73,7 @@ namespace armarx
     {
         getObjectScheduler()->waitForObjectState(eManagedIceObjectStarted, 5000);
         stateId = createRemoteStateInstance("RobotControl", NULL, "RobotStatechart", "");
-        std::map<int, StateBasePtr> stateList = getChildStatesByName(stateId,"Functional");
+        std::map<int, StateBasePtr> stateList = getChildStatesByName(stateId, "Functional");
         ARMARX_INFO << "Functional State Id:" << stateList.begin()->first << flush;
         assert(stateList.size() > 0);
         int robotFunctionalStateId = stateList.begin()->first;
@@ -84,17 +83,19 @@ namespace armarx
         const std::string proxyName = getProperty<std::string>("proxyName").getValue();
         const std::string stateName = getProperty<std::string>("stateName").getValue();
         ARMARX_IMPORTANT << VAROUT(proxyName) << VAROUT(stateName);
-        if(!proxyName.empty() && !stateName.empty())
+
+        if (!proxyName.empty() && !stateName.empty())
         {
             auto statebase = robotFunctionalState->findSubstateByName("DynamicRemoteState");
             ARMARX_CHECK_EXPRESSION(statebase);
             DynamicRemoteStatePtr state = DynamicRemoteStatePtr::dynamicCast(statebase);
 
-            if(!state)
+            if (!state)
             {
                 ARMARX_ERROR << "dynamic state pointer null";
                 return;
             }
+
             state->getObjectScheduler()->waitForObjectState(eManagedIceObjectStarted, 5000);
             EventPtr evt = createEvent<EvLoadScenario>();
             evt->eventReceiverName = "toAll";
@@ -140,7 +141,7 @@ namespace armarx
         addTransition<EvInit>(stateIdling, stateRobotPreInitialized);
         addTransition<EvInitialized>(stateRobotPreInitialized, stateRobotInitialized);
         addTransition<EvLoadScenario>(stateRobotInitialized, stateScenarioRunning,
-                                      PM::createMapping()->mapFromEvent("*","*"));
+                                      PM::createMapping()->mapFromEvent("*", "*"));
         addTransition<EvInit>(stateScenarioRunning, stateRobotPreInitialized);
         addTransition<Success>(stateScenarioRunning, stateRobotInitialized);
 
@@ -154,9 +155,9 @@ namespace armarx
     void StateRobotControl::onEnter()
     {
         // install global running conditions for the robot (e.g. temperature < xx°C)
-//        KinematicUnitObserverInterfacePrx prx = getContext()->getProxy<KinematicUnitObserverInterfacePrx>("KinematicUnitObserver");
-//        installCondition<Failure>(Expression::create()
-//                         ->add(channels::KinematicUnitObserver::jointTemperatures.getDatafield("KinematicUnitObserver", "NECK_JOINT0"), checks::KinematicUnitObserver::larger->getCheckStr(),  50.f));
+        //        KinematicUnitObserverInterfacePrx prx = getContext()->getProxy<KinematicUnitObserverInterfacePrx>("KinematicUnitObserver");
+        //        installCondition<Failure>(Expression::create()
+        //                         ->add(channels::KinematicUnitObserver::jointTemperatures.getDatafield("KinematicUnitObserver", "NECK_JOINT0"), checks::KinematicUnitObserver::larger->getCheckStr(),  50.f));
     }
 
 
diff --git a/source/RobotAPI/statecharts/operations/RobotControl.h b/source/RobotAPI/statecharts/operations/RobotControl.h
index 93e0354e491405bcbacab83329996992153d1e46..c0d2cb409b03da05d24c8ea87e18ee8d7ee16949 100644
--- a/source/RobotAPI/statecharts/operations/RobotControl.h
+++ b/source/RobotAPI/statecharts/operations/RobotControl.h
@@ -2,14 +2,13 @@
 * This file is part of ArmarX.
 *
 * ArmarX is free software; you can redistribute it and/or modify
-* it under the terms of the GNU Lesser General Public License as
-* published by the Free Software Foundation; either version 2 of
-* the License, or (at your option) any later version.
+* it under the terms of the GNU General Public License version 2 as
+* published by the Free Software Foundation.
 *
 * ArmarX is distributed in the hope that it will be useful, but
 * WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-* GNU Lesser General Public License for more details.
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program. If not, see <http://www.gnu.org/licenses/>.
@@ -17,16 +16,16 @@
 * @package    Robot::
 * @author     Mirko Waechter( mirko.waechter at kit dot edu)
 * @date       2012
-* @copyright  http://www.gnu.org/licenses/gpl.txt
+* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */
 
 #ifndef _ARMARX_COMPONENT_ROBOTCONTROL_H
 #define _ARMARX_COMPONENT_ROBOTCONTROL_H
 
-#include <Core/statechart/Statechart.h>
-#include <Core/core/system/ImportExportComponent.h>
-#include <Core/interface/operations/RobotControlIceBase.h>
+#include <ArmarXCore/statechart/Statechart.h>
+#include <ArmarXCore/core/system/ImportExportComponent.h>
+#include <ArmarXCore/interface/operations/RobotControlIceBase.h>
 
 namespace armarx
 {
@@ -76,7 +75,7 @@ namespace armarx
         void onExitRemoteStateOfferer();
         void startRobotStatechart();
 
-        void hardReset(const Ice::Current & = ::Ice::Current());
+        void hardReset(const Ice::Current& = ::Ice::Current());
 
         virtual PropertyDefinitionsPtr createPropertyDefinitions();
 
@@ -106,7 +105,7 @@ namespace armarx
        \enddot
      */
     struct Statechart_Robot :
-        StateTemplate<Statechart_Robot>
+            StateTemplate<Statechart_Robot>
     {
         void defineState();
         void defineSubstates();
@@ -143,7 +142,7 @@ namespace armarx
        \enddot
      */
     struct StateRobotControl :
-        StateTemplate<StateRobotControl>
+            StateTemplate<StateRobotControl>
     {
         void onEnter();
         void defineSubstates();
@@ -153,7 +152,7 @@ namespace armarx
      * Robot is in the state preinitialized.
      */
     struct RobotPreInitialized :
-        StateTemplate<RobotPreInitialized>
+            StateTemplate<RobotPreInitialized>
     {
         RobotPreInitialized();
         void onEnter();